mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Low Bandwidth Trajectory Follower has now much less comments and debugging information - which means that it will parse on UR robot in around 400 ms instead of 700 ms. It also has an adjustment loop in case the robot does not reach any of the trajectory points specified. It will catch-up at every trajectory point sent by MoveIt and will try to get as close as possible to the desired pointi (it will check if all joints are within MAX_JOINT_DIFFERENCE from the desired positions)
63 lines
3.3 KiB
XML
63 lines
3.3 KiB
XML
<?xml version="1.0"?>
|
|
<!--
|
|
Universal robot common bringup. Starts ur driver node and robot state
|
|
publisher (translates joint positions to propper tfs).
|
|
|
|
Usage:
|
|
ur_common.launch robot_ip:=<value>
|
|
-->
|
|
<launch>
|
|
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
|
<arg name="robot_ip" />
|
|
<arg name="min_payload" />
|
|
<arg name="max_payload" />
|
|
<arg name="prefix" default="" />
|
|
<arg name="use_ros_control" default="false"/>
|
|
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
|
<arg name="time_interval" default="0.008"/>
|
|
<arg name="servoj_time" default="0.008" />
|
|
<arg name="servoj_time_waiting" default="0.001" />
|
|
<arg name="max_waiting_time" default="2.0" />
|
|
<arg name="debug" default="false" />
|
|
<arg name="more_debug" default="false" />
|
|
<arg name="servoj_gain" default="100." />
|
|
<arg name="servoj_lookahead_time" default="1." />
|
|
<arg name="max_joint_difference" default="0.01" />
|
|
<arg name="base_frame" default="$(arg prefix)base" />
|
|
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
|
<arg name="shutdown_on_disconnect" default="true" />
|
|
|
|
<!-- require_activation defines when the service /ur_driver/robot_enable needs to be called. -->
|
|
<arg name="require_activation" default="Never" /> <!-- Never, Always, OnStartup -->
|
|
|
|
<!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits -->
|
|
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
|
|
|
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
|
|
|
|
<!-- driver -->
|
|
<node name="ur_driver" pkg="ur_modern_driver" type="ur_driver" output="screen">
|
|
<!-- copy the specified IP address to be consistant with ROS-Industrial spec. -->
|
|
<param name="prefix" type="str" value="$(arg prefix)" />
|
|
<param name="robot_ip_address" type="str" value="$(arg robot_ip)" />
|
|
<param name="use_ros_control" type="bool" value="$(arg use_ros_control)"/>
|
|
<param name="use_lowbandwidth_trajectory_follower" type="bool" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
|
<param name="min_payload" type="double" value="$(arg min_payload)" />
|
|
<param name="max_payload" type="double" value="$(arg max_payload)" />
|
|
<param name="max_velocity" type="double" value="$(arg max_velocity)" />
|
|
<param name="time_interval" type="double" value="$(arg time_interval)" />
|
|
<param name="servoj_time" type="double" value="$(arg servoj_time)" />
|
|
<param name="servoj_time_waiting" type="double" value="$(arg servoj_time_waiting)" />
|
|
<param name="max_waiting_time" type="double" value="$(arg max_waiting_time)" />
|
|
<param name="debug" type="bool" value="$(arg debug)"/>
|
|
<param name="more_debug" type="bool" value="$(arg more_debug)"/>
|
|
<param name="servoj_gain" type="double" value="$(arg servoj_gain)" />
|
|
<param name="servoj_lookahead_time" type="double" value="$(arg servoj_lookahead_time)" />
|
|
<param name="max_joint_difference" type="double" value="$(arg max_joint_difference)" />
|
|
<param name="base_frame" type="str" value="$(arg base_frame)"/>
|
|
<param name="tool_frame" type="str" value="$(arg tool_frame)"/>
|
|
<param name="require_activation" type="str" value="$(arg require_activation)" />
|
|
<param name="shutdown_on_disconnect" type="bool" value="$(arg shutdown_on_disconnect)"/>
|
|
</node>
|
|
</launch>
|