From 2661cf9e3404fffe5a346223155c9f889c5d33ca Mon Sep 17 00:00:00 2001
From: shanmukhavishnu <50124557+iam-shanmukha@users.noreply.github.com>
Date: Wed, 23 Jun 2021 10:04:57 +0530
Subject: [PATCH] custom frame_id in param
user can give custom frame_id in launch file param
```
```
---
tfmini_ros/src/TFmini_ros_node.cpp | 10 ++++++++--
1 file changed, 8 insertions(+), 2 deletions(-)
diff --git a/tfmini_ros/src/TFmini_ros_node.cpp b/tfmini_ros/src/TFmini_ros_node.cpp
index 93a82e1..d3bd6c8 100644
--- a/tfmini_ros/src/TFmini_ros_node.cpp
+++ b/tfmini_ros/src/TFmini_ros_node.cpp
@@ -4,13 +4,19 @@ int main(int argc, char **argv)
{
ros::init(argc, argv, "tfmini_ros_node");
ros::NodeHandle nh("~");
- std::string id = "TFmini";
+ //std::string id = "TFmini";
+ std::string id;
std::string portName;
int baud_rate;
benewake::TFmini *tfmini_obj;
nh.param("serial_port", portName, std::string("/dev/ttyUSB0"));
nh.param("baud_rate", baud_rate, 115200);
+ std::string frame_id = "TFmini";
+ if(!nh.getParam("frame_id", frame_id))
+ {
+ ROS_WARN_STREAM("No frame_id provided - default: " << frame_id);
+ }
tfmini_obj = new benewake::TFmini(portName, baud_rate);
ros::Publisher pub_range = nh.advertise(id, 1000, true);
@@ -19,7 +25,7 @@ int main(int argc, char **argv)
TFmini_range.field_of_view = 0.04;
TFmini_range.min_range = 0.3;
TFmini_range.max_range = 12;
- TFmini_range.header.frame_id = id;
+ TFmini_range.header.frame_id = frame_id;
float dist = 0;
ROS_INFO_STREAM("Start processing ...");