Skip to content

Commit

Permalink
修改bringup文件以能够正常使用,现已能同时连接两台机械臂
Browse files Browse the repository at this point in the history
  • Loading branch information
SakuraToErii committed Nov 13, 2024
1 parent 9c4e320 commit 4f97ddd
Show file tree
Hide file tree
Showing 6 changed files with 116 additions and 29 deletions.
42 changes: 27 additions & 15 deletions launch/both_arm_moveit_planning_execution.launch
Original file line number Diff line number Diff line change
@@ -1,19 +1,31 @@
<launch>

<group ns="left_arm">
<remap from="/follow_joint_trajectory" to="scaled_pos_traj_controller/follow_joint_trajectory"/>
<include file="$(find ur5_e_moveit_config)/launch/move_group.launch">
<arg name="limited" default="false"/>
<arg name="debug" default="false" />
</include>
</group>
<!--
# 不使用 group
/follow_joint_trajectory
/move_group/status
<group ns="right_arm">
<remap from="/follow_joint_trajectory" to="scaled_pos_traj_controller/follow_joint_trajectory"/>
<include file="$(find ur5_e_moveit_config)/launch/move_group.launch">
<arg name="limited" default="false"/>
<arg name="debug" default="false" />
</include>
</group>
# 使用 group ns="left_arm"
/left_arm/follow_joint_trajectory
/left_arm/move_group/status
组内的参数只在组内有效
-->
<group ns="left_arm">
<remap from="/follow_joint_trajectory" to="scaled_pos_traj_controller/follow_joint_trajectory"/>
<include file="$(find ur5_e_moveit_config)/launch/move_group.launch">
<arg name="limited" default="false"/>
<!-- 是否使用关节限制 -->
<arg name="debug" default="false" />
<!-- 是否开启调试 -->
</include>
</group>

<group ns="right_arm">
<remap from="/follow_joint_trajectory" to="scaled_pos_traj_controller/follow_joint_trajectory"/>
<include file="$(find ur5_e_moveit_config)/launch/move_group.launch">
<arg name="limited" default="false"/>
<arg name="debug" default="false" />
</include>
</group>

</launch>
71 changes: 70 additions & 1 deletion launch/left_arm_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,22 +4,89 @@
<arg name="robot_ip" default="192.168.0.2" doc="IP address by which the robot can be reached."/>
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
<arg name="trajectory_port" default="50003" doc="Port that will be opened by the driver to allow trajectory forwarding."/>
<arg name="script_command_port" default="50004" doc="Port that will be opened by the driver to allow forwarding script commands to the robot."/>

<!-- TF前缀参数:用于在tf树中为机器人添加命名空间前缀 -->
<!-- 例如:如果 tf_prefix="left_",那么所有的关节和链接名称都会加上"left_"前缀 -->
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>

<!-- 默认启动的控制器列表:这些控制器会在启动时自动激活 -->
<!-- joint_state_controller: 发布关节状态信息 -->
<!-- scaled_pos_joint_traj_controller: 带速度缩放的位置轨迹控制器 -->
<!-- speed_scaling_state_controller: 速度缩放状态控制器 -->
<!-- force_torque_sensor_controller: 力矩传感器控制器 -->
<arg name="controllers" default="joint_state_controller scaled_pos_joint_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>

<!-- 初始加载但不启动的控制器列表 -->
<!-- pos_joint_traj_controller: 普通的位置轨迹控制器(作为备用) -->
<arg name="stopped_controllers" default="pos_joint_traj_controller" doc="Controllers that are initally loaded, but not started."/>

<!-- 控制器配置文件的路径 -->
<!-- 包含了所有控制器的详细配置参数(PID参数、限制等) -->
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur5e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>


<!-- 机器人描述文件的路径 -->
<!-- 包含了机器人的URDF模型定义和其他相关参数 -->
<arg name="robot_description_file" default="$(find ur_e_description)/launch/ur5e_upload.launch" doc="Robot description launch file."/>

<!-- 运动学配置文件的路径 -->
<!-- 用于校准修正的运动学配置文件 -->
<arg name="kinematics_config" default="$(find ordis_dual_arm)/etc/dual_arm_left.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>

<!-- 工具通信参数 -->
<!-- 用于启用工具通信 -->
<arg name="use_tool_communication" default="false" doc="On e-Series robots tool communication can be enabled with this argument"/>

<!-- 工具电压 -->
<arg name="tool_voltage" default="0" doc="Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true."/>

<!-- 工具通信奇偶校验位设置 -->
<!-- 奇偶校验用于通信错误检测,0表示无校验 -->
<!-- 仅在 use_tool_communication=true 时使用 -->
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/>

<!-- 工具通信波特率设置 -->
<!-- 定义串口通信的速率,115200是常用的波特率 -->
<!-- 仅在 use_tool_communication=true 时使用, -->
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/>

<!-- 工具通信停止位设置 -->
<!-- 定义每个数据包结束时的停止位数量 -->
<!-- 仅在 use_tool_communication=true 时使用 -->
<arg name="tool_stop_bits" default="1" doc="Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true."/>

<!-- 接收通道空闲字符数设置 -->
<!-- 定义接收数据包之间的空闲字符数 -->
<!-- 仅在 use_tool_communication=true 时使用 -->
<arg name="tool_rx_idle_chars" default="1.5" doc="Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>

<!-- 发送通道空闲字符数设置 -->
<!-- 定义发送数据包之间的空闲字符数 -->
<!-- 仅在 use_tool_communication=true 时使用 -->
<arg name="tool_tx_idle_chars" default="3.5" doc="Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>

<!-- 工具通信设备名称 -->
<!-- 定义用于工具通信的本地设备文件路径 -->
<!-- 仅在 use_tool_communication=true 时使用 -->
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>

<!-- 工具通信TCP端口 -->
<!-- 定义机器人控制器发布工具通信接口的端口号 -->
<!-- 仅在 use_tool_communication=true 时使用 -->
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>


<!-- 限制模式设置 -->
<!-- 当设为true时,每个轴的旋转范围限制在-PI到PI之间 -->
<!-- 用于增加安全性或满足特定应用需求,这条已废弃 -->
<!--<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>-->

<!-- 无头模式设置 -->
<!-- 当设为true时,自动向机器人发送URScript执行 -->
<!-- 在e系列机器人上需要设置为'远程控制'模式 -->
<!-- 启用此模式不需要在机器人上安装URCap -->
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>

<include file="$(find ur_robot_driver)/launch/ur_common.launch">
Expand All @@ -31,6 +98,8 @@
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
<arg name="trajectory_port" value="$(arg trajectory_port)"/>
<arg name="script_command_port" value="$(arg script_command_port)"/>
<arg name="limited" value="$(arg limited)"/>
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
<arg name="controllers" value="$(arg controllers)"/>
Expand Down
14 changes: 8 additions & 6 deletions launch/right_arm_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,15 @@
<launch>
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
<arg name="robot_ip" default="192.168.0.3" doc="IP address by which the robot can be reached."/>
<arg name="reverse_port" default="50003" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
<arg name="script_sender_port" default="50004" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
<arg name="reverse_port" default="50005" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
<arg name="script_sender_port" default="50006" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
<arg name="trajectory_port" default="50007" doc="Port that will be opened by the driver to allow trajectory forwarding."/>
<arg name="script_command_port" default="50008" doc="Port that will be opened by the driver to allow forwarding script commands to the robot."/>
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
<arg name="controllers" default="joint_state_controller scaled_pos_joint_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
<arg name="stopped_controllers" default="pos_joint_traj_controller" doc="Controllers that are initally loaded, but not started."/>
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur5e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
<arg name="robot_description_file" default="$(find ur_e_description)/launch/ur5e_upload.launch" doc="Robot description launch file."/>
<arg name="robot_description_file" default="$(find ur_description)/launch/load_ur5e.launch" doc="Robot description launch file."/>
<arg name="kinematics_config" default="$(find ordis_dual_arm)/etc/dual_arm_right.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
<arg name="use_tool_communication" default="false" doc="On e-Series robots tool communication can be enabled with this argument"/>
<arg name="tool_voltage" default="0" doc="Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true."/>
Expand All @@ -19,7 +21,6 @@
<arg name="tool_tx_idle_chars" default="3.5" doc="Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>

<include file="$(find ur_robot_driver)/launch/ur_common.launch">
Expand All @@ -31,7 +32,8 @@
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
<arg name="limited" value="$(arg limited)"/>
<arg name="trajectory_port" value="$(arg trajectory_port)"/>
<arg name="script_command_port" value="$(arg script_command_port)"/>
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
<arg name="controllers" value="$(arg controllers)"/>
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
Expand All @@ -46,4 +48,4 @@
<arg name="tool_tcp_port" value="$(arg tool_tcp_port)"/>
</include>

</launch>
</launch>
5 changes: 0 additions & 5 deletions launch/robot_cell_upload_macs.launch

This file was deleted.

9 changes: 9 additions & 0 deletions launch/robot_cell_upload_ordis.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<?xml version="1.0"?>
<launch>
<!-- <param name="robot_cell_description" textfile="$(find ur_e_description)/urdf/robot_cell.sdf" /> -->
<!-- 使用xacro宏处理器将robot_cell.sdf文件转换为URDF格式 -->
<!-- robot_cell_description 是自定义参数,用于描述完整工作单元
SDF 文件用于详细描述仿真环境和物理特性
两者结合使用可以创建完整的机器人工作环境仿真-->
<param name="robot_cell_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/robot_cell.sdf'" />
</launch>
4 changes: 2 additions & 2 deletions sdf/robot_cell.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<geometry>
<mesh>
<!-- <uri>package://ur_e_description/meshes/robot_cell/visual/robot_cell.stl</uri> -->
<uri>file:///home/abhishek/catkin_ws/src/ordis_dual_arm/meshes/robot_cell/visual/robot_cell.dae</uri>
<uri>package://ordis_dual_arm/meshes/robot_cell/visual/robot_cell.dae</uri>
</mesh>
</geometry>
</visual>
Expand All @@ -21,7 +21,7 @@
<geometry>
<mesh>
<!-- <uri>package://ur_e_description/meshes/robot_cell/collision/robot_cell_simplified.stl</uri> -->
<uri>file:///home/abhishek/catkin_ws/src/ordis_dual_arm/meshes/robot_cell/collision/robot_cell_simplified.stl</uri>
<uri>package://ordis_dual_arm/meshes/robot_cell/collision/robot_cell_simplified.stl</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
Expand Down

0 comments on commit 4f97ddd

Please sign in to comment.