Skip to content

Commit

Permalink
Add configurable reverse ip address (ros-industrial#299)
Browse files Browse the repository at this point in the history
  • Loading branch information
gonzalocasas committed Apr 24, 2019
1 parent 77fa08a commit 872e3e1
Show file tree
Hide file tree
Showing 13 changed files with 30 additions and 2 deletions.
2 changes: 2 additions & 0 deletions launch/ur10_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -34,6 +35,7 @@
<!-- ur common -->
<include file="$(find ur_modern_driver)/launch/ur_common.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur10_bringup_compatible.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -35,6 +36,7 @@
<!-- ur common -->
<include file="$(find ur_modern_driver)/launch/ur_common.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur10_bringup_joint_limited.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="10.0"/>
Expand All @@ -28,6 +29,7 @@

<include file="$(find ur_modern_driver)/launch/ur10_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="limited" value="true"/>
<arg name="min_payload" value="$(arg min_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur10_ros_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />

<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -27,6 +28,7 @@
<!-- Load hardware interface -->
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
<param name="reverse_ip_address" type="str" value="$(arg reverse_ip_address)" />
<param name="reverse_port" type="int" value="$(arg reverse_port)" />
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur3_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -34,6 +35,7 @@
<!-- ur common -->
<include file="$(find ur_modern_driver)/launch/ur_common.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur3_bringup_joint_limited.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="3.0"/>
Expand All @@ -28,6 +29,7 @@

<include file="$(find ur_modern_driver)/launch/ur3_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="limited" value="true"/>
<arg name="min_payload" value="$(arg min_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur3_ros_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />

<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -27,6 +28,7 @@
<!-- Load hardware interface -->
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
<param name="reverse_ip_address" type="str" value="$(arg reverse_ip_address)" />
<param name="reverse_port" type="int" value="$(arg reverse_port)" />
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur5_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -34,6 +35,7 @@
<!-- ur common -->
<include file="$(find ur_modern_driver)/launch/ur_common.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur5_bringup_compatible.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -35,6 +36,7 @@
<!-- ur common -->
<include file="$(find ur_modern_driver)/launch/ur_common.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur5_bringup_joint_limited.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="5.0"/>
Expand All @@ -28,6 +29,7 @@

<include file="$(find ur_modern_driver)/launch/ur5_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="reverse_ip_address" value="$(arg reverse_ip_address)"/>
<arg name="reverse_port" value="$(arg reverse_port)"/>
<arg name="limited" value="true"/>
<arg name="min_payload" value="$(arg min_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur5_ros_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />

<arg name="robot_ip"/>
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
Expand All @@ -27,6 +28,7 @@
<!-- Load hardware interface -->
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
<param name="reverse_ip_address" type="str" value="$(arg reverse_ip_address)" />
<param name="reverse_port" type="int" value="$(arg reverse_port)" />
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
Expand Down
2 changes: 2 additions & 0 deletions launch/ur_common.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
<launch>
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip" />
<arg name="reverse_ip_address" default=""/>
<arg name="reverse_port" default="50001"/>
<arg name="min_payload" />
<arg name="max_payload" />
Expand Down Expand Up @@ -39,6 +40,7 @@
<!-- 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="reverse_ip_address" type="str" value="$(arg reverse_ip_address)" />
<param name="reverse_port" type="int" value="$(arg reverse_port)" />
<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)"/>
Expand Down
8 changes: 6 additions & 2 deletions src/ros_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include "ur_modern_driver/ur/state.h"

static const std::string IP_ADDR_ARG("~robot_ip_address");
static const std::string REVERSE_IP_ADDR_ARG("~reverse_ip_address");
static const std::string REVERSE_PORT_ARG("~reverse_port");
static const std::string ROS_CONTROL_ARG("~use_ros_control");
static const std::string LOW_BANDWIDTH_TRAJECTORY_FOLLOWER("~use_lowbandwidth_trajectory_follower");
Expand All @@ -69,11 +70,12 @@ struct ProgArgs
std::string base_frame;
std::string tool_frame;
std::string tcp_link;
std::string reverse_ip_address;
int32_t reverse_port;
std::vector<std::string> joint_names;
double max_acceleration;
double max_velocity;
double max_vel_change;
int32_t reverse_port;
bool use_ros_control;
bool use_lowbandwidth_trajectory_follower;
bool shutdown_on_disconnect;
Expand Down Expand Up @@ -114,6 +116,7 @@ bool parse_args(ProgArgs &args)
LOG_ERROR("robot_ip_address parameter must be set!");
return false;
}
ros::param::param(REVERSE_IP_ADDR_ARG, args.reverse_ip_address, std::string());
ros::param::param(REVERSE_PORT_ARG, args.reverse_port, int32_t(50001));
ros::param::param(MAX_VEL_CHANGE_ARG, args.max_vel_change, 15.0); // rad/s
ros::param::param(MAX_VEL_CHANGE_ARG, args.max_velocity, 10.0);
Expand Down Expand Up @@ -148,7 +151,8 @@ int main(int argc, char **argv)
std::transform(args.joint_names.begin(), args.joint_names.end(), args.joint_names.begin(),
[&args](std::string name) { return args.prefix + name; });

std::string local_ip(getLocalIPAccessibleFromHost(args.host));
std::string local_ip(args.reverse_ip_address.empty() ? getLocalIPAccessibleFromHost(args.host) :
args.reverse_ip_address);

URFactory factory(args.host);
vector<Service *> services;
Expand Down

0 comments on commit 872e3e1

Please sign in to comment.