SensorHandlers.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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 /* SENSORHANDLERS_HPP_ */
00157 #endif


labust_navigation
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:33