diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/slider_control_gazebo.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/slider_control_gazebo.launch new file mode 100644 index 00000000..066bea13 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/slider_control_gazebo.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py b/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py index 64e1b997..61117ec8 100755 --- a/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py +++ b/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py @@ -14,8 +14,7 @@ import rospy from sensor_msgs.msg import JointState from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint -from pymycobot.mycobot import MyCobot -import copy +# from pymycobot.mycobot import MyCobot mc, pub_command = None, None @@ -37,7 +36,7 @@ def callback(data): joint_trajectory.points.append(point) pub_command.publish(joint_trajectory) # Publish the joint trajectory - mc.send_angles(data_list, 25) + # mc.send_angles(data_list, 25) # rospy.loginfo(rospy.get_caller_id() + "%s", data_list) def listener(): @@ -45,17 +44,17 @@ def listener(): rospy.init_node("control_slider", anonymous=True) - port = rospy.get_param("~port", "/dev/ttyUSB0") - baud = rospy.get_param("~baud", 115200) - print(port, baud) - mc = MyCobot(port, baud) + # port = rospy.get_param("~port", "/dev/ttyUSB0") + # baud = rospy.get_param("~baud", 115200) + # print(port, baud) + # mc = MyCobot(port, baud) pub_command = rospy.Publisher("/mycobot_position_controller/command", JointTrajectory, queue_size=10) rospy.Subscriber("/joint_states", JointState, callback) - time.sleep(0.05) - mc.set_fresh_mode(1) - time.sleep(0.05) + # time.sleep(0.05) + # mc.set_fresh_mode(1) + # time.sleep(0.05) # spin() simply keeps python from exiting until this node is stopped # spin()只是阻止python退出,直到该节点停止 diff --git a/mycobot_description/urdf/mycobot_630/base.dae b/mycobot_description/urdf/mycobot_pro_630/base.dae similarity index 100% rename from mycobot_description/urdf/mycobot_630/base.dae rename to mycobot_description/urdf/mycobot_pro_630/base.dae diff --git a/mycobot_description/urdf/mycobot_630/link1.dae b/mycobot_description/urdf/mycobot_pro_630/link1.dae similarity index 100% rename from mycobot_description/urdf/mycobot_630/link1.dae rename to mycobot_description/urdf/mycobot_pro_630/link1.dae diff --git a/mycobot_description/urdf/mycobot_630/link2.dae b/mycobot_description/urdf/mycobot_pro_630/link2.dae similarity index 100% rename from mycobot_description/urdf/mycobot_630/link2.dae rename to mycobot_description/urdf/mycobot_pro_630/link2.dae diff --git a/mycobot_description/urdf/mycobot_630/link3.dae b/mycobot_description/urdf/mycobot_pro_630/link3.dae similarity index 100% rename from mycobot_description/urdf/mycobot_630/link3.dae rename to mycobot_description/urdf/mycobot_pro_630/link3.dae diff --git a/mycobot_description/urdf/mycobot_630/link4.dae b/mycobot_description/urdf/mycobot_pro_630/link4.dae similarity index 100% rename from mycobot_description/urdf/mycobot_630/link4.dae rename to mycobot_description/urdf/mycobot_pro_630/link4.dae diff --git a/mycobot_description/urdf/mycobot_630/link5.dae b/mycobot_description/urdf/mycobot_pro_630/link5.dae similarity index 100% rename from mycobot_description/urdf/mycobot_630/link5.dae rename to mycobot_description/urdf/mycobot_pro_630/link5.dae diff --git a/mycobot_description/urdf/mycobot_630/link6.dae b/mycobot_description/urdf/mycobot_pro_630/link6.dae similarity index 100% rename from mycobot_description/urdf/mycobot_630/link6.dae rename to mycobot_description/urdf/mycobot_pro_630/link6.dae diff --git a/mycobot_description/urdf/mycobot_pro_630/mycobot_630.urdf b/mycobot_description/urdf/mycobot_pro_630/mycobot_630.urdf new file mode 100755 index 00000000..464a9422 --- /dev/null +++ b/mycobot_description/urdf/mycobot_pro_630/mycobot_630.urdf @@ -0,0 +1,155 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_description/urdf/mycobot_630/mycobot_630_gazebo.urdf b/mycobot_description/urdf/mycobot_pro_630/mycobot_630_gazebo.urdf similarity index 100% rename from mycobot_description/urdf/mycobot_630/mycobot_630_gazebo.urdf rename to mycobot_description/urdf/mycobot_pro_630/mycobot_630_gazebo.urdf diff --git a/mycobot_pro/mycobot_630/launch/mycobot_630_slider.launch b/mycobot_pro/mycobot_630/launch/mycobot_630_slider.launch index edf5a4fc..5b537013 100644 --- a/mycobot_pro/mycobot_630/launch/mycobot_630_slider.launch +++ b/mycobot_pro/mycobot_630/launch/mycobot_630_slider.launch @@ -1,6 +1,6 @@ - +