pose_estimation_node.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef HECTOR_POSE_ESTIMATION_NODE_H
00030 #define HECTOR_POSE_ESTIMATION_NODE_H
00031 
00032 #include <hector_pose_estimation/pose_estimation.h>
00033 
00034 #include <ros/ros.h>
00035 
00036 #include <sensor_msgs/Imu.h>
00037 #if defined(USE_MAV_MSGS)
00038   #include <mav_msgs/Height.h>
00039 #elif defined(USE_HECTOR_UAV_MSGS)
00040   #include <hector_uav_msgs/Altimeter.h>
00041 #else
00042   #include <geometry_msgs/PointStamped.h>
00043 #endif
00044 #include <sensor_msgs/NavSatFix.h>
00045 #include <geometry_msgs/QuaternionStamped.h>
00046 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00047 #include <geometry_msgs/TwistWithCovarianceStamped.h>
00048 #include <geometry_msgs/Vector3Stamped.h>
00049 #include <nav_msgs/Odometry.h>
00050 #include <std_msgs/String.h>
00051 #include <tf/transform_broadcaster.h>
00052 #include <tf/transform_listener.h>
00053 
00054 #include <message_filters/subscriber.h>
00055 #include <message_filters/time_synchronizer.h>
00056 
00057 namespace hector_pose_estimation {
00058 
00059 class PoseEstimationNode {
00060 public:
00061   PoseEstimationNode(const SystemPtr& system = SystemPtr());
00062   virtual ~PoseEstimationNode();
00063 
00064   virtual bool init();
00065   virtual void reset();
00066   virtual void cleanup();
00067 
00068   virtual void publish();
00069 
00070 protected:
00071   void imuCallback(const sensor_msgs::ImuConstPtr& imu);
00072 
00073 #if defined(USE_MAV_MSGS)
00074   void heightCallback(const mav_msgs::HeightConstPtr& height);
00075 #elif defined(USE_HECTOR_UAV_MSGS)
00076   void baroCallback(const hector_uav_msgs::AltimeterConstPtr& altimeter);
00077 #else
00078   void heightCallback(const geometry_msgs::PointStampedConstPtr& height);
00079 #endif
00080 
00081   void magneticCallback(const geometry_msgs::Vector3StampedConstPtr& magnetic);
00082   void gpsCallback(const sensor_msgs::NavSatFixConstPtr& gps, const geometry_msgs::Vector3StampedConstPtr& gps_velocity);
00083   void poseupdateCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose);
00084   void twistupdateCallback(const geometry_msgs::TwistWithCovarianceStampedConstPtr& twist);
00085   void syscommandCallback(const std_msgs::StringConstPtr& syscommand);
00086 
00087   virtual ros::NodeHandle& getNodeHandle() { return nh_; }
00088   virtual ros::NodeHandle& getPrivateNodeHandle() { return private_nh_; }
00089 
00090   tf::TransformBroadcaster *getTransformBroadcaster();
00091   tf::TransformListener *getTransformListener();
00092 
00093 protected:
00094   PoseEstimation *pose_estimation_;
00095 
00096 private:
00097   ros::NodeHandle nh_;
00098   ros::NodeHandle private_nh_;
00099 
00100   ros::Subscriber imu_subscriber_, baro_subscriber_, height_subscriber_, magnetic_subscriber_;
00101   message_filters::Subscriber<sensor_msgs::NavSatFix> gps_subscriber_;
00102   message_filters::Subscriber<geometry_msgs::Vector3Stamped> gps_velocity_subscriber_;
00103   message_filters::TimeSynchronizer<sensor_msgs::NavSatFix,geometry_msgs::Vector3Stamped> *gps_synchronizer_;
00104   ros::Publisher state_publisher_, pose_publisher_, velocity_publisher_, imu_publisher_, global_publisher_, euler_publisher_;
00105   ros::Publisher angular_velocity_bias_publisher_, linear_acceleration_bias_publisher_, gps_pose_publisher_;
00106   ros::Subscriber poseupdate_subscriber_, twistupdate_subscriber_;
00107   ros::Subscriber syscommand_subscriber_;
00108 
00109   std::vector<tf::StampedTransform> transforms_;
00110   tf::TransformBroadcaster transform_broadcaster_;
00111   tf::TransformListener *transform_listener_;
00112 
00113   bool publish_covariances_;
00114   bool publish_world_other_transform_;
00115   std::string other_frame_;
00116 };
00117 
00118 } // namespace hector_pose_estimation
00119 
00120 #endif // HECTOR_POSE_ESTIMATION_NODE_H


hector_pose_estimation
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:24:34