pf_data_publisher.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <deque>
4 #include <mutex>
5 
6 #include <ros/ros.h>
7 #include <sensor_msgs/LaserScan.h>
8 
10 
12 {
13 public:
14  PFDataPublisher(std::shared_ptr<ScanConfig> config, std::shared_ptr<ScanParameters> params);
15 
16  virtual void read(PFR2000Packet_A& packet);
17  virtual void read(PFR2000Packet_B& packet);
18  virtual void read(PFR2000Packet_C& packet);
19  virtual void read(PFR2300Packet_C1& packet);
20 
21  virtual bool start();
22 
23  virtual bool stop();
24 
25 protected:
27  std::string frame_id_;
29  std::deque<sensor_msgs::LaserScanPtr> d_queue_;
30  std::mutex q_mutex_;
31 
32  std::shared_ptr<ScanConfig> config_;
33  std::shared_ptr<ScanParameters> params_;
34 
35  bool check_status(uint32_t status_flags);
36 
37  template <typename T>
38  void to_msg_queue(T& packet, uint16_t layer_idx = 0, int layer_inclination = 0);
39  virtual void handle_scan(sensor_msgs::LaserScanPtr msg, uint16_t layer_idx, int layer_inclination,
40  bool apply_correction = true) = 0;
41 
42  virtual void resetCurrentScans()
43  {
44  }
45 };
PFDataPublisher::q_mutex_
std::mutex q_mutex_
Definition: pf_data_publisher.h:30
PFDataPublisher::d_queue_
std::deque< sensor_msgs::LaserScanPtr > d_queue_
Definition: pf_data_publisher.h:29
ros::Publisher
PFDataPublisher
Definition: pf_data_publisher.h:11
PFDataPublisher::frame_id_
std::string frame_id_
Definition: pf_data_publisher.h:27
ros.h
PFDataPublisher::nh_
ros::NodeHandle nh_
Definition: pf_data_publisher.h:26
PFDataPublisher::read
virtual void read(PFR2000Packet_A &packet)
Definition: pf_data_publisher.cpp:16
PFR2000Packet_C
Definition: pf_r2000_packet_c.h:5
PFR2300Packet_C1
Definition: pf_r2300_packet_c1.h:5
PFDataPublisher::resetCurrentScans
virtual void resetCurrentScans()
Definition: pf_data_publisher.h:42
PFDataPublisher::check_status
bool check_status(uint32_t status_flags)
Definition: pf_data_publisher.cpp:136
PFR2000Packet_A
Definition: pf_r2000_packet_a.h:5
PFDataPublisher::start
virtual bool start()
Definition: pf_data_publisher.cpp:40
PFDataPublisher::params_
std::shared_ptr< ScanParameters > params_
Definition: pf_data_publisher.h:33
PFDataPublisher::PFDataPublisher
PFDataPublisher(std::shared_ptr< ScanConfig > config, std::shared_ptr< ScanParameters > params)
Definition: pf_data_publisher.cpp:11
pf_packet_reader.h
PFDataPublisher::handle_scan
virtual void handle_scan(sensor_msgs::LaserScanPtr msg, uint16_t layer_idx, int layer_inclination, bool apply_correction=true)=0
PFR2000Packet_B
Definition: pf_r2000_packet_b.h:5
PFDataPublisher::to_msg_queue
void to_msg_queue(T &packet, uint16_t layer_idx=0, int layer_inclination=0)
Definition: pf_data_publisher.cpp:54
PFDataPublisher::stop
virtual bool stop()
Definition: pf_data_publisher.cpp:45
PFDataPublisher::config_
std::shared_ptr< ScanConfig > config_
Definition: pf_data_publisher.h:32
PFDataPublisher::header_publisher_
ros::Publisher header_publisher_
Definition: pf_data_publisher.h:28
PFPacketReader
Definition: pf_packet_reader.h:11
config
config
ros::NodeHandle


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