Public Member Functions | Private Member Functions | Private Attributes
estimation::OdomEstimationNode Class Reference

#include <odom_estimation_node.h>

List of all members.

Public Member Functions

 OdomEstimationNode ()
 constructor
virtual ~OdomEstimationNode ()
 destructor

Private Member Functions

bool getStatus (robot_pose_ekf::GetStatus::Request &req, robot_pose_ekf::GetStatus::Response &resp)
 get the status of the filter
void gpsCallback (const GpsConstPtr &gps)
 callback function for vo data
void imuCallback (const ImuConstPtr &imu)
 callback function for imu data
void odomCallback (const OdomConstPtr &odom)
 callback function for odo data
void spin (const ros::TimerEvent &e)
 the mail filter loop that will be called periodically
void voCallback (const VoConstPtr &vo)
 callback function for vo data

Private Attributes

std::string base_footprint_frame_
tf::Transform base_gps_init_
tf::Transform base_vo_init_
tf::StampedTransform camera_base_
std::ofstream corr_file_
bool debug_
unsigned int ekf_sent_counter_
std::ofstream extra_file_
ros::Time filter_stamp_
bool gps_active_
unsigned int gps_callback_counter_
MatrixWrapper::SymmetricMatrix gps_covariance_
std::ofstream gps_file_
ros::Time gps_init_stamp_
bool gps_initializing_
tf::Transform gps_meas_
ros::Time gps_stamp_
ros::Subscriber gps_sub_
ros::Time gps_time_
bool gps_used_
bool imu_active_
unsigned int imu_callback_counter_
MatrixWrapper::SymmetricMatrix imu_covariance_
std::ofstream imu_file_
ros::Time imu_init_stamp_
bool imu_initializing_
tf::Transform imu_meas_
ros::Time imu_stamp_
ros::Subscriber imu_sub_
ros::Time imu_time_
bool imu_used_
OdomEstimation my_filter_
ros::NodeHandle node_
bool odom_active_
tf::TransformBroadcaster odom_broadcaster_
unsigned int odom_callback_counter_
MatrixWrapper::SymmetricMatrix odom_covariance_
std::ofstream odom_file_
ros::Time odom_init_stamp_
bool odom_initializing_
tf::Transform odom_meas_
ros::Time odom_stamp_
ros::Subscriber odom_sub_
ros::Time odom_time_
bool odom_used_
geometry_msgs::PoseWithCovarianceStamped output_
std::string output_frame_
ros::Publisher pose_pub_
tf::TransformListener robot_state_
bool self_diagnose_
ros::ServiceServer state_srv_
std::string tf_prefix_
std::ofstream time_file_
double timeout_
ros::Timer timer_
bool vo_active_
unsigned int vo_callback_counter_
MatrixWrapper::SymmetricMatrix vo_covariance_
std::ofstream vo_file_
ros::Time vo_init_stamp_
bool vo_initializing_
tf::Transform vo_meas_
ros::Time vo_stamp_
ros::Subscriber vo_sub_
ros::Time vo_time_
bool vo_used_

Detailed Description

Definition at line 77 of file odom_estimation_node.h.


Constructor & Destructor Documentation

constructor

Definition at line 54 of file odom_estimation_node.cpp.

destructor

Definition at line 156 of file odom_estimation_node.cpp.


Member Function Documentation

bool estimation::OdomEstimationNode::getStatus ( robot_pose_ekf::GetStatus::Request &  req,
robot_pose_ekf::GetStatus::Response &  resp 
) [private]

get the status of the filter

Definition at line 472 of file odom_estimation_node.cpp.

callback function for vo data

Definition at line 332 of file odom_estimation_node.cpp.

callback function for imu data

Definition at line 220 of file odom_estimation_node.cpp.

callback function for odo data

Definition at line 173 of file odom_estimation_node.cpp.

the mail filter loop that will be called periodically

Definition at line 372 of file odom_estimation_node.cpp.

callback function for vo data

Definition at line 291 of file odom_estimation_node.cpp.


Member Data Documentation

Definition at line 136 of file odom_estimation_node.h.

Definition at line 125 of file odom_estimation_node.h.

Definition at line 124 of file odom_estimation_node.h.

Definition at line 126 of file odom_estimation_node.h.

Definition at line 139 of file odom_estimation_node.h.

Definition at line 135 of file odom_estimation_node.h.

Definition at line 142 of file odom_estimation_node.h.

Definition at line 139 of file odom_estimation_node.h.

Definition at line 128 of file odom_estimation_node.h.

Definition at line 130 of file odom_estimation_node.h.

Definition at line 142 of file odom_estimation_node.h.

MatrixWrapper::SymmetricMatrix estimation::OdomEstimationNode::gps_covariance_ [private]

Definition at line 134 of file odom_estimation_node.h.

Definition at line 139 of file odom_estimation_node.h.

Definition at line 129 of file odom_estimation_node.h.

Definition at line 132 of file odom_estimation_node.h.

Definition at line 123 of file odom_estimation_node.h.

Definition at line 128 of file odom_estimation_node.h.

Definition at line 109 of file odom_estimation_node.h.

Definition at line 127 of file odom_estimation_node.h.

Definition at line 131 of file odom_estimation_node.h.

Definition at line 130 of file odom_estimation_node.h.

Definition at line 142 of file odom_estimation_node.h.

MatrixWrapper::SymmetricMatrix estimation::OdomEstimationNode::imu_covariance_ [private]

Definition at line 134 of file odom_estimation_node.h.

Definition at line 139 of file odom_estimation_node.h.

Definition at line 129 of file odom_estimation_node.h.

Definition at line 132 of file odom_estimation_node.h.

Definition at line 123 of file odom_estimation_node.h.

Definition at line 128 of file odom_estimation_node.h.

Definition at line 109 of file odom_estimation_node.h.

Definition at line 127 of file odom_estimation_node.h.

Definition at line 131 of file odom_estimation_node.h.

Definition at line 113 of file odom_estimation_node.h.

Definition at line 106 of file odom_estimation_node.h.

Definition at line 130 of file odom_estimation_node.h.

Definition at line 120 of file odom_estimation_node.h.

Definition at line 142 of file odom_estimation_node.h.

MatrixWrapper::SymmetricMatrix estimation::OdomEstimationNode::odom_covariance_ [private]

Definition at line 134 of file odom_estimation_node.h.

Definition at line 139 of file odom_estimation_node.h.

Definition at line 129 of file odom_estimation_node.h.

Definition at line 132 of file odom_estimation_node.h.

Definition at line 123 of file odom_estimation_node.h.

Definition at line 128 of file odom_estimation_node.h.

Definition at line 109 of file odom_estimation_node.h.

Definition at line 127 of file odom_estimation_node.h.

Definition at line 131 of file odom_estimation_node.h.

geometry_msgs::PoseWithCovarianceStamped estimation::OdomEstimationNode::output_ [private]

Definition at line 116 of file odom_estimation_node.h.

Definition at line 136 of file odom_estimation_node.h.

Definition at line 108 of file odom_estimation_node.h.

Definition at line 119 of file odom_estimation_node.h.

Definition at line 135 of file odom_estimation_node.h.

Definition at line 110 of file odom_estimation_node.h.

Definition at line 136 of file odom_estimation_node.h.

Definition at line 139 of file odom_estimation_node.h.

Definition at line 133 of file odom_estimation_node.h.

Definition at line 107 of file odom_estimation_node.h.

Definition at line 130 of file odom_estimation_node.h.

Definition at line 142 of file odom_estimation_node.h.

MatrixWrapper::SymmetricMatrix estimation::OdomEstimationNode::vo_covariance_ [private]

Definition at line 134 of file odom_estimation_node.h.

Definition at line 139 of file odom_estimation_node.h.

Definition at line 129 of file odom_estimation_node.h.

Definition at line 132 of file odom_estimation_node.h.

Definition at line 123 of file odom_estimation_node.h.

Definition at line 128 of file odom_estimation_node.h.

Definition at line 109 of file odom_estimation_node.h.

Definition at line 127 of file odom_estimation_node.h.

Definition at line 131 of file odom_estimation_node.h.


The documentation for this class was generated from the following files:


robot_pose_ekf
Author(s): Wim Meeussen, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:07:38