Skip to content

Commit 7e8e360

Browse files
committed
更新630 URDF模型初始姿态
1 parent 672dd9c commit 7e8e360

File tree

4 files changed

+12
-7
lines changed

4 files changed

+12
-7
lines changed

demo_img/pro630/pro630.png

-3.05 KB
Loading

mycobot_description/urdf/mycobot_pro_630/mycobot_pro_630.urdf

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -131,10 +131,11 @@
131131

132132
<joint name="joint2_to_joint1" type="revolute">
133133
<axis xyz="0 0 -1"/>
134-
<limit effort = "1000.0" lower = "-4.71" upper = "1.5707" velocity = "0"/>
134+
<!-- <limit effort = "1000.0" lower = "-4.71" upper = "1.5707" velocity = "0"/> -->
135+
<limit effort = "1000.0" lower = "-3.14159" upper = "3.14159" velocity = "0"/>
135136
<parent link="link1"/>
136137
<child link="link2"/>
137-
<origin xyz= "0 0 0" rpy = "1.5707 0 0"/>
138+
<origin xyz= "0 0 0" rpy = "1.5707 -1.5708 0"/>
138139
</joint>
139140

140141

@@ -148,10 +149,11 @@
148149

149150
<joint name="joint4_to_joint3" type="revolute">
150151
<axis xyz=" 0 0 -1"/>
151-
<limit effort = "1000.0" lower = "-4.53" upper = "1.3962" velocity = "0"/>
152+
<!-- <limit effort = "1000.0" lower = "-4.53" upper = "1.3962" velocity = "0"/> -->
153+
<limit effort = "1000.0" lower = "-2.9670" upper = "2.9670" velocity = "0"/>
152154
<parent link="link3"/>
153155
<child link="link4"/>
154-
<origin xyz= "0.267 0 -0.0745" rpy = "0 0 0"/>
156+
<origin xyz= "0.267 0 -0.0745" rpy = "0 0 1.5708"/>
155157
</joint>
156158

157159
<joint name="joint5_to_joint4" type="revolute">

mycobot_pro/mycobot_630/config/mycobot_630.rviz

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -180,7 +180,7 @@ Visualization Manager:
180180
Views:
181181
Current:
182182
Class: rviz/Orbit
183-
Distance: 1.5878180265426636
183+
Distance: 2.1886165142059326
184184
Enable Stereo Rendering:
185185
Stereo Eye Separation: 0.05999999865889549
186186
Stereo Focal Distance: 1
@@ -196,9 +196,9 @@ Visualization Manager:
196196
Invert Z Axis: false
197197
Name: Current View
198198
Near Clip Distance: 0.009999999776482582
199-
Pitch: 0.5947973132133484
199+
Pitch: 0.8997963666915894
200200
Target Frame: <Fixed Frame>
201-
Yaw: 2.5353903770446777
201+
Yaw: 3.4653899669647217
202202
Saved: ~
203203
Window Geometry:
204204
Displays:

mycobot_pro/mycobot_630/scripts/mycobot_630_slider.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,9 @@ def callback(data):
2121
for index, value in enumerate(data.position):
2222
radians_to_angles = round(math.degrees(value), 2)
2323
data_list.append(radians_to_angles)
24+
25+
data_list[1] = data_list[1] - 90
26+
data_list[3] = data_list[3] - 90
2427

2528
rospy.loginfo(rospy.get_caller_id() + "%s", data_list)
2629
mc.write_angles(data_list, 800)

0 commit comments

Comments
 (0)