Skip to content

Commit

Permalink
更新630 URDF模型初始姿态
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Jan 7, 2025
1 parent 672dd9c commit 7e8e360
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 7 deletions.
Binary file modified demo_img/pro630/pro630.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
10 changes: 6 additions & 4 deletions mycobot_description/urdf/mycobot_pro_630/mycobot_pro_630.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -131,10 +131,11 @@

<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 -1"/>
<limit effort = "1000.0" lower = "-4.71" upper = "1.5707" velocity = "0"/>
<!-- <limit effort = "1000.0" lower = "-4.71" upper = "1.5707" velocity = "0"/> -->
<limit effort = "1000.0" lower = "-3.14159" upper = "3.14159" velocity = "0"/>
<parent link="link1"/>
<child link="link2"/>
<origin xyz= "0 0 0" rpy = "1.5707 0 0"/>
<origin xyz= "0 0 0" rpy = "1.5707 -1.5708 0"/>
</joint>


Expand All @@ -148,10 +149,11 @@

<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 -1"/>
<limit effort = "1000.0" lower = "-4.53" upper = "1.3962" velocity = "0"/>
<!-- <limit effort = "1000.0" lower = "-4.53" upper = "1.3962" velocity = "0"/> -->
<limit effort = "1000.0" lower = "-2.9670" upper = "2.9670" velocity = "0"/>
<parent link="link3"/>
<child link="link4"/>
<origin xyz= "0.267 0 -0.0745" rpy = "0 0 0"/>
<origin xyz= "0.267 0 -0.0745" rpy = "0 0 1.5708"/>
</joint>

<joint name="joint5_to_joint4" type="revolute">
Expand Down
6 changes: 3 additions & 3 deletions mycobot_pro/mycobot_630/config/mycobot_630.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 1.5878180265426636
Distance: 2.1886165142059326
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Expand All @@ -196,9 +196,9 @@ Visualization Manager:
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.5947973132133484
Pitch: 0.8997963666915894
Target Frame: <Fixed Frame>
Yaw: 2.5353903770446777
Yaw: 3.4653899669647217
Saved: ~
Window Geometry:
Displays:
Expand Down
3 changes: 3 additions & 0 deletions mycobot_pro/mycobot_630/scripts/mycobot_630_slider.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@ def callback(data):
for index, value in enumerate(data.position):
radians_to_angles = round(math.degrees(value), 2)
data_list.append(radians_to_angles)

data_list[1] = data_list[1] - 90
data_list[3] = data_list[3] - 90

rospy.loginfo(rospy.get_caller_id() + "%s", data_list)
mc.write_angles(data_list, 800)
Expand Down

0 comments on commit 7e8e360

Please sign in to comment.