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 
77 class OdomEstimationNode
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_;
134  MatrixWrapper::SymmetricMatrix odom_covariance_, imu_covariance_, vo_covariance_, gps_covariance_;
135  bool debug_, self_diagnose_;
137 
138  // log files for debugging
140 
141  // counters
143 
144 }; // class
145 
146 }; // namespace
147 
148 #endif
estimation::VoConstPtr
boost::shared_ptr< nav_msgs::Odometry const > VoConstPtr
Definition: odom_estimation_node.h:104
estimation::OdomEstimationNode::base_gps_init_
tf::Transform base_gps_init_
Definition: odom_estimation_node.h:156
estimation::OdomEstimationNode::odom_active_
bool odom_active_
Definition: odom_estimation_node.h:161
wtf.resp
resp
Definition: wtf.py:12
ros::Publisher
estimation::OdomEstimationNode::base_footprint_frame_
std::string base_footprint_frame_
Definition: odom_estimation_node.h:167
boost::shared_ptr
estimation::OdomEstimationNode::gps_covariance_
MatrixWrapper::SymmetricMatrix gps_covariance_
Definition: odom_estimation_node.h:165
estimation::OdomEstimationNode::~OdomEstimationNode
virtual ~OdomEstimationNode()
destructor
Definition: odom_estimation_node.cpp:156
estimation::GpsConstPtr
boost::shared_ptr< nav_msgs::Odometry const > GpsConstPtr
Definition: odom_estimation_node.h:105
estimation::OdomEstimationNode::imu_active_
bool imu_active_
Definition: odom_estimation_node.h:161
estimation::OdomEstimationNode::odom_covariance_
MatrixWrapper::SymmetricMatrix odom_covariance_
Definition: odom_estimation_node.h:165
estimation::VelConstPtr
boost::shared_ptr< geometry_msgs::Twist const > VelConstPtr
Definition: odom_estimation_node.h:106
ros.h
estimation::OdomEstimationNode::odomCallback
void odomCallback(const OdomConstPtr &odom)
callback function for odo data
Definition: odom_estimation_node.cpp:173
estimation::OdomEstimationNode::vo_covariance_
MatrixWrapper::SymmetricMatrix vo_covariance_
Definition: odom_estimation_node.h:165
estimation::OdomEstimationNode::vo_used_
bool vo_used_
Definition: odom_estimation_node.h:162
estimation::OdomEstimationNode::getStatus
bool getStatus(robot_pose_ekf::GetStatus::Request &req, robot_pose_ekf::GetStatus::Response &resp)
get the status of the filter
Definition: odom_estimation_node.cpp:494
estimation::OdomEstimationNode::gps_time_
ros::Time gps_time_
Definition: odom_estimation_node.h:158
estimation::OdomEstimationNode::gps_sub_
ros::Subscriber gps_sub_
Definition: odom_estimation_node.h:140
estimation::OdomEstimationNode::imu_initializing_
bool imu_initializing_
Definition: odom_estimation_node.h:163
estimation::OdomEstimationNode::imu_used_
bool imu_used_
Definition: odom_estimation_node.h:162
estimation::OdomEstimationNode::filter_stamp_
ros::Time filter_stamp_
Definition: odom_estimation_node.h:159
estimation::OdomEstimationNode::vo_init_stamp_
ros::Time vo_init_stamp_
Definition: odom_estimation_node.h:160
estimation::OdomEstimationNode::output_
geometry_msgs::PoseWithCovarianceStamped output_
Definition: odom_estimation_node.h:147
estimation::OdomEstimation
Definition: odom_estimation.h:91
tf::StampedTransform
estimation::OdomEstimationNode::pose_pub_
ros::Publisher pose_pub_
Definition: odom_estimation_node.h:139
estimation::OdomEstimationNode::imu_callback_counter_
unsigned int imu_callback_counter_
Definition: odom_estimation_node.h:173
estimation::OdomEstimationNode::OdomEstimationNode
OdomEstimationNode()
constructor
Definition: odom_estimation_node.cpp:54
transform_broadcaster.h
ros::ServiceServer
estimation::OdomEstimationNode::vo_file_
std::ofstream vo_file_
Definition: odom_estimation_node.h:170
estimation::OdomEstimationNode::vo_callback_counter_
unsigned int vo_callback_counter_
Definition: odom_estimation_node.h:173
estimation::OdomEstimationNode::tf_prefix_
std::string tf_prefix_
Definition: odom_estimation_node.h:167
estimation::ImuConstPtr
boost::shared_ptr< sensor_msgs::Imu const > ImuConstPtr
Definition: odom_estimation_node.h:103
estimation::OdomEstimationNode::vo_stamp_
ros::Time vo_stamp_
Definition: odom_estimation_node.h:159
estimation::OdomEstimationNode::odom_time_
ros::Time odom_time_
Definition: odom_estimation_node.h:158
estimation::OdomEstimationNode::imuCallback
void imuCallback(const ImuConstPtr &imu)
callback function for imu data
Definition: odom_estimation_node.cpp:220
estimation::OdomEstimationNode::odom_broadcaster_
tf::TransformBroadcaster odom_broadcaster_
Definition: odom_estimation_node.h:151
estimation::OdomEstimationNode::corr_file_
std::ofstream corr_file_
Definition: odom_estimation_node.h:170
estimation::OdomEstimationNode::odom_sub_
ros::Subscriber odom_sub_
Definition: odom_estimation_node.h:140
tf::TransformBroadcaster
estimation::OdomEstimationNode::self_diagnose_
bool self_diagnose_
Definition: odom_estimation_node.h:166
estimation::OdomEstimationNode::vo_initializing_
bool vo_initializing_
Definition: odom_estimation_node.h:163
estimation::OdomEstimationNode::base_vo_init_
tf::Transform base_vo_init_
Definition: odom_estimation_node.h:155
odom_estimation.h
estimation::OdomEstimationNode::gps_init_stamp_
ros::Time gps_init_stamp_
Definition: odom_estimation_node.h:160
estimation::OdomEstimationNode::vo_meas_
tf::Transform vo_meas_
Definition: odom_estimation_node.h:154
estimation::OdomEstimationNode::vo_sub_
ros::Subscriber vo_sub_
Definition: odom_estimation_node.h:140
estimation::OdomEstimationNode::vo_time_
ros::Time vo_time_
Definition: odom_estimation_node.h:158
estimation::OdomEstimationNode::imu_covariance_
MatrixWrapper::SymmetricMatrix imu_covariance_
Definition: odom_estimation_node.h:165
estimation::OdomEstimationNode::node_
ros::NodeHandle node_
Definition: odom_estimation_node.h:137
estimation::OdomEstimationNode::odom_init_stamp_
ros::Time odom_init_stamp_
Definition: odom_estimation_node.h:160
estimation::OdomEstimationNode::imu_stamp_
ros::Time imu_stamp_
Definition: odom_estimation_node.h:159
estimation::OdomEstimationNode::time_file_
std::ofstream time_file_
Definition: odom_estimation_node.h:170
estimation::OdomEstimationNode::odom_meas_
tf::Transform odom_meas_
Definition: odom_estimation_node.h:154
estimation::OdomEstimationNode::odom_used_
bool odom_used_
Definition: odom_estimation_node.h:162
estimation::OdomEstimationNode::extra_file_
std::ofstream extra_file_
Definition: odom_estimation_node.h:170
estimation::OdomEstimationNode::timeout_
double timeout_
Definition: odom_estimation_node.h:164
ros::TimerEvent
tf::Transform
estimation::OdomEstimationNode::voCallback
void voCallback(const VoConstPtr &vo)
callback function for vo data
Definition: odom_estimation_node.cpp:291
estimation::OdomEstimationNode::imu_file_
std::ofstream imu_file_
Definition: odom_estimation_node.h:170
estimation::OdomEstimationNode::odom_file_
std::ofstream odom_file_
Definition: odom_estimation_node.h:170
estimation::OdomEstimationNode::gps_stamp_
ros::Time gps_stamp_
Definition: odom_estimation_node.h:159
estimation::OdomEstimationNode::camera_base_
tf::StampedTransform camera_base_
Definition: odom_estimation_node.h:157
estimation::OdomEstimationNode::vo_active_
bool vo_active_
Definition: odom_estimation_node.h:161
transform_listener.h
tf.h
estimation::OdomEstimationNode::gps_active_
bool gps_active_
Definition: odom_estimation_node.h:161
estimation::OdomEstimationNode::state_srv_
ros::ServiceServer state_srv_
Definition: odom_estimation_node.h:141
ros::Time
estimation::OdomEstimationNode::imu_init_stamp_
ros::Time imu_init_stamp_
Definition: odom_estimation_node.h:160
estimation::OdomEstimationNode::imu_time_
ros::Time imu_time_
Definition: odom_estimation_node.h:158
tf::TransformListener
estimation::OdomEstimationNode::gps_file_
std::ofstream gps_file_
Definition: odom_estimation_node.h:170
estimation::OdomEstimationNode::my_filter_
OdomEstimation my_filter_
Definition: odom_estimation_node.h:144
estimation::OdomEstimationNode::odom_stamp_
ros::Time odom_stamp_
Definition: odom_estimation_node.h:159
estimation::OdomEstimationNode::gps_callback_counter_
unsigned int gps_callback_counter_
Definition: odom_estimation_node.h:173
estimation::OdomConstPtr
boost::shared_ptr< nav_msgs::Odometry const > OdomConstPtr
Definition: odom_estimation_node.h:102
estimation::OdomEstimationNode::gpsCallback
void gpsCallback(const GpsConstPtr &gps)
callback function for vo data
Definition: odom_estimation_node.cpp:332
estimation::OdomEstimationNode::spin
void spin(const ros::TimerEvent &e)
the mail filter loop that will be called periodically
Definition: odom_estimation_node.cpp:380
estimation::OdomEstimationNode::debug_
bool debug_
Definition: odom_estimation_node.h:166
estimation
Definition: odom_estimation.h:57
estimation::OdomEstimationNode::imu_sub_
ros::Subscriber imu_sub_
Definition: odom_estimation_node.h:140
estimation::OdomEstimationNode::gps_used_
bool gps_used_
Definition: odom_estimation_node.h:162
estimation::OdomEstimationNode::odom_initializing_
bool odom_initializing_
Definition: odom_estimation_node.h:163
estimation::OdomEstimationNode::timer_
ros::Timer timer_
Definition: odom_estimation_node.h:138
estimation::OdomEstimationNode::imu_meas_
tf::Transform imu_meas_
Definition: odom_estimation_node.h:154
estimation::OdomEstimationNode::robot_state_
tf::TransformListener robot_state_
Definition: odom_estimation_node.h:150
estimation::OdomEstimationNode::output_frame_
std::string output_frame_
Definition: odom_estimation_node.h:167
estimation::OdomEstimationNode::ekf_sent_counter_
unsigned int ekf_sent_counter_
Definition: odom_estimation_node.h:173
ros::Timer
estimation::OdomEstimationNode::gps_meas_
tf::Transform gps_meas_
Definition: odom_estimation_node.h:154
estimation::OdomEstimationNode::gps_initializing_
bool gps_initializing_
Definition: odom_estimation_node.h:163
ros::NodeHandle
ros::Subscriber
estimation::OdomEstimationNode::odom_callback_counter_
unsigned int odom_callback_counter_
Definition: odom_estimation_node.h:173


robot_pose_ekf
Author(s): Wim Meeussen
autogenerated on Wed Mar 2 2022 00:50:47