Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
laserscan_transformer.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 
5 #pragma GCC diagnostic push
6 #pragma GCC diagnostic ignored "-Wfloat-equal"
7 #pragma GCC diagnostic ignored "-Wdouble-promotion"
8 #include <laser_geometry/laser_geometry.h>
9 #include <tf/transform_listener.h>
10 #pragma GCC diagnostic pop
11 
12 constexpr const char* TOPIC_LASER_SCAN = "/racer/laser/scan";
13 constexpr const char* TOPIC_LASER_SCAN_POINTCLOUD = "/racer/laser/tf_pointcloud";
14 constexpr const char* MODEL_BASE_LINK = "base_link";
15 
25 {
26  public:
28 
29  private:
30  ros::NodeHandle m_node_handle;
31  ros::Subscriber m_laserscan_subscriber;
32  ros::Publisher m_pointcloud_publisher;
33  laser_geometry::LaserProjection m_projector;
34  tf::TransformListener m_listener;
35 
36  void scanCallback(const sensor_msgs::LaserScan::ConstPtr& laserscan);
37 };
This converter class converts a 2D laser scan as defined by sensor_msgs/LaserScan into a point cloud ...
constexpr const char * MODEL_BASE_LINK
constexpr const char * TOPIC_LASER_SCAN
constexpr const char * TOPIC_LASER_SCAN_POINTCLOUD