#include <pose_estimation_node.h>
Definition at line 59 of file pose_estimation_node.h.
hector_pose_estimation::PoseEstimationNode::PoseEstimationNode | ( | const SystemPtr & | system = SystemPtr() | ) |
Definition at line 41 of file pose_estimation_node.cpp.
Definition at line 57 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::cleanup | ( | ) | [virtual] |
Definition at line 114 of file pose_estimation_node.cpp.
virtual ros::NodeHandle& hector_pose_estimation::PoseEstimationNode::getNodeHandle | ( | ) | [inline, protected, virtual] |
Definition at line 87 of file pose_estimation_node.h.
virtual ros::NodeHandle& hector_pose_estimation::PoseEstimationNode::getPrivateNodeHandle | ( | ) | [inline, protected, virtual] |
Definition at line 88 of file pose_estimation_node.h.
tf::TransformBroadcaster * hector_pose_estimation::PoseEstimationNode::getTransformBroadcaster | ( | ) | [protected] |
Definition at line 260 of file pose_estimation_node.cpp.
tf::TransformListener * hector_pose_estimation::PoseEstimationNode::getTransformListener | ( | ) | [protected] |
Definition at line 264 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::gpsCallback | ( | const sensor_msgs::NavSatFixConstPtr & | gps, |
const geometry_msgs::Vector3StampedConstPtr & | gps_velocity | ||
) | [protected] |
Definition at line 149 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::heightCallback | ( | const geometry_msgs::PointStampedConstPtr & | height | ) | [protected] |
Definition at line 134 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::imuCallback | ( | const sensor_msgs::ImuConstPtr & | imu | ) | [protected] |
Definition at line 122 of file pose_estimation_node.cpp.
bool hector_pose_estimation::PoseEstimationNode::init | ( | ) | [virtual] |
Definition at line 64 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::magneticCallback | ( | const geometry_msgs::Vector3StampedConstPtr & | magnetic | ) | [protected] |
Definition at line 141 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::poseupdateCallback | ( | const geometry_msgs::PoseWithCovarianceStampedConstPtr & | pose | ) | [protected] |
Definition at line 174 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::publish | ( | ) | [virtual] |
Definition at line 190 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::reset | ( | ) | [virtual] |
Definition at line 110 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::syscommandCallback | ( | const std_msgs::StringConstPtr & | syscommand | ) | [protected] |
Definition at line 182 of file pose_estimation_node.cpp.
void hector_pose_estimation::PoseEstimationNode::twistupdateCallback | ( | const geometry_msgs::TwistWithCovarianceStampedConstPtr & | twist | ) | [protected] |
Definition at line 178 of file pose_estimation_node.cpp.
ros::Publisher hector_pose_estimation::PoseEstimationNode::angular_velocity_bias_publisher_ [private] |
Definition at line 105 of file pose_estimation_node.h.
Definition at line 100 of file pose_estimation_node.h.
Definition at line 104 of file pose_estimation_node.h.
Definition at line 104 of file pose_estimation_node.h.
Definition at line 105 of file pose_estimation_node.h.
message_filters::Subscriber<sensor_msgs::NavSatFix> hector_pose_estimation::PoseEstimationNode::gps_subscriber_ [private] |
Definition at line 101 of file pose_estimation_node.h.
message_filters::TimeSynchronizer<sensor_msgs::NavSatFix,geometry_msgs::Vector3Stamped>* hector_pose_estimation::PoseEstimationNode::gps_synchronizer_ [private] |
Definition at line 103 of file pose_estimation_node.h.
message_filters::Subscriber<geometry_msgs::Vector3Stamped> hector_pose_estimation::PoseEstimationNode::gps_velocity_subscriber_ [private] |
Definition at line 102 of file pose_estimation_node.h.
Definition at line 100 of file pose_estimation_node.h.
Definition at line 104 of file pose_estimation_node.h.
Definition at line 100 of file pose_estimation_node.h.
ros::Publisher hector_pose_estimation::PoseEstimationNode::linear_acceleration_bias_publisher_ [private] |
Definition at line 105 of file pose_estimation_node.h.
Definition at line 100 of file pose_estimation_node.h.
Definition at line 97 of file pose_estimation_node.h.
std::string hector_pose_estimation::PoseEstimationNode::other_frame_ [private] |
Definition at line 115 of file pose_estimation_node.h.
Definition at line 94 of file pose_estimation_node.h.
Definition at line 104 of file pose_estimation_node.h.
Definition at line 106 of file pose_estimation_node.h.
Definition at line 98 of file pose_estimation_node.h.
Definition at line 113 of file pose_estimation_node.h.
Definition at line 114 of file pose_estimation_node.h.
Definition at line 104 of file pose_estimation_node.h.
Definition at line 107 of file pose_estimation_node.h.
tf::TransformBroadcaster hector_pose_estimation::PoseEstimationNode::transform_broadcaster_ [private] |
Definition at line 110 of file pose_estimation_node.h.
Definition at line 111 of file pose_estimation_node.h.
std::vector<tf::StampedTransform> hector_pose_estimation::PoseEstimationNode::transforms_ [private] |
Definition at line 109 of file pose_estimation_node.h.
Definition at line 106 of file pose_estimation_node.h.
Definition at line 104 of file pose_estimation_node.h.