mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Taking IP address from parameter server as default instead of command line as per ROS-Industrial specs
This commit is contained in:
@@ -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)"/>
|
||||
|
||||
@@ -431,14 +431,19 @@ int main(int argc, char **argv) {
|
||||
if (ros::param::get("use_sim_time", use_sim_time)) {
|
||||
ROS_WARN("use_sim_time is set!!");
|
||||
}
|
||||
if (!(ros::param::get("~robot_ip_address", host))) {
|
||||
if (argc > 1) {
|
||||
ROS_WARN(
|
||||
"Please set the parameter robot_ip_address instead of giving it as a command line argument. This method is DEPRECATED");
|
||||
host = argv[1];
|
||||
} else if (!(ros::param::get("~robot_ip", host))) {
|
||||
} else {
|
||||
ROS_FATAL(
|
||||
"Could not get robot ip. Please supply it as command line parameter or on the parameter server as robot_ip");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
RosWrapper interface(host);
|
||||
|
||||
ros::spin();
|
||||
|
||||
Reference in New Issue
Block a user