Skip to content

Commit

Permalink
Proposed fix for issue ROBOTIS-GIT#1
Browse files Browse the repository at this point in the history
This is a proposed fix for the issue ROBOTIS-GIT#1, No ability to set frame_id in the scan message. It's only for the ROS1 version of the driver, but similar solution could probably be implemented for the ROS2 version as well.
  • Loading branch information
dominik-polic authored Jun 30, 2022
1 parent a22fa44 commit c937c2d
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion src/ld08_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,9 @@ int main(int argc , char **argv)
strcpy(product_ver,"LD08");
ros::init(argc, argv, product_ver);
ros::NodeHandle nh; /* create a ROS Node */
ros::NodeHandle priv_nh("~");
std::string frame_id;
priv_nh.param("frame_id", frame_id, std::string("base_scan"));
char topic_name[20]={0};
strcat(topic_name,product_ver);
strcat(topic_name,"/scan");
Expand Down Expand Up @@ -59,7 +62,7 @@ int main(int argc , char **argv)
cmd_port.Open(port_name);
sensor_msgs::LaserScan scan;
scan.header.stamp = ros::Time::now();
scan.header.frame_id = "base_scan";
scan.header.frame_id = frame_id;
scan.range_min = 0.0;
scan.range_max = 100.0;

Expand Down

0 comments on commit c937c2d

Please sign in to comment.