Go to the documentation of this file.
36 #ifndef __ODOM_ESTIMATION_NODE__
37 #define __ODOM_ESTIMATION_NODE__
45 #include <robot_pose_ekf/GetStatus.h>
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"
54 #include <boost/thread/mutex.hpp>
77 class OdomEstimationNode
104 bool getStatus(robot_pose_ekf::GetStatus::Request& req, robot_pose_ekf::GetStatus::Response&
resp);
116 geometry_msgs::PoseWithCovarianceStamped
output_;
boost::shared_ptr< nav_msgs::Odometry const > VoConstPtr
tf::Transform base_gps_init_
std::string base_footprint_frame_
MatrixWrapper::SymmetricMatrix gps_covariance_
virtual ~OdomEstimationNode()
destructor
boost::shared_ptr< nav_msgs::Odometry const > GpsConstPtr
MatrixWrapper::SymmetricMatrix odom_covariance_
boost::shared_ptr< geometry_msgs::Twist const > VelConstPtr
void odomCallback(const OdomConstPtr &odom)
callback function for odo data
MatrixWrapper::SymmetricMatrix vo_covariance_
bool getStatus(robot_pose_ekf::GetStatus::Request &req, robot_pose_ekf::GetStatus::Response &resp)
get the status of the filter
geometry_msgs::PoseWithCovarianceStamped output_
unsigned int imu_callback_counter_
OdomEstimationNode()
constructor
unsigned int vo_callback_counter_
boost::shared_ptr< sensor_msgs::Imu const > ImuConstPtr
void imuCallback(const ImuConstPtr &imu)
callback function for imu data
tf::TransformBroadcaster odom_broadcaster_
ros::Subscriber odom_sub_
tf::Transform base_vo_init_
ros::Time gps_init_stamp_
MatrixWrapper::SymmetricMatrix imu_covariance_
ros::Time odom_init_stamp_
std::ofstream extra_file_
void voCallback(const VoConstPtr &vo)
callback function for vo data
tf::StampedTransform camera_base_
ros::ServiceServer state_srv_
ros::Time imu_init_stamp_
OdomEstimation my_filter_
unsigned int gps_callback_counter_
boost::shared_ptr< nav_msgs::Odometry const > OdomConstPtr
void gpsCallback(const GpsConstPtr &gps)
callback function for vo data
void spin(const ros::TimerEvent &e)
the mail filter loop that will be called periodically
tf::TransformListener robot_state_
std::string output_frame_
unsigned int ekf_sent_counter_
unsigned int odom_callback_counter_
robot_pose_ekf
Author(s): Wim Meeussen
autogenerated on Wed Mar 2 2022 00:50:47