6 #include <dynamic_reconfigure/server.h> 15 #include "pf_driver/PFDriverR2000Config.h" 16 #include "pf_driver/PFDriverR2300Config.h" 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);
27 bool start_transmission(std::shared_ptr<std::mutex> net_mtx, std::shared_ptr<std::condition_variable> net_cv,
40 std::shared_ptr<Reader<PFPacket>>
reader_;
46 std::shared_ptr<HandleInfo>
info_;
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);
74 std::shared_ptr<std::condition_variable> net_cv,
bool& net_fail);
void start_watchdog_timer(float duration)
std::shared_ptr< Reader< PFPacket > > reader_
void change_state(PFState state)
ros::Timer watchdog_timer_
std::shared_ptr< ScanConfig > config_
void feed_watchdog(const ros::TimerEvent &e)
bool start_transmission(std::shared_ptr< std::mutex > net_mtx, std::shared_ptr< std::condition_variable > net_cv, bool &net_fail)
std::shared_ptr< ScanParameters > params_
bool can_change_state(PFState state)
std::shared_ptr< HandleInfo > info_
std::unique_ptr< Transport > transport_
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)
std::unique_ptr< Pipeline > PipelinePtr
void connection_failure_cb()
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)
std::shared_ptr< PFSDPBase > protocol_interface_