hector_pose_estimation_rtt.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, Johannes Meyer and Martin Nowara, 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_RTT_H
00030 #define HECTOR_POSE_ESTIMATION_RTT_H
00031 
00032 #include <hector_pose_estimation/pose_estimation.h>
00033 
00034 #include <rtt/TaskContext.hpp>
00035 #include <rtt/InputPort.hpp>
00036 #include <rtt/OutputPort.hpp>
00037 
00038 #include <sensor_msgs/typekit/Imu.h>
00039 
00040 #include <nav_msgs/typekit/Odometry.h>
00041 #include <geometry_msgs/typekit/PoseStamped.h>
00042 #include <geometry_msgs/typekit/Vector3Stamped.h>
00043 #ifdef USE_MAV_MSGS
00044   #include <mav_msgs/Height.h>
00045 #else
00046   #include <geometry_msgs/typekit/PointStamped.h>
00047 #endif
00048 #include <geometry_msgs/typekit/PoseWithCovarianceStamped.h>
00049 #include <sensor_msgs/typekit/NavSatFix.h>
00050 #include <std_msgs/String.h>
00051 
00052 #include <ros/ros.h>
00053 
00054 namespace hector_pose_estimation {
00055 
00056 class PoseEstimationTaskContext : public RTT::TaskContext, PoseEstimation {
00057 public:
00058   PoseEstimationTaskContext(const std::string& name = "PoseEsimation", const SystemPtr& system = SystemPtr());
00059   virtual ~PoseEstimationTaskContext();
00060 
00061   void updateOutputs();
00062   void reset();
00063 
00064   using TaskCore::cleanup;
00065 
00066 protected:
00067   bool configureHook();
00068   void cleanupHook();
00069 
00070   bool startHook();
00071   void stopHook();
00072 
00073   void updateHook();
00074 
00075   void commandCallback(RTT::base::PortInterface *);
00076 
00077 private:
00078   RTT::InputPort<sensor_msgs::Imu> imu_input_;
00079   sensor_msgs::Imu imu_in_;
00080 
00081   RTT::InputPort<geometry_msgs::PoseWithCovarianceStamped> pose_update_input_;
00082   geometry_msgs::PoseWithCovarianceStamped pose_update_;
00083 
00084   RTT::InputPort<geometry_msgs::Vector3Stamped> magnetic_input_;
00085   geometry_msgs::Vector3Stamped magnetic_;
00086 
00087 #ifdef USE_MAV_MSGS
00088   RTT::InputPort<mav_msgs::Height> height_input_;
00089   mav_msgs::Height height_;
00090 #else
00091   RTT::InputPort<geometry_msgs::PointStamped> height_input_;
00092   geometry_msgs::PointStamped height_;
00093 #endif
00094 
00095   RTT::InputPort<sensor_msgs::NavSatFix> gps_input_;
00096   RTT::InputPort<geometry_msgs::Vector3Stamped> gps_velocity_input_;
00097   sensor_msgs::NavSatFix gps_;
00098   geometry_msgs::Vector3Stamped gps_velocity_;
00099 
00100   RTT::OutputPort<nav_msgs::Odometry> state_output_;
00101   nav_msgs::Odometry state_;
00102 
00103   RTT::OutputPort<sensor_msgs::Imu> imu_output_;
00104   sensor_msgs::Imu imu_out_;
00105 
00106   RTT::OutputPort<geometry_msgs::PoseStamped> pose_output_;
00107   geometry_msgs::PoseStamped pose_;
00108 
00109   RTT::OutputPort<geometry_msgs::Vector3Stamped> velocity_output_;
00110   geometry_msgs::Vector3Stamped velocity_;
00111 
00112   RTT::OutputPort<sensor_msgs::NavSatFix> global_position_output_;
00113   sensor_msgs::NavSatFix global_position_;
00114 
00115   RTT::OutputPort<geometry_msgs::Vector3Stamped> angular_velocity_bias_output_, linear_acceleration_bias_output_;
00116   geometry_msgs::Vector3Stamped angular_velocity_bias_;
00117   geometry_msgs::Vector3Stamped linear_acceleration_bias_;
00118 
00119   RTT::InputPort<std_msgs::String> command_input_;
00120 
00121   ros::NodeHandle node_handle_;
00122   std::string param_namespace_;
00123 };
00124 
00125 } // namespace hector_pose_estimation
00126 
00127 #endif // HECTOR_POSE_ESTIMATION_RTT_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


hector_pose_estimation_rtt
Author(s): Johannes Meyer
autogenerated on Sun Jun 2 2013 11:34:21