diff --git a/autonomous_robotics_ros/src/ti_mmwave_rospkg/include/mmWaveCommSrv.hpp b/autonomous_robotics_ros/src/ti_mmwave_rospkg/include/mmWaveCommSrv.hpp
index 9e845e9..804afa6 100755
--- a/autonomous_robotics_ros/src/ti_mmwave_rospkg/include/mmWaveCommSrv.hpp
+++ b/autonomous_robotics_ros/src/ti_mmwave_rospkg/include/mmWaveCommSrv.hpp
@@ -76,6 +76,8 @@ class mmWaveCommSrv : public nodelet::Nodelet
std::string mySerialPort;
int myBaudRate;
+
+ std::string mmWaveCLIName;
}; //Class mmWaveCommSrv
} //namespace ti_mmwave_rospkg
diff --git a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_east.launch b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_east.launch
index 781697e..2c807a7 100644
--- a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_east.launch
+++ b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_east.launch
@@ -12,18 +12,21 @@
-
+
-
+
+
-
+
+
+
diff --git a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_north.launch b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_north.launch
index 89cb9d1..b326d41 100644
--- a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_north.launch
+++ b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_north.launch
@@ -12,18 +12,21 @@
-
+
-
+
+
-
+
+
+
-
+
+
+
diff --git a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_west.launch b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_west.launch
index 177a8c6..5b815fb 100644
--- a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_west.launch
+++ b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/bubble_sensor_west.launch
@@ -12,18 +12,21 @@
-
+
-
+
+
-
+
+
+
diff --git a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/ti_mmwave_sensor.launch b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/ti_mmwave_sensor.launch
index e73ba7b..17aa815 100644
--- a/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/ti_mmwave_sensor.launch
+++ b/autonomous_robotics_ros/src/ti_mmwave_rospkg/launch/ti_mmwave_sensor.launch
@@ -19,11 +19,14 @@
+
-
+
+
+
diff --git a/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveCommSrv.cpp b/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveCommSrv.cpp
index 11ae675..716f41b 100755
--- a/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveCommSrv.cpp
+++ b/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveCommSrv.cpp
@@ -53,11 +53,12 @@ void mmWaveCommSrv::onInit()
private_nh2.getParam("command_port", mySerialPort);
private_nh2.getParam("command_rate", myBaudRate);
+ private_nh2.getParam("mmWaveCLI_name", mmWaveCLIName);
ROS_INFO("mmWaveCommSrv: command_port = %s", mySerialPort.c_str());
ROS_INFO("mmWaveCommSrv: command_rate = %d", myBaudRate);
- commSrv = private_nh.advertiseService("/mmWaveCLI", &mmWaveCommSrv::commSrv_cb, this);
+ commSrv = private_nh.advertiseService(mmWaveCLIName, &mmWaveCommSrv::commSrv_cb, this);
NODELET_DEBUG("mmWaveCommsrv: Finished onInit function");
}
diff --git a/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveQuickConfig.cpp b/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveQuickConfig.cpp
index 7bdf3b9..de13910 100755
--- a/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveQuickConfig.cpp
+++ b/autonomous_robotics_ros/src/ti_mmwave_rospkg/src/mmWaveQuickConfig.cpp
@@ -47,18 +47,20 @@
int main(int argc, char **argv) {
ros::init(argc, argv, "mmWaveQuickConfig");
ros::NodeHandle nh;
+ ros::NodeHandle private_nh("~");
ti_mmwave_rospkg::mmWaveCLI srv;
if (argc != 2) {
ROS_INFO("mmWaveQuickConfig: usage: mmWaveQuickConfig /file_directory/params.cfg");
return 1;
} else
ROS_INFO("mmWaveQuickConfig: Configuring mmWave device using config file: %s", argv[1]);
-
- ros::ServiceClient client = nh.serviceClient("/mmWaveCLI");
+ std::string mmWaveCLIName;
+ private_nh.getParam("mmWaveCLI_name", mmWaveCLIName);
+ ros::ServiceClient client = nh.serviceClient(mmWaveCLIName);
std::ifstream myParams;
ti_mmwave_rospkg::ParameterParser parser;
//wait for service to become available
- ros::service::waitForService("/mmWaveCLI", 10000);
+ ros::service::waitForService(mmWaveCLIName, 10000);
//wait 0.5 secs to avoid multi-sensor conflicts
ros::Duration(0.5).sleep();