$search

hector_pose_estimation::PoseEstimationNode Class Reference

#include <pose_estimation_node.h>

Inheritance diagram for hector_pose_estimation::PoseEstimationNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void cleanup ()
virtual bool init ()
 PoseEstimationNode (const SystemPtr &system=SystemPtr())
virtual void publish ()
virtual void reset ()
virtual ~PoseEstimationNode ()

Protected Member Functions

virtual ros::NodeHandlegetNodeHandle ()
virtual ros::NodeHandlegetPrivateNodeHandle ()
tf::TransformBroadcastergetTransformBroadcaster ()
tf::TransformListenergetTransformListener ()
void gpsCallback (const sensor_msgs::NavSatFixConstPtr &gps, const geometry_msgs::Vector3StampedConstPtr &gps_velocity)
void heightCallback (const geometry_msgs::PointStampedConstPtr &height)
void imuCallback (const sensor_msgs::ImuConstPtr &imu)
void magneticCallback (const geometry_msgs::Vector3StampedConstPtr &magnetic)
void poseupdateCallback (const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
void syscommandCallback (const std_msgs::StringConstPtr &syscommand)
void twistupdateCallback (const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)

Protected Attributes

PoseEstimationpose_estimation_

Private Attributes

ros::Publisher angular_velocity_bias_publisher_
ros::Subscriber baro_subscriber_
ros::Publisher global_publisher_
ros::Publisher gps_pose_publisher_
message_filters::Subscriber
< sensor_msgs::NavSatFix
gps_subscriber_
message_filters::TimeSynchronizer
< sensor_msgs::NavSatFix,
geometry_msgs::Vector3Stamped > * 
gps_synchronizer_
message_filters::Subscriber
< geometry_msgs::Vector3Stamped
gps_velocity_subscriber_
ros::Subscriber height_subscriber_
ros::Publisher imu_publisher_
ros::Subscriber imu_subscriber_
ros::Publisher linear_acceleration_bias_publisher_
ros::Subscriber magnetic_subscriber_
ros::NodeHandle nh_
std::string other_frame_
ros::Publisher pose_publisher_
ros::Subscriber poseupdate_subscriber_
ros::NodeHandle private_nh_
bool publish_world_other_transform_
ros::Publisher state_publisher_
ros::Subscriber syscommand_subscriber_
tf::TransformBroadcaster transform_broadcaster_
tf::TransformListenertransform_listener_
std::vector< tf::StampedTransformtransforms_
ros::Subscriber twistupdate_subscriber_
ros::Publisher velocity_publisher_
bool with_covariances_

Detailed Description

Definition at line 59 of file pose_estimation_node.h.


Constructor & Destructor Documentation

hector_pose_estimation::PoseEstimationNode::PoseEstimationNode ( const SystemPtr system = SystemPtr()  ) 

Definition at line 40 of file pose_estimation_node.cpp.

hector_pose_estimation::PoseEstimationNode::~PoseEstimationNode (  )  [virtual]

Definition at line 56 of file pose_estimation_node.cpp.


Member Function Documentation

void hector_pose_estimation::PoseEstimationNode::cleanup (  )  [virtual]

Definition at line 113 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 258 of file pose_estimation_node.cpp.

tf::TransformListener * hector_pose_estimation::PoseEstimationNode::getTransformListener (  )  [protected]

Definition at line 262 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 154 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::heightCallback ( const geometry_msgs::PointStampedConstPtr height  )  [protected]

Definition at line 139 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::imuCallback ( const sensor_msgs::ImuConstPtr imu  )  [protected]

Definition at line 121 of file pose_estimation_node.cpp.

bool hector_pose_estimation::PoseEstimationNode::init (  )  [virtual]

Definition at line 63 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::magneticCallback ( const geometry_msgs::Vector3StampedConstPtr magnetic  )  [protected]

Definition at line 146 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::poseupdateCallback ( const geometry_msgs::PoseWithCovarianceStampedConstPtr pose  )  [protected]

Definition at line 179 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::publish (  )  [virtual]

Definition at line 195 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::reset (  )  [virtual]

Definition at line 109 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::syscommandCallback ( const std_msgs::StringConstPtr &  syscommand  )  [protected]

Definition at line 187 of file pose_estimation_node.cpp.

void hector_pose_estimation::PoseEstimationNode::twistupdateCallback ( const geometry_msgs::TwistWithCovarianceStampedConstPtr twist  )  [protected]

Definition at line 183 of file pose_estimation_node.cpp.


Member Data Documentation

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 105 of file pose_estimation_node.h.

Definition at line 101 of file pose_estimation_node.h.

Definition at line 103 of file pose_estimation_node.h.

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.

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.

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 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.

Definition at line 110 of file pose_estimation_node.h.

Definition at line 111 of file pose_estimation_node.h.

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.

Definition at line 113 of file pose_estimation_node.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


hector_pose_estimation
Author(s): Johannes Meyer
autogenerated on Tue Mar 5 13:00:54 2013