pps.h
Go to the documentation of this file.
1 
34 #ifndef MULTISENSE_ROS_PPS_H
35 #define MULTISENSE_ROS_PPS_H
36 
37 #include <boost/shared_ptr.hpp>
38 #include <boost/thread.hpp>
39 #include <ros/ros.h>
40 
41 #include <multisense_lib/MultiSenseChannel.hh>
42 
43 namespace multisense_ros {
44 
45 class Pps {
46 public:
47 
49  ~Pps();
50 
52 
53 private:
54 
55  //
56  // CRL sensor API
57 
59 
60  //
61  // Driver nodes
62 
64 
65  //
66  // PPS publisher
67 
69 
71 
72  //
73  // Publish control
74 
75  int32_t subscribers_;
76  void connect();
77  void disconnect();
78 };
79 
80 }
81 
82 #endif
void disconnect()
Definition: pps.cpp:130
ros::NodeHandle device_nh_
Definition: pps.h:63
void connect()
Definition: pps.cpp:125
crl::multisense::Channel * driver_
Definition: pps.h:58
int32_t subscribers_
Definition: pps.h:75
Pps(crl::multisense::Channel *driver)
Definition: pps.cpp:54
void ppsCallback(const crl::multisense::pps::Header &header)
Definition: pps.cpp:102
ros::Publisher stamped_pps_pub_
Definition: pps.h:70
const std::string header
ros::Publisher pps_pub_
Definition: pps.h:68


multisense_ros
Author(s):
autogenerated on Sat Apr 6 2019 02:16:53