Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Cobotx b450 #126

Merged
merged 7 commits into from
Nov 15, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(cobotx_a450)
project(mercury_a1)
add_compile_options(-std=c++11)

## Find catkin and any catkin packages
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>
<!-- Load URDF file,加载URDF文件 -->
<arg name="model" default="$(find mycobot_description)/urdf/cobotx_a450/cobotx_a450.urdf"/>
<arg name="rvizconfig" default="$(find cobotx_a450)/config/cobotx_a450.rviz" />
<arg name="model" default="$(find mycobot_description)/urdf/mercury_a1/mercury_a1.urdf"/>
<arg name="rvizconfig" default="$(find mercury_a1)/config/mercury_a1.rviz" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />
<!-- Combinejoin values to TF ,将值合并到TF-->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
<arg name="port" default="/dev/ttyAMA1" />
<arg name="baud" default="115200" />

<arg name="model" default="$(find mycobot_description)/urdf/cobotx_a450/cobotx_a450.urdf"/>
<arg name="rvizconfig" default="$(find cobotx_a450)/config/cobotx_a450.rviz" />
<arg name="model" default="$(find mycobot_description)/urdf/mercury_a1/mercury_a1.urdf"/>
<arg name="rvizconfig" default="$(find mercury_a1)/config/mercury_a1.rviz" />
<arg name="gui" default="false" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />
Expand All @@ -14,10 +14,10 @@
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />

<include file="$(find cobotx_a450_communication)/launch/communication_service.launch">
<include file="$(find mercury_a1_communication)/launch/communication_service.launch">
<arg name="port" value="$(arg port)" />
<arg name="baud" value="$(arg baud)" />
</include>
<node name="real_listener" pkg="cobotx_a450" type="listen_real.py" />
<node name="simple_gui" pkg="cobotx_a450" type="simple_gui.py" />
<node name="real_listener" pkg="mercury_a1" type="listen_real.py" />
<node name="simple_gui" pkg="mercury_a1" type="simple_gui.py" />
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
<!-- <arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" /> -->
<!-- Load file model ,加载文件模型-->
<arg name="model" default="$(find mycobot_description)/urdf/cobotx_a450/cobotx_a450.urdf"/>
<arg name="rvizconfig" default="$(find cobotx_a450)/config/cobotx_a450.rviz" />
<arg name="model" default="$(find mycobot_description)/urdf/mercury_a1/mercury_a1.urdf"/>
<arg name="rvizconfig" default="$(find mercury_a1)/config/mercury_a1.rviz" />
<arg name="gui" default="true" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
<arg name="port" default="/dev/ttyAMA1" />
<arg name="baud" default="115200" />

<arg name="model" default="$(find mycobot_description)/urdf/cobotx_a450/cobotx_a450.urdf"/>
<arg name="rvizconfig" default="$(find cobotx_a450)/config/cobotx_a450.rviz" />
<arg name="model" default="$(find mycobot_description)/urdf/mercury_a1/mercury_a1.urdf"/>
<arg name="rvizconfig" default="$(find mercury_a1)/config/mercury_a1.rviz" />
<arg name="gui" default="false" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />
Expand All @@ -14,10 +14,10 @@
<!-- Show in Rviz ,显示在Rviz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />

<include file="$(find cobotx_a450_communication)/launch/communication_service.launch">
<include file="$(find mercury_a1_communication)/launch/communication_service.launch">
<arg name="port" value="$(arg port)" />
<arg name="baud" value="$(arg baud)" />
</include>
<!-- listen and pub the real angles ,监听并发布真实角度-->
<node name="real_listener" pkg="cobotx_a450" type="listen_real.py" />
<node name="real_listener" pkg="mercury_a1" type="listen_real.py" />
</launch>
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<launch>
<arg name="model" default="$(find mycobot_description)/urdf/cobotx_a450/cobotx_a450.urdf"/>
<arg name="rvizconfig" default="$(find cobotx_a450)/config/cobotx_a450.rviz" />
<arg name="model" default="$(find mycobot_description)/urdf/mercury_a1/mercury_a1.urdf"/>
<arg name="rvizconfig" default="$(find mercury_a1)/config/mercury_a1.rviz" />
<arg name="gui" default="true" />

<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<package format="2">
<name>cobotx_a450</name>
<name>mercury_a1</name>
<version>0.3.0</version>
<description>The cobotx_a450 package</description>
<description>The mercury_a1 package</description>

<author email="[email protected]">Wangweijian</author>
<maintainer email="[email protected]">Wangweijian</maintainer>
Expand All @@ -18,9 +18,9 @@
<build_depend>std_msgs</build_depend>
<build_depend>actionlib</build_depend>
<build_depend>mycobot_description</build_depend>
<build_depend>cobotx_a450_communication</build_depend>
<build_depend>mercury_a1_communication</build_depend>

<build_export_depend>cobotx_a450_communication</build_export_depend>
<build_export_depend>mercury_a1_communication</build_export_depend>
<build_export_depend>mycobot_description</build_export_depend>

<exec_depend>roscpp</exec_depend>
Expand All @@ -36,7 +36,7 @@
<exec_depend>controller_manager</exec_depend>
<exec_depend>python-tk</exec_depend>
<exec_depend>mycobot_description</exec_depend>
<exec_depend>cobotx_a450_communication</exec_depend>
<exec_depend>mercury_a1_communication</exec_depend>


<!-- The export tag contains other, unspecified, tags -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,24 +6,24 @@
from std_msgs.msg import Header
from visualization_msgs.msg import Marker

from pymycobot.cobotx import CobotX
from pymycobot.mercury import Mercury


def talker():
rospy.init_node("display", anonymous=True)

print("Try connect real CobotX...")
print("Try connect real Mercury...")
port = rospy.get_param("~port", "/dev/ttyAMA1")
baud = rospy.get_param("~baud", 115200)
print("port: {}, baud: {}\n".format(port, baud))
try:
mc = CobotX(port, baud)
mc = Mercury(port, baud)
except Exception as e:
print(e)
print(
"""\
\rTry connect CobotX failed!
\rPlease check wether connected with CobotX.
\rTry connect Mercury failed!
\rPlease check wether connected with Mercury.
\rPlease chckt wether the port or baud is right.
"""
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import rospy
from sensor_msgs.msg import JointState
from std_msgs.msg import Header
from cobotx_a450_communication.srv import GetAngles
from mercury_a1_communication.srv import GetAngles


def talker():
Expand Down
66 changes: 66 additions & 0 deletions Mercury/mercury_a1/scripts/listen_real_of_topic.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#!/usr/bin/env python3
# encoding:utf-8

import math
import rospy
from sensor_msgs.msg import JointState
from std_msgs.msg import Header
from mercury_a1_communication.msg import MercuryAngles


class Listener(object):
def __init__(self):
super(Listener, self).__init__()

rospy.loginfo("start ...")
rospy.init_node("real_listener_1", anonymous=True)
# init publisher.初始化发布者
self.pub = rospy.Publisher("joint_states", JointState, queue_size=10)
# init subscriber.初始化订阅者
self.sub = rospy.Subscriber("myarm/angles_real", MercuryAngles, self.callback)
rospy.spin()

def callback(self, data):
"""`mercury/angles_real` subscriber callback method.

Args:
data (MercuryAngles): callback argument.
"""
# ini publisher object. 初始化发布者对象
joint_state_send = JointState()
joint_state_send.header = Header()

joint_state_send.name = [
"joint1_to_base",
"joint2_to_joint1",
"joint3_to_joint2",
"joint4_to_joint3",
"joint5_to_joint4",
"joint6_to_joint5",
"joint7_to_joint6",
]
joint_state_send.velocity = [0]
joint_state_send.effort = []
joint_state_send.header.stamp = rospy.Time.now()

# process callback data. 处理回调数据。
radians_list = [
data.joint_1 * (math.pi / 180),
data.joint_2 * (math.pi / 180),
data.joint_3 * (math.pi / 180),
data.joint_4 * (math.pi / 180),
data.joint_5 * (math.pi / 180),
data.joint_6 * (math.pi / 180),
data.joint_7 * (math.pi / 180),
]
rospy.loginfo("res: {}".format(radians_list))

joint_state_send.position = radians_list
self.pub.publish(joint_state_send)


if __name__ == "__main__":
try:
Listener()
except rospy.ROSInterruptException:
pass
Loading
Loading