00001 #ifndef LISTENERS_H 00002 #define LISTENERS_H 00003 00004 #include <control_msgs/JointTrajectoryControllerState.h> 00005 #include <ros/ros.h> 00006 #include <std_msgs/UInt32.h> 00007 #include <ric_board/Battery.h> 00008 #include <sensor_msgs/NavSatFix.h> 00009 #include <actionlib_msgs/GoalStatusArray.h> 00010 #include <sensor_msgs/Imu.h> 00011 #include <sensor_msgs/Image.h> 00012 #include <sensor_msgs/LaserScan.h> 00013 #include <nav_msgs/Odometry.h> 00014 #include <control_msgs/JointTrajectoryControllerState.h> 00015 #include <sensor_msgs/Range.h> 00016 00018 class Listener 00019 { 00020 protected: 00021 long int _signalTime; 00022 00023 public: 00024 Listener(){_signalTime = 0;} 00025 virtual void subscribe() = 0; 00026 long int getLastSignal() {return _signalTime;} 00027 }; 00028 00030 class Arm : public Listener 00031 { 00032 public: 00033 Arm(){}; 00034 void subscribe() 00035 { 00036 _nHandle.param<std::string>("arm_topic",_topicName, "arm_trajectory_controller/state"); 00037 _sub = _nHandle.subscribe(_topicName, 1000, &Arm::_chatterCallback, this); 00038 } 00039 00040 private: 00041 ros::NodeHandle _nHandle; 00042 ros::Subscriber _sub; 00043 std::string _topicName; 00044 00045 void _chatterCallback(const control_msgs::JointTrajectoryControllerState::ConstPtr& msg) {_signalTime = clock();} 00046 }; 00047 00049 class Battery : public Listener 00050 { 00051 public: 00052 00053 Battery() 00054 { 00055 _batPower = 0; 00056 }; 00057 int getBatteryPwr() {return _batPower;} 00058 void subscribe() 00059 { 00060 _nHandle.param<std::string>("battery_topic",_topicName, "battery_monitor"); 00061 _sub = _nHandle.subscribe(_topicName, 1000, &Battery::_chatterCallback, this); 00062 } 00063 00064 private: 00065 ros::NodeHandle _nHandle; 00066 ros::Subscriber _sub; 00067 std::string _topicName; 00068 int _batPower; 00069 void _chatterCallback(const ric_board::Battery::Ptr& msg) 00070 { 00071 if (msg->data > msg->max) 00072 _batPower = 100; 00073 else 00074 _batPower = ( (msg->data - msg->min) / (msg->max - msg->min) ) * 100.0f ; 00075 _signalTime = clock(); 00076 } 00077 }; 00078 00080 class FrontCam : public Listener 00081 { 00082 public: 00083 FrontCam(){}; 00084 void subscribe() 00085 { 00086 _nHandle.param<std::string>("front_cam_topic",_topicName, "front_camera/image_raw"); 00087 _sub = _nHandle.subscribe(_topicName, 1000, &FrontCam::_chatterCallback, this); 00088 } 00089 00090 private: 00091 ros::NodeHandle _nHandle; 00092 ros::Subscriber _sub; 00093 std::string _topicName; 00094 00095 void _chatterCallback(const sensor_msgs::Image::ConstPtr& msg) {_signalTime = clock();} 00096 }; 00097 00099 class Gps : public Listener 00100 { 00101 public: 00102 Gps(){}; 00103 void subscribe() 00104 { 00105 _nHandle.param<std::string>("gps_topic",_topicName, "GPS/fix"); 00106 _sub = _nHandle.subscribe(_topicName, 1000, &Gps::_chatterCallback, this); 00107 } 00108 00109 private: 00110 ros::NodeHandle _nHandle; 00111 ros::Subscriber _sub; 00112 std::string _topicName; 00113 00114 void _chatterCallback(const sensor_msgs::NavSatFix::ConstPtr& msg) {_signalTime = clock();} 00115 }; 00116 00118 class Gripper : public Listener 00119 { 00120 public: 00121 Gripper(){}; 00122 void subscribe() 00123 { 00124 _nHandle.param<std::string>("gripper_topic",_topicName, "gripper_controller/gripper_cmd/status"); 00125 _sub = _nHandle.subscribe(_topicName, 1000, &Gripper::_chatterCallback, this); 00126 } 00127 00128 private: 00129 ros::NodeHandle _nHandle; 00130 ros::Subscriber _sub; 00131 std::string _topicName; 00132 00133 void _chatterCallback(const actionlib_msgs::GoalStatusArray& msg) {_signalTime = clock();} 00134 }; 00135 00137 class Imu : public Listener 00138 { 00139 public: 00140 Imu(){}; 00141 void subscribe() 00142 { 00143 _nHandle.param<std::string>("imu_topic",_topicName, "IMU/data"); 00144 _sub = _nHandle.subscribe(_topicName, 1000, &Imu::_chatterCallback, this); 00145 } 00146 00147 private: 00148 ros::NodeHandle _nHandle; 00149 ros::Subscriber _sub; 00150 std::string _topicName; 00151 00152 void _chatterCallback(const sensor_msgs::Imu::ConstPtr& msg) {_signalTime = clock();} 00153 }; 00154 00156 class Kinect2 : public Listener 00157 { 00158 public: 00159 Kinect2(){}; 00160 void subscribe() 00161 { 00162 _nHandle.param<std::string>("kinect2_topic",_topicName, "kinect2/hd/image_depth_rect"); 00163 _sub = _nHandle.subscribe(_topicName, 1000, &Kinect2::_chatterCallback, this); 00164 } 00165 00166 private: 00167 ros::NodeHandle _nHandle; 00168 ros::Subscriber _sub; 00169 std::string _topicName; 00170 00171 void _chatterCallback(const sensor_msgs::Image::ConstPtr& msg) {_signalTime = clock();} 00172 }; 00173 00175 class Lidar : public Listener 00176 { 00177 public: 00178 Lidar(){}; 00179 void subscribe() 00180 { 00181 _nHandle.param<std::string>("lidar_topic",_topicName, "scan"); 00182 _sub = _nHandle.subscribe(_topicName, 1000, &Lidar::_chatterCallback, this); 00183 } 00184 00185 private: 00186 ros::NodeHandle _nHandle; 00187 ros::Subscriber _sub; 00188 std::string _topicName; 00189 00190 void _chatterCallback(const sensor_msgs::LaserScan::ConstPtr& msg) { _signalTime = clock();} 00191 }; 00192 00194 class Odom : public Listener 00195 { 00196 public: 00197 Odom(){}; 00198 void subscribe() 00199 { 00200 _nHandle.param<std::string>("odom_topic",_topicName, "mobile_base_controller/odom"); 00201 _sub = _nHandle.subscribe(_topicName, 1000, &Odom::_chatterCallback, this); 00202 } 00203 00204 private: 00205 ros::NodeHandle _nHandle; 00206 ros::Subscriber _sub; 00207 std::string _topicName; 00208 00209 void _chatterCallback(const nav_msgs::Odometry::ConstPtr& msg) {_signalTime = clock();} 00210 }; 00211 00213 00214 class PanTilt : public Listener 00215 { 00216 public: 00217 PanTilt(){}; 00218 void subscribe() 00219 { 00220 _nHandle.param<std::string>("pan_tilt_topic",_topicName, "pan_tilt_trajectory_controller/state"); 00221 _sub = _nHandle.subscribe(_topicName, 1000, &PanTilt::_chatterCallback, this); 00222 } 00223 00224 private: 00225 ros::NodeHandle _nHandle; 00226 ros::Subscriber _sub; 00227 std::string _topicName; 00228 00229 void _chatterCallback(const control_msgs::JointTrajectoryControllerState::ConstPtr &msg) {_signalTime = clock();} 00230 }; 00231 00232 00234 class RearCam : public Listener 00235 { 00236 public: 00237 RearCam(){}; 00238 void subscribe() 00239 { 00240 _nHandle.param<std::string>("rear_cam_topic",_topicName, "rear_camera/image_raw"); 00241 _sub = _nHandle.subscribe(_topicName, 1000, &RearCam::_chatterCallback, this); 00242 } 00243 00244 private: 00245 ros::NodeHandle _nHandle; 00246 ros::Subscriber _sub; 00247 std::string _topicName; 00248 00249 void _chatterCallback(const sensor_msgs::Image::ConstPtr& msg) {_signalTime = clock();} 00250 }; 00251 00253 class SR300 : public Listener 00254 { 00255 public: 00256 SR300(){}; 00257 void subscribe() 00258 { 00259 _nHandle.param<std::string>("sr300_topic",_topicName, "sr300/color/image_raw"); 00260 _sub = _nHandle.subscribe(_topicName, 1000, &SR300::_chatterCallback, this); 00261 } 00262 00263 private: 00264 ros::NodeHandle _nHandle; 00265 ros::Subscriber _sub; 00266 std::string _topicName; 00267 00268 void _chatterCallback(const sensor_msgs::Image::ConstPtr& msg) { _signalTime = clock();} 00269 }; 00270 00272 class UrfLeft : public Listener 00273 { 00274 public: 00275 UrfLeft(){}; 00276 void subscribe() 00277 { 00278 _nHandle.param<std::string>("urf_left_topic",_topicName, "URF/left"); 00279 _sub = _nHandle.subscribe(_topicName, 1000, &UrfLeft::_chatterCallback, this); 00280 } 00281 00282 private: 00283 ros::NodeHandle _nHandle; 00284 ros::Subscriber _sub; 00285 std::string _topicName; 00286 00287 void _chatterCallback(const sensor_msgs::Range::ConstPtr& msg) {_signalTime = clock();} 00288 }; 00289 00291 class UrfRear : public Listener 00292 { 00293 public: 00294 UrfRear(){}; 00295 void subscribe() 00296 { 00297 _nHandle.param<std::string>("urf_rear_topic",_topicName, "URF/rear"); 00298 _sub = _nHandle.subscribe(_topicName, 1000, &UrfRear::_chatterCallback, this); 00299 } 00300 00301 private: 00302 00303 ros::NodeHandle _nHandle; 00304 ros::Subscriber _sub; 00305 std::string _topicName; 00306 00307 void _chatterCallback(const sensor_msgs::Range::ConstPtr& msg) { _signalTime = clock();} 00308 }; 00309 00311 class UrfRight : public Listener 00312 { 00313 public: 00314 UrfRight(){}; 00315 void subscribe() 00316 { 00317 _nHandle.param<std::string>("urf_right_topic",_topicName, "URF/right"); 00318 _sub = _nHandle.subscribe(_topicName, 1000, &UrfRight::_chatterCallback, this); 00319 } 00320 00321 private: 00322 ros::NodeHandle _nHandle; 00323 ros::Subscriber _sub; 00324 std::string _topicName; 00325 00326 void _chatterCallback(const sensor_msgs::Range::ConstPtr& msg) {_signalTime = clock();} 00327 }; 00328 00329 #endif //LISTENERS_H