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> 104 bool getStatus(robot_pose_ekf::GetStatus::Request& req, robot_pose_ekf::GetStatus::Response&
resp);
116 geometry_msgs::PoseWithCovarianceStamped
output_;
void spin(const ros::TimerEvent &e)
the mail filter loop that will be called periodically
OdomEstimation my_filter_
OdomEstimationNode()
constructor
boost::shared_ptr< nav_msgs::Odometry const > VoConstPtr
virtual ~OdomEstimationNode()
destructor
unsigned int vo_callback_counter_
MatrixWrapper::SymmetricMatrix odom_covariance_
tf::Transform base_gps_init_
boost::shared_ptr< sensor_msgs::Imu const > ImuConstPtr
unsigned int imu_callback_counter_
std::string base_footprint_frame_
bool getStatus(robot_pose_ekf::GetStatus::Request &req, robot_pose_ekf::GetStatus::Response &resp)
get the status of the filter
geometry_msgs::PoseWithCovarianceStamped output_
ros::Time odom_init_stamp_
void odomCallback(const OdomConstPtr &odom)
callback function for odo data
MatrixWrapper::SymmetricMatrix vo_covariance_
std::ofstream extra_file_
tf::TransformBroadcaster odom_broadcaster_
void voCallback(const VoConstPtr &vo)
callback function for vo data
tf::Transform base_vo_init_
void imuCallback(const ImuConstPtr &imu)
callback function for imu data
MatrixWrapper::SymmetricMatrix imu_covariance_
ros::Time gps_init_stamp_
unsigned int ekf_sent_counter_
ros::Subscriber odom_sub_
tf::TransformListener robot_state_
tf::StampedTransform camera_base_
boost::shared_ptr< nav_msgs::Odometry const > GpsConstPtr
unsigned int gps_callback_counter_
ros::ServiceServer state_srv_
ros::Time imu_init_stamp_
MatrixWrapper::SymmetricMatrix gps_covariance_
void gpsCallback(const GpsConstPtr &gps)
callback function for vo data
std::string output_frame_
unsigned int odom_callback_counter_
boost::shared_ptr< geometry_msgs::Twist const > VelConstPtr
boost::shared_ptr< nav_msgs::Odometry const > OdomConstPtr