Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef SENSORHANDLERS_HPP_
00035 #define SENSORHANDLERS_HPP_
00036 #include <labust/math/NumberManipulation.hpp>
00037
00038 #include <sensor_msgs/NavSatFix.h>
00039 #include <sensor_msgs/Imu.h>
00040 #include <geometry_msgs/TwistStamped.h>
00041 #include <tf/transform_listener.h>
00042
00043 #include <ros/ros.h>
00044
00045 namespace labust
00046 {
00047 namespace navigation
00048 {
00049
00050 struct NewArrived
00051 {
00052 NewArrived():isNew(false){};
00053
00054 inline bool newArrived()
00055 {
00056 if (isNew)
00057 {
00058 isNew=false;
00059 return true;
00060 }
00061 return false;
00062 }
00063
00064 protected:
00065 bool isNew;
00066 };
00070 class GPSHandler : public NewArrived
00071 {
00072 public:
00073 void configure(ros::NodeHandle& nh);
00074
00075 inline const std::pair<double, double>&
00076 position() const {return posxy;}
00077
00078 inline const std::pair<double, double>&
00079 origin() const {return originLL;}
00080
00081 inline const std::pair<double, double>&
00082 latlon() const {return posLL;}
00083
00084 private:
00085 void onGps(const sensor_msgs::NavSatFix::ConstPtr& data);
00086 std::pair<double, double> posxy, originLL, posLL;
00087 tf::TransformListener listener;
00088 ros::Subscriber gps;
00089 };
00090
00094 class ImuHandler : public NewArrived
00095 {
00096 public:
00097 enum {roll=0, pitch, yaw};
00098 enum {p=0,q,r};
00099 enum {ax,ay,az};
00100
00101 void configure(ros::NodeHandle& nh);
00102
00103 inline const double* orientation() const{return rpy;}
00104
00105 inline const double* rate() const{return pqr;}
00106
00107 inline const double* acc() const{return axyz;}
00108
00109 private:
00110 void onImu(const sensor_msgs::Imu::ConstPtr& data);
00111 tf::TransformListener listener;
00112 labust::math::unwrap unwrap;
00113 ros::Subscriber imu;
00114 double rpy[3], pqr[3], axyz[3];
00115 };
00116
00117 class DvlHandler : public NewArrived
00118 {
00119 public:
00120 enum {u=0,v,w};
00121
00122 DvlHandler():r(0){};
00123
00124 void configure(ros::NodeHandle& nh);
00125
00126 inline const double* body_speeds() const {return uvw;};
00127
00128 inline void current_r(double yaw_rate) {r = yaw_rate;};
00129
00130 private:
00131 void onDvl(const geometry_msgs::TwistStamped::ConstPtr& data);
00132 double uvw[3], r;
00133 ros::Subscriber nu_dvl;
00134 tf::TransformListener listener;
00135 };
00136 }
00137 }
00138
00139 #endif