Skip to content

Commit

Permalink
add ros1 myarm c650 package
Browse files Browse the repository at this point in the history
  • Loading branch information
Tenero-Jz committed Apr 26, 2024
1 parent 6dfc757 commit 57a8e46
Show file tree
Hide file tree
Showing 3 changed files with 49 additions and 56 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ Panels:
- /TF1
- /TF1/Frames1
Splitter Ratio: 0.5
Tree Height: 603
Tree Height: 523
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expand Down Expand Up @@ -69,6 +69,11 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
endeffector:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
joint1:
Alpha: 1
Show Axes: false
Expand All @@ -94,16 +99,6 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
joint6:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
joint7:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Expand All @@ -125,25 +120,23 @@ Visualization Manager:
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: true
All Enabled: false
base:
Value: true
endeffector:
Value: false
joint1:
Value: true
Value: false
joint2:
Value: true
Value: false
joint3:
Value: true
Value: false
joint4:
Value: true
Value: false
joint5:
Value: true
joint6:
Value: true
joint7:
Value: true
Value: false
Marker Alpha: 1
Marker Scale: 0.20000000298023224
Marker Scale: 0.5
Name: TF
Show Arrows: true
Show Axes: true
Expand All @@ -155,9 +148,8 @@ Visualization Manager:
joint3:
joint4:
joint5:
joint6:
joint7:
{}
endeffector:
{}
Update Interval: 0
Value: true
Enabled: true
Expand Down Expand Up @@ -188,7 +180,7 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 1.2526283264160156
Distance: 1.7395164966583252
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Expand All @@ -204,17 +196,17 @@ Visualization Manager:
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.2103991061449051
Pitch: 0.5348014831542969
Target Frame: <Fixed Frame>
Yaw: 2.6453990936279297
Yaw: 1.529981255531311
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 900
Height: 820
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002e6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002e6000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002e6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002e6000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000004c7000002e600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd00000004000000000000015600000296fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000296000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000296fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000296000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000061b0000003efc0100000002fb0000000800540069006d006501000000000000061b000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000003aa0000029600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
Expand All @@ -223,6 +215,6 @@ Window Geometry:
collapsed: false
Views:
collapsed: false
Width: 1848
Width: 1563
X: 72
Y: 27
1 change: 1 addition & 0 deletions myArm/myarm_c650/scripts/slider_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
from sensor_msgs.msg import JointState

from pymycobot.myarm import MyArm
from pymycobot.myarmc import MyArmC


mc = None
Expand Down
50 changes: 25 additions & 25 deletions mycobot_description/urdf/myarm_c650/myarm_c650.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,13 @@
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/joint1.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.085 " rpy = " 0 0 0"/>
<origin xyz = "0.0 0 -0.092 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/joint1.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.085 " rpy = " 0 0 0"/>
<origin xyz = "0.0 0 -0.092 " rpy = " 0 0 0"/>
</collision>
</link>

Expand All @@ -39,13 +39,13 @@
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/joint2.dae"/>
</geometry>
<origin xyz = "0.0 0 0.0 " rpy = " 3.14159 0 -1.5708 "/>
<origin xyz = "0.0 0.006 0.0 " rpy = " 3.14159 0 -1.5708 "/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/joint2.dae"/>
</geometry>
<origin xyz = "0.0 0 0.0 " rpy = " 3.14159 0 -1.5708"/>
<origin xyz = "0.0 0.006 0.0 " rpy = " 3.14159 0 -1.5708"/>
</collision>
</link>

Expand All @@ -55,13 +55,13 @@

<mesh filename="package://mycobot_description/urdf/myarm_c650/joint3.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.054 " rpy = " 0 0 0"/>
<origin xyz = "0.0 -0.001 0.004 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/joint3.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.054" rpy = " 0 0 0"/>
<origin xyz = "0.0 -0.001 0.004" rpy = " 0 0 0"/>
</collision>
</link>

Expand All @@ -71,13 +71,13 @@
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/joint4.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 -1.5708"/>
<origin xyz = "0.0 0 0 " rpy = " 0 0 3.14159"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/joint4.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 -1.5708"/>
<origin xyz = "0.0 0 0 " rpy = " 0 0 3.14159"/>
</collision>
</link>

Expand All @@ -88,47 +88,47 @@

<mesh filename="package://mycobot_description/urdf/myarm_c650/joint5.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.051 " rpy = " 0 0 3.14159"/>
<origin xyz = "0 0 0 " rpy = " 0 0 1.5708"/>
</visual>
<collision>
<geometry>

<mesh filename="package://mycobot_description/urdf/myarm_c650/joint5.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.051 " rpy = " 0 0 3.14159"/>
<origin xyz = "0 0 0 " rpy = " 0 0 1.5708"/>
</collision>
</link>


<link name="joint6">
<link name="endeffector">
<visual>
<geometry>

<mesh filename="package://mycobot_description/urdf/myarm_c650/endeffector.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.0 " rpy = " 0 0 -1.5708"/>
<origin xyz = "0 0 -0.003 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>

<mesh filename="package://mycobot_description/urdf/myarm_c650/endeffector.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.0 " rpy = " 0 0 -1.5708"/>
<origin xyz = "0 0 -0.003 " rpy = " 0 0 0"/>
</collision>
</link>

<!-- <link name="joint7">
<!-- <link name="endeffector">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/j7.dae"/>
<mesh filename="package://mycobot_description/urdf/myarm_c650/endeffector.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.009 " rpy = " 0 0 -1.5708"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/myarm_c650/j7.dae"/>
<mesh filename="package://mycobot_description/urdf/myarm_c650/endeffector.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.009 " rpy = " 0 0 -1.5708"/>
</collision>
Expand Down Expand Up @@ -160,7 +160,7 @@
<limit effort = "1000.0" lower = "-2.8797" upper = "2.8797" velocity = "0"/>
<parent link="joint2"/>
<child link="joint3"/>
<origin xyz= "0 -0.11 0 " rpy = "1.5708 0 0"/>
<origin xyz= "0.0565 -0.296 0 " rpy = "0 0 0"/>
</joint>


Expand All @@ -170,7 +170,7 @@
<limit effort = "1000.0" lower = "-1.7453" upper = "1.3962" velocity = "0"/>
<parent link="joint3"/>
<child link="joint4"/>
<origin xyz= "0.0 0 0.0" rpy = "-1.5708 0 3.14159"/>
<origin xyz= "0.081 0 0.0" rpy = "0 1.5708 0"/>
</joint>


Expand All @@ -179,23 +179,23 @@
<limit effort = "1000.0" lower = "-2.8797" upper = "2.8797" velocity = "0"/>
<parent link="joint4"/>
<child link="joint5"/>
<origin xyz= "0 -0.126 0" rpy = "1.5708 0 0"/>
<origin xyz= "0.0 0.0003 0.2517" rpy = "1.5708 0 1.5708"/>
</joint>


<joint name="joint6_to_joint5" type="revolute">
<joint name="endeffector_to_joint5" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-1.9198" upper = "1.9198" velocity = "0"/>
<parent link="joint5"/>
<child link="joint6"/>
<origin xyz= "0 0.0 0" rpy = "-1.5708 0 0"/>
<child link="endeffector"/>
<origin xyz= "0 0.055 0" rpy = "-1.5708 0 0"/>
</joint>

<!-- <joint name="joint7_to_joint6" type="revolute">
<!-- <joint name="endeffector_to_endeffector" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-2.8797" upper = "2.8797" velocity = "0"/>
<parent link="joint6"/>
<child link="joint7"/>
<parent link="endeffector"/>
<child link="endeffector"/>
<origin xyz= "0 -0.056 0" rpy = "1.5708 0 0"/>
</joint> -->

Expand Down

0 comments on commit 57a8e46

Please sign in to comment.