odom_estimation_node.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * notice, this list of conditions and the following disclaimer.
12 * * Redistributions in binary form must reproduce the above
13 * copyright notice, this list of conditions and the following
14 * disclaimer in the documentation and/or other materials provided
15 * with the distribution.
16 * * Neither the name of the Willow Garage nor the names of its
17 * contributors may be used to endorse or promote products derived
18 * from this software without specific prior written permission.
19 *
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 * POSSIBILITY OF SUCH DAMAGE.
32 *********************************************************************/
33 
34 /* Author: Wim Meeussen */
35 
36 #ifndef __ODOM_ESTIMATION_NODE__
37 #define __ODOM_ESTIMATION_NODE__
38 
39 // ros stuff
40 #include <ros/ros.h>
41 #include <tf/tf.h>
42 #include <tf/transform_listener.h>
44 #include "odom_estimation.h"
45 #include <robot_pose_ekf/GetStatus.h>
46 
47 // messages
48 #include "nav_msgs/Odometry.h"
49 #include "geometry_msgs/Twist.h"
50 #include "sensor_msgs/Imu.h"
51 #include "geometry_msgs/PoseStamped.h"
52 #include "geometry_msgs/PoseWithCovarianceStamped.h"
53 
54 #include <boost/thread/mutex.hpp>
55 
56 // log files
57 #include <fstream>
58 
59 namespace estimation
60 {
61 
76 
78 {
79 public:
82 
84  virtual ~OdomEstimationNode();
85 
86 private:
88  void spin(const ros::TimerEvent& e);
89 
91  void odomCallback(const OdomConstPtr& odom);
92 
94  void imuCallback(const ImuConstPtr& imu);
95 
97  void voCallback(const VoConstPtr& vo);
98 
100  void gpsCallback(const GpsConstPtr& gps);
101 
102 
104  bool getStatus(robot_pose_ekf::GetStatus::Request& req, robot_pose_ekf::GetStatus::Response& resp);
105 
111 
112  // ekf filter
114 
115  // estimated robot pose message to send
116  geometry_msgs::PoseWithCovarianceStamped output_;
117 
118  // robot state
121 
122  // vectors
133  double timeout_;
137 
138  // log files for debugging
140 
141  // counters
143 
144 }; // class
145 
146 }; // namespace
147 
148 #endif
void spin(const ros::TimerEvent &e)
the mail filter loop that will be called periodically
resp
Definition: wtf.py:12
boost::shared_ptr< nav_msgs::Odometry const > VoConstPtr
MatrixWrapper::SymmetricMatrix odom_covariance_
boost::shared_ptr< sensor_msgs::Imu const > ImuConstPtr
bool getStatus(robot_pose_ekf::GetStatus::Request &req, robot_pose_ekf::GetStatus::Response &resp)
get the status of the filter
geometry_msgs::PoseWithCovarianceStamped output_
void odomCallback(const OdomConstPtr &odom)
callback function for odo data
MatrixWrapper::SymmetricMatrix vo_covariance_
tf::TransformBroadcaster odom_broadcaster_
void voCallback(const VoConstPtr &vo)
callback function for vo data
void imuCallback(const ImuConstPtr &imu)
callback function for imu data
MatrixWrapper::SymmetricMatrix imu_covariance_
boost::shared_ptr< nav_msgs::Odometry const > GpsConstPtr
MatrixWrapper::SymmetricMatrix gps_covariance_
void gpsCallback(const GpsConstPtr &gps)
callback function for vo data
boost::shared_ptr< geometry_msgs::Twist const > VelConstPtr
boost::shared_ptr< nav_msgs::Odometry const > OdomConstPtr


robot_pose_ekf
Author(s): Wim Meeussen, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:38