Skip to content

Commit

Permalink
rsi_hw_iface: rename RSI params to better reflect function.
Browse files Browse the repository at this point in the history
  • Loading branch information
gavanderhoorn committed Aug 30, 2016
1 parent a65565c commit cf26f02
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 11 deletions.
6 changes: 3 additions & 3 deletions kuka_rsi_hw_interface/src/kuka_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,15 +155,15 @@ void KukaHardwareInterface::start()

void KukaHardwareInterface::configure()
{
if (nh_.getParam("rsi/address", local_host_) && nh_.getParam("rsi/port", local_port_))
if (nh_.getParam("rsi/listen_address", local_host_) && nh_.getParam("rsi/listen_port", local_port_))
{
ROS_INFO_STREAM_NAMED("kuka_hardware_interface",
"Setting up RSI server on: (" << local_host_ << ", " << local_port_ << ")");
}
else
{
ROS_ERROR("Failed to get RSI address or port from parameter server!");
throw std::runtime_error("Failed to get RSI address or port from parameter server.");
ROS_ERROR("Failed to get RSI listen address or listen port from parameter server!");
throw std::runtime_error("Failed to get RSI listen address or listen port from parameter server.");
}
rt_rsi_pub_.reset(new realtime_tools::RealtimePublisher<std_msgs::String>(nh_, "rsi_xml_doc", 3));
}
Expand Down
4 changes: 2 additions & 2 deletions kuka_rsi_hw_interface/test/ag1_params.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
rsi:
address: "192.168.1.11"
port: 49151
listen_address: "192.168.1.11"
listen_port: 49151
4 changes: 2 additions & 2 deletions kuka_rsi_hw_interface/test/ag2_params.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
rsi:
address: "192.168.1.11"
port: 49152
listen_address: "192.168.1.11"
listen_port: 49152

4 changes: 2 additions & 2 deletions kuka_rsi_hw_interface/test/test_params.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
rsi:
address: "192.168.1.67"
port: 49152
listen_address: "192.168.1.67"
listen_port: 49152
4 changes: 2 additions & 2 deletions kuka_rsi_hw_interface/test/test_params_sim.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
rsi:
address: "127.0.0.1"
port: 49152
listen_address: "127.0.0.1"
listen_port: 49152

0 comments on commit cf26f02

Please sign in to comment.