laser_scan_publisher.cpp
Go to the documentation of this file.
2 
3 #include "pf_driver/PFR2000Header.h"
4 
5 LaserscanPublisher::LaserscanPublisher(std::shared_ptr<ScanConfig> config, std::shared_ptr<ScanParameters> params,
6  const std::string& scan_topic, const std::string& frame_id)
7  : PFDataPublisher(config, params)
8 {
9  scan_publisher_ = nh_.advertise<sensor_msgs::LaserScan>(scan_topic, 1);
10  header_publisher_ = nh_.advertise<pf_driver::PFR2000Header>("/r2000_header", 1);
11  frame_id_ = frame_id;
12 }
13 
14 void LaserscanPublisher::handle_scan(sensor_msgs::LaserScanPtr msg, uint16_t layer_idx, int layer_inclination,
15  bool apply_correction)
16 {
17  publish_scan(msg);
18 }
19 
20 void LaserscanPublisher::publish_scan(sensor_msgs::LaserScanPtr msg)
21 {
23 }
PFDataPublisher
Definition: pf_data_publisher.h:11
PFDataPublisher::frame_id_
std::string frame_id_
Definition: pf_data_publisher.h:27
LaserscanPublisher::scan_publisher_
ros::Publisher scan_publisher_
Definition: laser_scan_publisher.h:12
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
PFDataPublisher::nh_
ros::NodeHandle nh_
Definition: pf_data_publisher.h:26
laser_scan_publisher.h
LaserscanPublisher::publish_scan
void publish_scan(sensor_msgs::LaserScanPtr msg)
Definition: laser_scan_publisher.cpp:20
LaserscanPublisher::LaserscanPublisher
LaserscanPublisher(std::shared_ptr< ScanConfig > config, std::shared_ptr< ScanParameters > params, const std::string &scan_topic, const std::string &frame_id)
Definition: laser_scan_publisher.cpp:5
LaserscanPublisher::handle_scan
virtual void handle_scan(sensor_msgs::LaserScanPtr msg, uint16_t layer_idx, int layer_inclination, bool apply_correction)
Definition: laser_scan_publisher.cpp:14
PFDataPublisher::header_publisher_
ros::Publisher header_publisher_
Definition: pf_data_publisher.h:28
config
config


pf_driver
Author(s): Harsh Deshpande
autogenerated on Sun Feb 4 2024 03:32:56