1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Taking IP address from parameter server as default instead of command line as per ROS-Industrial specs

This commit is contained in:
Thomas Timm Andersen
2015-09-17 13:40:16 +02:00
parent fc219e4eee
commit 0310193b15
2 changed files with 14 additions and 16 deletions

View File

@@ -16,19 +16,12 @@
<!-- 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)"/>
<!-- 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)"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<!-- driver -->
<node name="ur_driver" pkg="ur_modern_driver" type="ur_driver" args="$(arg robot_ip)" output="screen">
<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="robot_ip_address" type="str" value="$(arg robot_ip)"/>
<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)"/>