Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Applied frame_id argument #12

Open
wants to merge 3 commits into
base: ros2-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions include/lipkg.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,8 @@ class LiPkg
sensor_msgs::msg::LaserScan GetLaserScan() {return output;}
void setStamp(rclcpp::Time timeStamp) {output.header.stamp = timeStamp;}

void setFrameId(std::string frameId) {frame_id = frameId;}

private:
uint16_t mTimestamp;
double mSpeed;
Expand All @@ -105,6 +107,7 @@ class LiPkg
FrameData mFrameData;
sensor_msgs::msg::LaserScan output;
void ToLaserscan(std::vector < PointData > src);
std::string frame_id;
};

class LD00_LiPkg: public LiPkg
Expand Down
22 changes: 15 additions & 7 deletions launch/ld08.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,23 @@


from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
frame_id = LaunchConfiguration("frame_id", default="base_scan")
namespace = LaunchConfiguration('namespace')

return LaunchDescription([
Node(
package='ld08_driver',
executable='ld08_driver',
name='ld08_driver',
output='screen'),
])
return LaunchDescription(
[
Node(
namespace=namespace,
package="ld08_driver",
executable="ld08_driver",
name="ld08_driver",
parameters=[{"frame_id": frame_id}],
output="screen",
),
]
)
2 changes: 1 addition & 1 deletion src/lipkg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@ void LiPkg::ToLaserscan(std::vector<PointData> src)
// Calculate the number of scanning points
unsigned int beam_size = ceil((angle_max - angle_min) / angle_increment);
// output.header.stamp = rclcpp::Time::now();
output.header.frame_id = "base_scan";
output.header.frame_id = frame_id;
output.angle_min = angle_min;
output.angle_max = angle_max;
output.range_min = range_min;
Expand Down
7 changes: 6 additions & 1 deletion src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,15 @@ int main(int argc, char ** argv)
rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr lidar_pub;

LiPkg * pkg;
std::string product;
std::string product, frame_id;
int32_t ver = 8;
pkg = new LD08_LiPkg;

node->declare_parameter<std::string>("frame_id");
node->get_parameter_or<std::string>("frame_id", frame_id, "base_scan");

pkg->setFrameId(frame_id);

CmdInterfaceLinux cmd_port(ver);
std::vector<std::pair<std::string, std::string>> device_list;
std::string port_name;
Expand Down