diff --git a/launch/ur10_bringup.launch b/launch/ur10_bringup.launch index 942a462d5..6b5960d30 100644 --- a/launch/ur10_bringup.launch +++ b/launch/ur10_bringup.launch @@ -9,7 +9,8 @@ - + + @@ -34,6 +35,7 @@ + diff --git a/launch/ur10_bringup_compatible.launch b/launch/ur10_bringup_compatible.launch index 749c693e6..6a4f3b842 100644 --- a/launch/ur10_bringup_compatible.launch +++ b/launch/ur10_bringup_compatible.launch @@ -9,7 +9,8 @@ - + + @@ -35,6 +36,7 @@ + diff --git a/launch/ur10_bringup_joint_limited.launch b/launch/ur10_bringup_joint_limited.launch index 85ff2166b..a99f0fc18 100644 --- a/launch/ur10_bringup_joint_limited.launch +++ b/launch/ur10_bringup_joint_limited.launch @@ -9,7 +9,8 @@ - + + @@ -28,6 +29,7 @@ + diff --git a/launch/ur10_ros_control.launch b/launch/ur10_ros_control.launch index 471bfd676..20bdef883 100644 --- a/launch/ur10_ros_control.launch +++ b/launch/ur10_ros_control.launch @@ -6,7 +6,8 @@ - + + @@ -27,6 +28,7 @@ + diff --git a/launch/ur3_bringup.launch b/launch/ur3_bringup.launch index 0c37dc9c6..106a1bd0d 100644 --- a/launch/ur3_bringup.launch +++ b/launch/ur3_bringup.launch @@ -9,7 +9,8 @@ - + + @@ -34,6 +35,7 @@ + diff --git a/launch/ur3_bringup_joint_limited.launch b/launch/ur3_bringup_joint_limited.launch index df0955597..e0c734ef4 100644 --- a/launch/ur3_bringup_joint_limited.launch +++ b/launch/ur3_bringup_joint_limited.launch @@ -9,7 +9,8 @@ - + + @@ -28,6 +29,7 @@ + diff --git a/launch/ur3_ros_control.launch b/launch/ur3_ros_control.launch index d778b808f..25b2d5beb 100644 --- a/launch/ur3_ros_control.launch +++ b/launch/ur3_ros_control.launch @@ -6,7 +6,8 @@ - + + @@ -27,6 +28,7 @@ + diff --git a/launch/ur5_bringup.launch b/launch/ur5_bringup.launch index 780d9bc0c..e568fce2f 100644 --- a/launch/ur5_bringup.launch +++ b/launch/ur5_bringup.launch @@ -9,7 +9,8 @@ - + + @@ -34,6 +35,7 @@ + diff --git a/launch/ur5_bringup_compatible.launch b/launch/ur5_bringup_compatible.launch index 069c2a6f5..197e95797 100644 --- a/launch/ur5_bringup_compatible.launch +++ b/launch/ur5_bringup_compatible.launch @@ -9,7 +9,8 @@ - + + @@ -35,6 +36,7 @@ + diff --git a/launch/ur5_bringup_joint_limited.launch b/launch/ur5_bringup_joint_limited.launch index 1975d3b63..5c32b6c3f 100644 --- a/launch/ur5_bringup_joint_limited.launch +++ b/launch/ur5_bringup_joint_limited.launch @@ -9,7 +9,8 @@ - + + @@ -28,6 +29,7 @@ + diff --git a/launch/ur5_ros_control.launch b/launch/ur5_ros_control.launch index d1118e6ae..f154441f2 100644 --- a/launch/ur5_ros_control.launch +++ b/launch/ur5_ros_control.launch @@ -6,7 +6,8 @@ - + + @@ -27,6 +28,7 @@ + diff --git a/launch/ur_common.launch b/launch/ur_common.launch index 726f7a1c6..2e639c080 100644 --- a/launch/ur_common.launch +++ b/launch/ur_common.launch @@ -8,7 +8,8 @@ --> - + + @@ -39,6 +40,7 @@ + diff --git a/src/ros_main.cpp b/src/ros_main.cpp index 7ea7fcf7e..cc49acfe5 100644 --- a/src/ros_main.cpp +++ b/src/ros_main.cpp @@ -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"); @@ -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 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; @@ -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); @@ -148,7 +151,13 @@ 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); + + // if no reverse IP address has been configured, try to detect one + if (local_ip.empty()) + { + local_ip = getLocalIPAccessibleFromHost(args.host); + } URFactory factory(args.host); vector services;