ROBOTIS-GIT / ld08_driver

ROS package for TurtleBot3 LD08 Lidar
Apache License 2.0
6 stars 22 forks source link

No ability to set the frame_id in the scan message. #1

Open JToolGD opened 2 years ago

JToolGD commented 2 years ago

As the title says. The frame_id is hardcoded to be base_scan. Meaning that robots with namespaces will have a link called tb1/base_scan in the tf, but the lidar keeps publishing with the frame_ide base_scan.

Funnily enough, the parameter is added to the launch file in this repo and the launch file in the turtlebot repo. This would give people the impression it should work, even if it doesn't.

JToolGD commented 2 years ago

Related to this question

dominik-polic commented 2 years ago

I've spent hours trying to figure out what I was doing wrong and the workaround in the question you linked saved me a lot of headache so I just wanted to say thanks, and I hope that this can be fixed in the future.

dominik-polic commented 2 years ago

This should be pretty easy to fix, I will describe my proposal below. I've got to test it a bit more, but so far it seems to be working.

Edit the following file: /ld08_driver/src/ld08_driver.cpp

Insert following between lines 31(ros::NodeHandle nh;) and 32(char topic_name[20]={0};):

ros::NodeHandle priv_nh("~");
std::string frame_id;
priv_nh.param("frame_id", frame_id, std::string("base_scan"));

Replace (on line 62):

scan.header.frame_id = "base_scan";

with:

scan.header.frame_id =  frame_id;

This should still set the default to "base_scan", but should honor the frame_id param from the .launch file.

If desired, I could fork this repository and create a pull request with the proposed change. Also, as a side note, this issue is about the ROS1 variant of this driver and I tested it on ROS Kinetic on a Raspberry Pi 4 B 2GB.

JToolGD commented 2 years ago

Yeah. That's how it's done with the LDS-01 version (starting at the main).

If you want to fix it, I'm sure it would be appreciated. The problem also exists in ros2-devel (I just checked) so it wouldn't completely resolve this issue. However, a fix in ROS1 would already be half the work.

I don't have the actual lidar myself (I'm the one who answered the related question, not asked it) so I won't be able to test it, yet your proposal looks solid.

I'd say go for it, make the fork and create your PR.

AradHajari commented 5 months ago

This should be pretty easy to fix, I will describe my proposal below. I've got to test it a bit more, but so far it seems to be working.

Edit the following file: /ld08_driver/src/ld08_driver.cpp

Insert following between lines 31(ros::NodeHandle nh;) and 32(char topic_name[20]={0};):

ros::NodeHandle priv_nh("~");
std::string frame_id;
priv_nh.param("frame_id", frame_id, std::string("base_scan"));

Replace (on line 62):

scan.header.frame_id = "base_scan";

with:

scan.header.frame_id =  frame_id;

This should still set the default to "base_scan", but should honor the frame_id param from the .launch file.

If desired, I could fork this repository and create a pull request with the proposed change. Also, as a side note, this issue is about the ROS1 variant of this driver and I tested it on ROS Kinetic on a Raspberry Pi 4 B 2GB.

Hi

This should be pretty easy to fix, I will describe my proposal below. I've got to test it a bit more, but so far it seems to be working.

Edit the following file: /ld08_driver/src/ld08_driver.cpp

Insert following between lines 31(ros::NodeHandle nh;) and 32(char topic_name[20]={0};):

ros::NodeHandle priv_nh("~");
std::string frame_id;
priv_nh.param("frame_id", frame_id, std::string("base_scan"));

Replace (on line 62):

scan.header.frame_id = "base_scan";

with:

scan.header.frame_id =  frame_id;

This should still set the default to "base_scan", but should honor the frame_id param from the .launch file.

If desired, I could fork this repository and create a pull request with the proposed change. Also, as a side note, this issue is about the ROS1 variant of this driver and I tested it on ROS Kinetic on a Raspberry Pi 4 B 2GB.

Hi, thank you for your proposed solution, I have encountered exactly the same problem but I cant find the ld08_driver in my turtlebot3_description or packages could you tell me how to find this package or add it manually to my program.