diff --git a/ur_bringup/launch/ur_common.launch b/ur_bringup/launch/ur_common.launch index cd3b292caa6eb98df20ed788f474bc7fb31d47a1..f2d9e9e6a5e84c0138ec061c5acf87945506e8f5 100644 --- a/ur_bringup/launch/ur_common.launch +++ b/ur_bringup/launch/ur_common.launch @@ -16,6 +16,9 @@ <arg name="min_payload"/> <arg name="max_payload"/> + <!-- 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] --> + <!-- copy the specified IP address to be consistant with ROS-Industrial spec. NOTE: The ip address is actually passed to the driver on the command line --> <param name="/robot_ip_address" type="str" value="$(arg robot_ip)"/> @@ -27,6 +30,7 @@ <node name="ur_driver" pkg="ur_driver" type="driver.py" args="$(arg robot_ip) $(arg reverse_port)" output="screen"> <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)"/> </node> <!-- TF Buffer Server -->