Public Member Functions | Private Member Functions | Private Attributes | List of all members
estimation::OdomEstimationNode Class Reference

#include <odom_estimation_node.h>

Public Member Functions

 OdomEstimationNode ()
 constructor More...
 
virtual ~OdomEstimationNode ()
 destructor More...
 

Private Member Functions

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

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

estimation::OdomEstimationNode::OdomEstimationNode ( )

constructor

Definition at line 54 of file odom_estimation_node.cpp.

estimation::OdomEstimationNode::~OdomEstimationNode ( )
virtual

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 494 of file odom_estimation_node.cpp.

void estimation::OdomEstimationNode::gpsCallback ( const GpsConstPtr gps)
private

callback function for vo data

Definition at line 332 of file odom_estimation_node.cpp.

void estimation::OdomEstimationNode::imuCallback ( const ImuConstPtr imu)
private

callback function for imu data

Definition at line 220 of file odom_estimation_node.cpp.

void estimation::OdomEstimationNode::odomCallback ( const OdomConstPtr odom)
private

callback function for odo data

Definition at line 173 of file odom_estimation_node.cpp.

void estimation::OdomEstimationNode::spin ( const ros::TimerEvent e)
private

the mail filter loop that will be called periodically

Definition at line 380 of file odom_estimation_node.cpp.

void estimation::OdomEstimationNode::voCallback ( const VoConstPtr vo)
private

callback function for vo data

Definition at line 291 of file odom_estimation_node.cpp.

Member Data Documentation

std::string estimation::OdomEstimationNode::base_footprint_frame_
private

Definition at line 136 of file odom_estimation_node.h.

tf::Transform estimation::OdomEstimationNode::base_gps_init_
private

Definition at line 125 of file odom_estimation_node.h.

tf::Transform estimation::OdomEstimationNode::base_vo_init_
private

Definition at line 124 of file odom_estimation_node.h.

tf::StampedTransform estimation::OdomEstimationNode::camera_base_
private

Definition at line 126 of file odom_estimation_node.h.

std::ofstream estimation::OdomEstimationNode::corr_file_
private

Definition at line 139 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::debug_
private

Definition at line 135 of file odom_estimation_node.h.

unsigned int estimation::OdomEstimationNode::ekf_sent_counter_
private

Definition at line 142 of file odom_estimation_node.h.

std::ofstream estimation::OdomEstimationNode::extra_file_
private

Definition at line 139 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::filter_stamp_
private

Definition at line 128 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::gps_active_
private

Definition at line 130 of file odom_estimation_node.h.

unsigned int estimation::OdomEstimationNode::gps_callback_counter_
private

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.

std::ofstream estimation::OdomEstimationNode::gps_file_
private

Definition at line 139 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::gps_init_stamp_
private

Definition at line 129 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::gps_initializing_
private

Definition at line 132 of file odom_estimation_node.h.

tf::Transform estimation::OdomEstimationNode::gps_meas_
private

Definition at line 123 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::gps_stamp_
private

Definition at line 128 of file odom_estimation_node.h.

ros::Subscriber estimation::OdomEstimationNode::gps_sub_
private

Definition at line 109 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::gps_time_
private

Definition at line 127 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::gps_used_
private

Definition at line 131 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::imu_active_
private

Definition at line 130 of file odom_estimation_node.h.

unsigned int estimation::OdomEstimationNode::imu_callback_counter_
private

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.

std::ofstream estimation::OdomEstimationNode::imu_file_
private

Definition at line 139 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::imu_init_stamp_
private

Definition at line 129 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::imu_initializing_
private

Definition at line 132 of file odom_estimation_node.h.

tf::Transform estimation::OdomEstimationNode::imu_meas_
private

Definition at line 123 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::imu_stamp_
private

Definition at line 128 of file odom_estimation_node.h.

ros::Subscriber estimation::OdomEstimationNode::imu_sub_
private

Definition at line 109 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::imu_time_
private

Definition at line 127 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::imu_used_
private

Definition at line 131 of file odom_estimation_node.h.

OdomEstimation estimation::OdomEstimationNode::my_filter_
private

Definition at line 113 of file odom_estimation_node.h.

ros::NodeHandle estimation::OdomEstimationNode::node_
private

Definition at line 106 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::odom_active_
private

Definition at line 130 of file odom_estimation_node.h.

tf::TransformBroadcaster estimation::OdomEstimationNode::odom_broadcaster_
private

Definition at line 120 of file odom_estimation_node.h.

unsigned int estimation::OdomEstimationNode::odom_callback_counter_
private

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.

std::ofstream estimation::OdomEstimationNode::odom_file_
private

Definition at line 139 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::odom_init_stamp_
private

Definition at line 129 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::odom_initializing_
private

Definition at line 132 of file odom_estimation_node.h.

tf::Transform estimation::OdomEstimationNode::odom_meas_
private

Definition at line 123 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::odom_stamp_
private

Definition at line 128 of file odom_estimation_node.h.

ros::Subscriber estimation::OdomEstimationNode::odom_sub_
private

Definition at line 109 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::odom_time_
private

Definition at line 127 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::odom_used_
private

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.

std::string estimation::OdomEstimationNode::output_frame_
private

Definition at line 136 of file odom_estimation_node.h.

ros::Publisher estimation::OdomEstimationNode::pose_pub_
private

Definition at line 108 of file odom_estimation_node.h.

tf::TransformListener estimation::OdomEstimationNode::robot_state_
private

Definition at line 119 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::self_diagnose_
private

Definition at line 135 of file odom_estimation_node.h.

ros::ServiceServer estimation::OdomEstimationNode::state_srv_
private

Definition at line 110 of file odom_estimation_node.h.

std::string estimation::OdomEstimationNode::tf_prefix_
private

Definition at line 136 of file odom_estimation_node.h.

std::ofstream estimation::OdomEstimationNode::time_file_
private

Definition at line 139 of file odom_estimation_node.h.

double estimation::OdomEstimationNode::timeout_
private

Definition at line 133 of file odom_estimation_node.h.

ros::Timer estimation::OdomEstimationNode::timer_
private

Definition at line 107 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::vo_active_
private

Definition at line 130 of file odom_estimation_node.h.

unsigned int estimation::OdomEstimationNode::vo_callback_counter_
private

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.

std::ofstream estimation::OdomEstimationNode::vo_file_
private

Definition at line 139 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::vo_init_stamp_
private

Definition at line 129 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::vo_initializing_
private

Definition at line 132 of file odom_estimation_node.h.

tf::Transform estimation::OdomEstimationNode::vo_meas_
private

Definition at line 123 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::vo_stamp_
private

Definition at line 128 of file odom_estimation_node.h.

ros::Subscriber estimation::OdomEstimationNode::vo_sub_
private

Definition at line 109 of file odom_estimation_node.h.

ros::Time estimation::OdomEstimationNode::vo_time_
private

Definition at line 127 of file odom_estimation_node.h.

bool estimation::OdomEstimationNode::vo_used_
private

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 Jan 21 2021 04:05:38