pf_interface.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <string>
4 #include <memory>
5 #include <future>
6 #include <dynamic_reconfigure/server.h>
7 
11 #include "pf_driver/pf/pipeline.h"
15 #include "pf_driver/PFDriverR2000Config.h"
16 #include "pf_driver/PFDriverR2300Config.h"
17 
19 {
20 public:
21  PFInterface();
22 
23  bool init(std::shared_ptr<HandleInfo> info, std::shared_ptr<ScanConfig> config,
24  std::shared_ptr<ScanParameters> params, const std::string& topic, const std::string& frame_id,
25  const uint16_t num_layers);
26 
27  bool start_transmission(std::shared_ptr<std::mutex> net_mtx, std::shared_ptr<std::condition_variable> net_cv,
28  bool& net_fail);
29  void stop_transmission();
30  void terminate();
31 
32 private:
33  using PipelinePtr = std::unique_ptr<Pipeline>;
34 
37  std::unique_ptr<Transport> transport_;
38  std::shared_ptr<PFSDPBase> protocol_interface_;
40  std::shared_ptr<Reader<PFPacket>> reader_;
41  std::string topic_;
42  std::string frame_id_;
43  uint16_t num_layers_;
44  std::string product_;
45 
46  std::shared_ptr<HandleInfo> info_;
47  std::shared_ptr<ScanConfig> config_;
48  std::shared_ptr<ScanParameters> params_;
49  std::string prev_handle_;
50 
51  enum class PFState
52  {
53  UNINIT,
54  INIT,
55  RUNNING,
56  SHUTDOWN,
57  ERROR
58  };
60 
61  bool init();
62 
63  void change_state(PFState state);
64  bool can_change_state(PFState state);
65 
66  void start_watchdog_timer(float duration);
67  void feed_watchdog(const ros::TimerEvent& e); // timer based
68  void on_shutdown();
69 
70  // factory functions
71  bool handle_version(int major_version, int minor_version, int device_family, const std::string& topic,
72  const std::string& frame_id, const uint16_t num_layers);
73  PipelinePtr get_pipeline(const std::string& packet_type, std::shared_ptr<std::mutex> net_mtx,
74  std::shared_ptr<std::condition_variable> net_cv, bool& net_fail);
75  void connection_failure_cb();
76 };
PFInterface::watchdog_timer_
ros::Timer watchdog_timer_
Definition: pf_interface.h:36
PFInterface::PFState
PFState
Definition: pf_interface.h:51
pipeline.h
PFInterface::start_watchdog_timer
void start_watchdog_timer(float duration)
Definition: pf_interface.cpp:178
PFInterface::reader_
std::shared_ptr< Reader< PFPacket > > reader_
Definition: pf_interface.h:40
PFInterface::PFState::ERROR
@ ERROR
PFInterface::feed_watchdog
void feed_watchdog(const ros::TimerEvent &e)
Definition: pf_interface.cpp:186
PFInterface::PFInterface
PFInterface()
Definition: pf_interface.cpp:12
PFInterface::num_layers_
uint16_t num_layers_
Definition: pf_interface.h:43
PFInterface::nh_
ros::NodeHandle nh_
Definition: pf_interface.h:35
PFInterface::on_shutdown
void on_shutdown()
Definition: pf_interface.cpp:191
PFInterface::terminate
void terminate()
Definition: pf_interface.cpp:160
PFInterface::init
bool init()
Definition: pf_interface.cpp:173
PFInterface::PFState::SHUTDOWN
@ SHUTDOWN
PFInterface::frame_id_
std::string frame_id_
Definition: pf_interface.h:42
PFInterface::start_transmission
bool start_transmission(std::shared_ptr< std::mutex > net_mtx, std::shared_ptr< std::condition_variable > net_cv, bool &net_fail)
Definition: pf_interface.cpp:128
PFInterface
Definition: pf_interface.h:18
PFInterface::config_
std::shared_ptr< ScanConfig > config_
Definition: pf_interface.h:47
pfsdp_2000.h
PFInterface::PFState::INIT
@ INIT
PFInterface::info_
std::shared_ptr< HandleInfo > info_
Definition: pf_interface.h:46
ros::TimerEvent
PFInterface::params_
std::shared_ptr< ScanParameters > params_
Definition: pf_interface.h:48
PFInterface::topic_
std::string topic_
Definition: pf_interface.h:41
PFInterface::prev_handle_
std::string prev_handle_
Definition: pf_interface.h:49
pf_packet_reader.h
PFInterface::state_
PFState state_
Definition: pf_interface.h:59
pf_parser.h
PFInterface::PipelinePtr
std::unique_ptr< Pipeline > PipelinePtr
Definition: pf_interface.h:33
PFInterface::can_change_state
bool can_change_state(PFState state)
Definition: pf_interface.cpp:123
PFInterface::handle_version
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)
Definition: pf_interface.cpp:210
PFInterface::PFState::UNINIT
@ UNINIT
pfsdp_2300.h
transport.h
PFInterface::connection_failure_cb
void connection_failure_cb()
Definition: pf_interface.cpp:197
PFInterface::pipeline_
PipelinePtr pipeline_
Definition: pf_interface.h:39
PFInterface::stop_transmission
void stop_transmission()
Definition: pf_interface.cpp:150
PFInterface::get_pipeline
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)
Definition: pf_interface.cpp:255
PFInterface::product_
std::string product_
Definition: pf_interface.h:44
PFInterface::protocol_interface_
std::shared_ptr< PFSDPBase > protocol_interface_
Definition: pf_interface.h:38
config
config
ros::Timer
PFInterface::transport_
std::unique_ptr< Transport > transport_
Definition: pf_interface.h:37
PFInterface::change_state
void change_state(PFState state)
Definition: pf_interface.cpp:103
PFInterface::PFState::RUNNING
@ RUNNING
ros::NodeHandle
pf_writer.h


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