diff --git a/demo_img/pro630/pro630.png b/demo_img/pro630/pro630.png index 8407f68e..615b1305 100644 Binary files a/demo_img/pro630/pro630.png and b/demo_img/pro630/pro630.png differ diff --git a/mycobot_description/urdf/mycobot_pro_630/mycobot_pro_630.urdf b/mycobot_description/urdf/mycobot_pro_630/mycobot_pro_630.urdf index 783b8ac6..2578a4b9 100755 --- a/mycobot_description/urdf/mycobot_pro_630/mycobot_pro_630.urdf +++ b/mycobot_description/urdf/mycobot_pro_630/mycobot_pro_630.urdf @@ -131,10 +131,11 @@ - + + - + @@ -148,10 +149,11 @@ - + + - + diff --git a/mycobot_pro/mycobot_630/config/mycobot_630.rviz b/mycobot_pro/mycobot_630/config/mycobot_630.rviz index 47752800..7769c6e6 100644 --- a/mycobot_pro/mycobot_630/config/mycobot_630.rviz +++ b/mycobot_pro/mycobot_630/config/mycobot_630.rviz @@ -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 @@ -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: - Yaw: 2.5353903770446777 + Yaw: 3.4653899669647217 Saved: ~ Window Geometry: Displays: diff --git a/mycobot_pro/mycobot_630/scripts/mycobot_630_slider.py b/mycobot_pro/mycobot_630/scripts/mycobot_630_slider.py index 62ed79bb..8d32163b 100755 --- a/mycobot_pro/mycobot_630/scripts/mycobot_630_slider.py +++ b/mycobot_pro/mycobot_630/scripts/mycobot_630_slider.py @@ -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)