Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
PFInterface Class Reference

#include <pf_interface.h>

Public Member Functions

bool init (std::shared_ptr< HandleInfo > info, std::shared_ptr< ScanConfig > config, std::shared_ptr< ScanParameters > params, const std::string &topic, const std::string &frame_id, const uint16_t num_layers)
 
 PFInterface ()
 
bool start_transmission (std::shared_ptr< std::mutex > net_mtx, std::shared_ptr< std::condition_variable > net_cv, bool &net_fail)
 
void stop_transmission ()
 
void terminate ()
 

Private Types

enum  PFState {
  PFState::UNINIT, PFState::INIT, PFState::RUNNING, PFState::SHUTDOWN,
  PFState::ERROR
}
 
using PipelinePtr = std::unique_ptr< Pipeline >
 

Private Member Functions

bool can_change_state (PFState state)
 
void change_state (PFState state)
 
void connection_failure_cb ()
 
void feed_watchdog (const ros::TimerEvent &e)
 
PipelinePtr get_pipeline (const std::string &packet_type, std::shared_ptr< std::mutex > net_mtx, std::shared_ptr< std::condition_variable > net_cv, bool &net_fail)
 
bool handle_version (int major_version, int minor_version, int device_family, const std::string &topic, const std::string &frame_id, const uint16_t num_layers)
 
bool init ()
 
void on_shutdown ()
 
void start_watchdog_timer (float duration)
 

Private Attributes

std::shared_ptr< ScanConfigconfig_
 
std::string frame_id_
 
std::shared_ptr< HandleInfoinfo_
 
ros::NodeHandle nh_
 
uint16_t num_layers_
 
std::shared_ptr< ScanParametersparams_
 
PipelinePtr pipeline_
 
std::string prev_handle_
 
std::string product_
 
std::shared_ptr< PFSDPBaseprotocol_interface_
 
std::shared_ptr< Reader< PFPacket > > reader_
 
PFState state_
 
std::string topic_
 
std::unique_ptr< Transporttransport_
 
ros::Timer watchdog_timer_
 

Detailed Description

Definition at line 18 of file pf_interface.h.

Member Typedef Documentation

◆ PipelinePtr

using PFInterface::PipelinePtr = std::unique_ptr<Pipeline>
private

Definition at line 33 of file pf_interface.h.

Member Enumeration Documentation

◆ PFState

enum PFInterface::PFState
strongprivate
Enumerator
UNINIT 
INIT 
RUNNING 
SHUTDOWN 
ERROR 

Definition at line 51 of file pf_interface.h.

Constructor & Destructor Documentation

◆ PFInterface()

PFInterface::PFInterface ( )

Definition at line 12 of file pf_interface.cpp.

Member Function Documentation

◆ can_change_state()

bool PFInterface::can_change_state ( PFState  state)
private

Definition at line 123 of file pf_interface.cpp.

◆ change_state()

void PFInterface::change_state ( PFState  state)
private

Definition at line 103 of file pf_interface.cpp.

◆ connection_failure_cb()

void PFInterface::connection_failure_cb ( )
private

Definition at line 197 of file pf_interface.cpp.

◆ feed_watchdog()

void PFInterface::feed_watchdog ( const ros::TimerEvent e)
private

Definition at line 186 of file pf_interface.cpp.

◆ get_pipeline()

std::unique_ptr< Pipeline > PFInterface::get_pipeline ( const std::string &  packet_type,
std::shared_ptr< std::mutex >  net_mtx,
std::shared_ptr< std::condition_variable >  net_cv,
bool &  net_fail 
)
private

Definition at line 255 of file pf_interface.cpp.

◆ handle_version()

bool PFInterface::handle_version ( int  major_version,
int  minor_version,
int  device_family,
const std::string &  topic,
const std::string &  frame_id,
const uint16_t  num_layers 
)
private

Definition at line 210 of file pf_interface.cpp.

◆ init() [1/2]

bool PFInterface::init ( )
private

Definition at line 173 of file pf_interface.cpp.

◆ init() [2/2]

bool PFInterface::init ( std::shared_ptr< HandleInfo info,
std::shared_ptr< ScanConfig config,
std::shared_ptr< ScanParameters params,
const std::string &  topic,
const std::string &  frame_id,
const uint16_t  num_layers 
)

Definition at line 16 of file pf_interface.cpp.

◆ on_shutdown()

void PFInterface::on_shutdown ( )
private

Definition at line 191 of file pf_interface.cpp.

◆ start_transmission()

bool PFInterface::start_transmission ( std::shared_ptr< std::mutex >  net_mtx,
std::shared_ptr< std::condition_variable >  net_cv,
bool &  net_fail 
)

Definition at line 128 of file pf_interface.cpp.

◆ start_watchdog_timer()

void PFInterface::start_watchdog_timer ( float  duration)
private

Definition at line 178 of file pf_interface.cpp.

◆ stop_transmission()

void PFInterface::stop_transmission ( )

Definition at line 150 of file pf_interface.cpp.

◆ terminate()

void PFInterface::terminate ( )

Definition at line 160 of file pf_interface.cpp.

Member Data Documentation

◆ config_

std::shared_ptr<ScanConfig> PFInterface::config_
private

Definition at line 47 of file pf_interface.h.

◆ frame_id_

std::string PFInterface::frame_id_
private

Definition at line 42 of file pf_interface.h.

◆ info_

std::shared_ptr<HandleInfo> PFInterface::info_
private

Definition at line 46 of file pf_interface.h.

◆ nh_

ros::NodeHandle PFInterface::nh_
private

Definition at line 35 of file pf_interface.h.

◆ num_layers_

uint16_t PFInterface::num_layers_
private

Definition at line 43 of file pf_interface.h.

◆ params_

std::shared_ptr<ScanParameters> PFInterface::params_
private

Definition at line 48 of file pf_interface.h.

◆ pipeline_

PipelinePtr PFInterface::pipeline_
private

Definition at line 39 of file pf_interface.h.

◆ prev_handle_

std::string PFInterface::prev_handle_
private

Definition at line 49 of file pf_interface.h.

◆ product_

std::string PFInterface::product_
private

Definition at line 44 of file pf_interface.h.

◆ protocol_interface_

std::shared_ptr<PFSDPBase> PFInterface::protocol_interface_
private

Definition at line 38 of file pf_interface.h.

◆ reader_

std::shared_ptr<Reader<PFPacket> > PFInterface::reader_
private

Definition at line 40 of file pf_interface.h.

◆ state_

PFState PFInterface::state_
private

Definition at line 59 of file pf_interface.h.

◆ topic_

std::string PFInterface::topic_
private

Definition at line 41 of file pf_interface.h.

◆ transport_

std::unique_ptr<Transport> PFInterface::transport_
private

Definition at line 37 of file pf_interface.h.

◆ watchdog_timer_

ros::Timer PFInterface::watchdog_timer_
private

Definition at line 36 of file pf_interface.h.


The documentation for this class was generated from the following files:


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