Skip to content

Commit

Permalink
20240726
Browse files Browse the repository at this point in the history
  • Loading branch information
Johnkey00 committed Jul 26, 2024
1 parent 6e5f3ad commit 9f27a3f
Show file tree
Hide file tree
Showing 12 changed files with 191 additions and 11 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<?xml version="1.0"?>
<launch>
<arg name="paused" default="false"/>
<arg name="gazebo_gui" default="true"/>
<arg name="use_gui" default="true"/>
<arg name="urdf_path" default="$(find mycobot_description)/urdf/mycobot/mycobot_280_m5_gazebo.urdf"/>

<!-- startup simulated world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" default="worlds/empty.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="gui" value="$(arg gazebo_gui)"/>
</include>

<!-- send robot urdf to param server -->
<param name="robot_description" textfile="$(arg urdf_path)" />

<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" if="$(arg use_gui)" />

<!-- push robot_description to factory and spawn robot in gazebo at the origin, change x,y,z arguments to spawn in a different position -->
<node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot -x 0 -y 0 -z 0"
respawn="false" output="screen" />

<include file="$(find mycobot_280_gazebo_moveit)/launch/ros_controllers.launch"/>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand All @@ -37,25 +36,25 @@ 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():
global mc, pub_command

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退出,直到该节点停止
Expand Down
155 changes: 155 additions & 0 deletions mycobot_description/urdf/mycobot_pro_630/mycobot_630.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter">
<xacro:property name="width" value=".2" />
<link name="base">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/base.dae" />
</geometry>
<origin xyz="0 0 0 " rpy=" 1.5706 0 0" />
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/base.dae" />
</geometry>
<origin xyz="0 0 0 " rpy=" 1.5706 0 0" />
</collision>

</link>
<link name="joint1">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link1.dae" />
</geometry>
<origin xyz="0 0 -0.06 " rpy="0 0 3.1415926" />
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link1.dae" />
</geometry>
<origin xyz="0 0 -0.06 " rpy=" 0 0 3.1415926" />
</collision>

</link>
<link name="joint2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link2.dae" />
</geometry>
<origin xyz="0 0 -0.0446 " rpy=" 1.5707 -1.5707 -1.5707" />
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link2.dae" />
</geometry>
<origin xyz="0 0 -0.0446 " rpy=" 1.5707 -1.5707 -1.5707" />
</collision>

</link>
<link name="joint3">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link3.dae" />
</geometry>
<origin xyz="0 0 -0.0444 " rpy=" 0 1.5707 0" />
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link3.dae" />
</geometry>
<origin xyz="0 0 -0.0444 " rpy="0 1.5707 0" />
</collision>

</link>
<link name="joint4">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link4.dae" />
</geometry>
<origin xyz="0 -0.002 0.041 " rpy=" -1.5707 0 -1.5707" />
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link4.dae" />
</geometry>
<origin xyz="0 -0.002 0.041 " rpy=" -1.5707 0 -1.5707" />
</collision>

</link>
<link name="joint5">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link5.dae" />
</geometry>
<origin xyz="-0.043 0 -0.08 " rpy=" 3.14159 1.5707 3.14159" />
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link5.dae" />
</geometry>
<origin xyz="-0.043 0 -0.08 " rpy=" 3.14159 1.5707 3.14159" />
</collision>

</link>
<link name="joint6">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link6.dae" />
</geometry>
<origin xyz="0.01 0 0" rpy=" 0 1.5707 0" />
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link6.dae" />
</geometry>
<origin xyz="0.01 0 0" rpy=" 0 1.5707 0" />
</collision>

</link>
<joint name="joint1_to_base" type="revolute">
<axis xyz="0 0 1" />
<limit effort="1000.0" lower="-3.14" upper="3.14159" velocity="0" />
<parent link="base" />
<child link="joint1" />
<origin xyz="0 0 0.22934" rpy="0 0 0" />
</joint>

<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 -1" />
<limit effort="1000.0" lower="-2.26" upper="2.26" velocity="0" />
<parent link="joint1" />
<child link="joint2" />
<origin xyz="0 0 0" rpy="1.5707 -1.5706 0" />
</joint>
<joint name="joint3_to_joint2" type="revolute">
<axis xyz=" 0 0 -1" />
<limit effort="1000.0" lower="-2.61" upper="2.618" velocity="0" />
<parent link="joint2" />
<child link="joint3" />
<origin xyz="0 0.27 0 " rpy="0 0 0" />
</joint>
<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 -1" />
<limit effort="1000.0" lower="-3.17" upper="3.17" velocity="0" />
<parent link="joint3" />
<child link="joint4" />
<origin xyz="0 0.267 -0.0745" rpy="0 0 1.5706" />
</joint>
<joint name="joint5_to_joint4" type="revolute">
<axis xyz="0 0 1" />
<limit effort="1000.0" lower="-2.99" upper="2.99" velocity="0" />
<parent link="joint4" />
<child link="joint5" />
<origin xyz="0 0 0.002" rpy="1.5707 -1.5707 0" />
</joint>
<joint name="joint6_to_joint5" type="revolute">
<axis xyz="-1 0 0" />
<limit effort="1000.0" lower="-3.03" upper="3.0368" velocity="0" />
<parent link="joint5" />
<child link="joint6" />
<origin xyz="-0.054 0 -0.08" rpy="-1.5707 0 0 " />
</joint>


</robot>

2 changes: 1 addition & 1 deletion mycobot_pro/mycobot_630/launch/mycobot_630_slider.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<launch>
<!-- Load URDF, rviz, etc. on the parameter server,加载参数服务器上的URDF、rviz等 -->
<arg name="model" default="$(find mycobot_description)/urdf/mycobot_630/mycobot_630.urdf"/>
<arg name="model" default="$(find mycobot_description)/urdf/mycobot_pro_630/mycobot_630.urdf"/>
<arg name="rvizconfig" default="$(find mycobot_630)/config/mycobot_630.rviz" />
<arg name="gui" default="true" />

Expand Down

0 comments on commit 9f27a3f

Please sign in to comment.