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 <std_msgs/Bool.h>
00041 #include <geometry_msgs/TwistStamped.h>
00042 #include <tf2_ros/buffer.h>
00043 #include <tf2_ros/transform_listener.h>
00044
00045 #include <ros/ros.h>
00046
00047 #include <Eigen/Dense>
00048
00049 namespace labust
00050 {
00051 namespace navigation
00052 {
00053
00054 struct NewArrived
00055 {
00056 NewArrived():isNew(false){};
00057
00058 inline bool newArrived()
00059 {
00060 if (isNew)
00061 {
00062 isNew=false;
00063 return true;
00064 }
00065 return false;
00066 }
00067
00068 protected:
00069 bool isNew;
00070 };
00074 class GPSHandler : public NewArrived
00075 {
00076 public:
00077 GPSHandler():listener(buffer){};
00078 void configure(ros::NodeHandle& nh);
00079
00080 inline const std::pair<double, double>&
00081 position() const {return posxy;}
00082
00083 inline const std::pair<double, double>&
00084 origin() const {return originLL;}
00085
00086 inline const std::pair<double, double>&
00087 latlon() const {return posLL;}
00088
00089 void setRotation(const Eigen::Quaternion<double>& quat){this->rot = quat;};
00090
00091 private:
00092 void onGps(const sensor_msgs::NavSatFix::ConstPtr& data);
00093 std::pair<double, double> posxy, originLL, posLL;
00094 tf2_ros::Buffer buffer;
00095 tf2_ros::TransformListener listener;
00096 ros::Subscriber gps;
00097 Eigen::Quaternion<double> rot;
00098 };
00099
00103 class ImuHandler : public NewArrived
00104 {
00105 public:
00106 enum {roll=0, pitch, yaw};
00107 enum {p=0,q,r};
00108 enum {ax,ay,az};
00109
00110 ImuHandler():listener(buffer),gps(0){};
00111
00112 void setGpsHandler(GPSHandler* gps){this->gps = gps;};
00113
00114 void configure(ros::NodeHandle& nh);
00115
00116 inline const double* orientation() const{return rpy;}
00117
00118 inline const double* rate() const{return pqr;}
00119
00120 inline const double* acc() const{return axyz;}
00121
00122 private:
00123 void onImu(const sensor_msgs::Imu::ConstPtr& data);
00124 tf2_ros::Buffer buffer;
00125 tf2_ros::TransformListener listener;
00126 labust::math::unwrap unwrap;
00127 ros::Subscriber imu;
00128 double rpy[3], pqr[3], axyz[3];
00129 GPSHandler* gps;
00130 };
00131
00132 class DvlHandler : public NewArrived
00133 {
00134 public:
00135 enum {u=0,v,w};
00136
00137 DvlHandler():r(0),listener(buffer),bottom_lock(false){};
00138
00139 void configure(ros::NodeHandle& nh);
00140
00141 inline const double* body_speeds() const {return uvw;};
00142
00143 inline void current_r(double yaw_rate) {r = yaw_rate;};
00144
00145 private:
00146 void onDvl(const geometry_msgs::TwistStamped::ConstPtr& data);
00147 void onBottomLock(const std_msgs::Bool::ConstPtr& data);
00148 double uvw[3], r;
00149 bool bottom_lock;
00150 ros::Subscriber nu_dvl, dvl_bottom;
00151 tf2_ros::Buffer buffer;
00152 tf2_ros::TransformListener listener;
00153 };
00154 }
00155 }
00156
00157 #endif