#include <pf_data_publisher.h>
|
bool | check_status (uint32_t status_flags) |
|
virtual void | handle_scan (sensor_msgs::LaserScanPtr msg, uint16_t layer_idx, int layer_inclination, bool apply_correction=true)=0 |
|
virtual void | resetCurrentScans () |
|
template<typename T > |
void | to_msg_queue (T &packet, uint16_t layer_idx=0, int layer_inclination=0) |
|
Definition at line 11 of file pf_data_publisher.h.
◆ PFDataPublisher()
◆ check_status()
bool PFDataPublisher::check_status |
( |
uint32_t |
status_flags | ) |
|
|
protected |
◆ handle_scan()
virtual void PFDataPublisher::handle_scan |
( |
sensor_msgs::LaserScanPtr |
msg, |
|
|
uint16_t |
layer_idx, |
|
|
int |
layer_inclination, |
|
|
bool |
apply_correction = true |
|
) |
| |
|
protectedpure virtual |
◆ read() [1/4]
◆ read() [2/4]
◆ read() [3/4]
◆ read() [4/4]
◆ resetCurrentScans()
virtual void PFDataPublisher::resetCurrentScans |
( |
| ) |
|
|
inlineprotectedvirtual |
◆ start()
bool PFDataPublisher::start |
( |
| ) |
|
|
virtual |
◆ stop()
bool PFDataPublisher::stop |
( |
| ) |
|
|
virtual |
◆ to_msg_queue()
template<typename T >
void PFDataPublisher::to_msg_queue |
( |
T & |
packet, |
|
|
uint16_t |
layer_idx = 0 , |
|
|
int |
layer_inclination = 0 |
|
) |
| |
|
protected |
◆ config_
std::shared_ptr<ScanConfig> PFDataPublisher::config_ |
|
protected |
◆ d_queue_
std::deque<sensor_msgs::LaserScanPtr> PFDataPublisher::d_queue_ |
|
protected |
◆ frame_id_
std::string PFDataPublisher::frame_id_ |
|
protected |
◆ header_publisher_
◆ nh_
◆ params_
◆ q_mutex_
std::mutex PFDataPublisher::q_mutex_ |
|
protected |
The documentation for this class was generated from the following files: