Go to the documentation of this file.00001
00034 #ifndef MULTISENSE_ROS_STATUS_H
00035 #define MULTISENSE_ROS_STATUS_H
00036
00037 #include <boost/shared_ptr.hpp>
00038 #include <boost/thread.hpp>
00039 #include <ros/ros.h>
00040
00041 #include <multisense_lib/MultiSenseChannel.hh>
00042
00043 namespace multisense_ros {
00044
00045 class Status {
00046 public:
00047
00048 Status(crl::multisense::Channel* driver);
00049 ~Status();
00050
00051 private:
00052
00053
00054
00055
00056 crl::multisense::Channel* driver_;
00057
00058
00059
00060
00061 ros::NodeHandle device_nh_;
00062
00063
00064
00065
00066 ros::Publisher status_pub_;
00067
00068
00069
00070
00071 ros::Timer status_timer_;
00072
00073
00074
00075
00076 void queryStatus(const ros::TimerEvent& event);
00077
00078
00079
00080
00081
00082 int32_t subscribers_;
00083 void connect();
00084 void disconnect();
00085
00086 };
00087
00088 }
00089
00090 #endif
00091