Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
hector_pose_estimation::PoseEstimationNode Class Reference

#include <pose_estimation_node.h>

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

Public Member Functions

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

Protected Member Functions

void ahrsCallback (const sensor_msgs::ImuConstPtr &ahrs)
 
virtual ros::NodeHandlegetNodeHandle ()
 
virtual ros::NodeHandlegetPrivateNodeHandle ()
 
tf::TransformBroadcastergetTransformBroadcaster ()
 
tf::TransformListenergetTransformListener ()
 
void globalReferenceUpdated ()
 
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 publishWorldNavTransform (const ros::TimerEvent &=ros::TimerEvent())
 
void rollpitchCallback (const sensor_msgs::ImuConstPtr &attitude)
 
void syscommandCallback (const std_msgs::StringConstPtr &syscommand)
 
void twistupdateCallback (const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
 

Protected Attributes

ros::Subscriber ahrs_subscriber_
 
ros::Publisher angular_velocity_bias_publisher_
 
ros::Publisher euler_publisher_
 
ros::Publisher geopose_publisher_
 
ros::Publisher global_fix_publisher_
 
ros::Publisher global_reference_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_
 
PoseEstimationpose_estimation_
 
ros::Publisher pose_publisher_
 
ros::Subscriber poseupdate_subscriber_
 
ros::NodeHandle private_nh_
 
bool publish_covariances_
 
bool publish_world_nav_transform_
 
ros::Duration publish_world_nav_transform_period_
 
ros::Timer publish_world_nav_transform_timer_
 
bool publish_world_other_transform_
 
ros::Subscriber rollpitch_subscriber_
 
geometry_msgs::PoseStamped sensor_pose_
 
double sensor_pose_pitch_
 
ros::Publisher sensor_pose_publisher_
 
double sensor_pose_roll_
 
double sensor_pose_yaw_
 
ros::Publisher state_publisher_
 
ros::Subscriber syscommand_subscriber_
 
std::string tf_prefix_
 
ros::Publisher timing_publisher_
 
tf::TransformBroadcaster transform_broadcaster_
 
tf::TransformListenertransform_listener_
 
std::vector< tf::StampedTransformtransforms_
 
ros::Subscriber twistupdate_subscriber_
 
ros::Publisher velocity_publisher_
 
geometry_msgs::TransformStamped world_nav_transform_
 
bool world_nav_transform_updated_
 
bool world_nav_transform_valid_
 

Detailed Description

Definition at line 59 of file pose_estimation_node.h.

Constructor & Destructor Documentation

◆ PoseEstimationNode()

hector_pose_estimation::PoseEstimationNode::PoseEstimationNode ( const SystemPtr system = SystemPtr(),
const StatePtr state = StatePtr() 
)

Definition at line 47 of file pose_estimation_node.cpp.

◆ ~PoseEstimationNode()

hector_pose_estimation::PoseEstimationNode::~PoseEstimationNode ( )
virtual

Definition at line 67 of file pose_estimation_node.cpp.

Member Function Documentation

◆ ahrsCallback()

void hector_pose_estimation::PoseEstimationNode::ahrsCallback ( const sensor_msgs::ImuConstPtr &  ahrs)
protected

Definition at line 186 of file pose_estimation_node.cpp.

◆ cleanup()

void hector_pose_estimation::PoseEstimationNode::cleanup ( )
virtual

Definition at line 161 of file pose_estimation_node.cpp.

◆ getNodeHandle()

virtual ros::NodeHandle& hector_pose_estimation::PoseEstimationNode::getNodeHandle ( )
inlineprotectedvirtual

Definition at line 93 of file pose_estimation_node.h.

◆ getPrivateNodeHandle()

virtual ros::NodeHandle& hector_pose_estimation::PoseEstimationNode::getPrivateNodeHandle ( )
inlineprotectedvirtual

Definition at line 94 of file pose_estimation_node.h.

◆ getTransformBroadcaster()

tf::TransformBroadcaster * hector_pose_estimation::PoseEstimationNode::getTransformBroadcaster ( )
protected

Definition at line 415 of file pose_estimation_node.cpp.

◆ getTransformListener()

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

Definition at line 419 of file pose_estimation_node.cpp.

◆ globalReferenceUpdated()

void hector_pose_estimation::PoseEstimationNode::globalReferenceUpdated ( )
protected

Definition at line 299 of file pose_estimation_node.cpp.

◆ gpsCallback()

void hector_pose_estimation::PoseEstimationNode::gpsCallback ( const sensor_msgs::NavSatFixConstPtr &  gps,
const geometry_msgs::Vector3StampedConstPtr &  gps_velocity 
)
protected

Definition at line 234 of file pose_estimation_node.cpp.

◆ heightCallback()

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

Definition at line 207 of file pose_estimation_node.cpp.

◆ imuCallback()

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

Definition at line 171 of file pose_estimation_node.cpp.

◆ init()

bool hector_pose_estimation::PoseEstimationNode::init ( )
virtual

Definition at line 74 of file pose_estimation_node.cpp.

◆ magneticCallback()

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

Definition at line 220 of file pose_estimation_node.cpp.

◆ poseupdateCallback()

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

Definition at line 270 of file pose_estimation_node.cpp.

◆ publish()

void hector_pose_estimation::PoseEstimationNode::publish ( )
virtual

Definition at line 320 of file pose_estimation_node.cpp.

◆ publishWorldNavTransform()

void hector_pose_estimation::PoseEstimationNode::publishWorldNavTransform ( const ros::TimerEvent = ros::TimerEvent())
protected

Definition at line 308 of file pose_estimation_node.cpp.

◆ reset()

void hector_pose_estimation::PoseEstimationNode::reset ( )
virtual

Definition at line 152 of file pose_estimation_node.cpp.

◆ rollpitchCallback()

void hector_pose_estimation::PoseEstimationNode::rollpitchCallback ( const sensor_msgs::ImuConstPtr &  attitude)
protected

Definition at line 193 of file pose_estimation_node.cpp.

◆ syscommandCallback()

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

Definition at line 291 of file pose_estimation_node.cpp.

◆ twistupdateCallback()

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

Definition at line 287 of file pose_estimation_node.cpp.

Member Data Documentation

◆ ahrs_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::ahrs_subscriber_
protected

Definition at line 105 of file pose_estimation_node.h.

◆ angular_velocity_bias_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::angular_velocity_bias_publisher_
protected

Definition at line 110 of file pose_estimation_node.h.

◆ euler_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::euler_publisher_
protected

Definition at line 109 of file pose_estimation_node.h.

◆ geopose_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::geopose_publisher_
protected

Definition at line 109 of file pose_estimation_node.h.

◆ global_fix_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::global_fix_publisher_
protected

Definition at line 109 of file pose_estimation_node.h.

◆ global_reference_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::global_reference_publisher_
protected

Definition at line 113 of file pose_estimation_node.h.

◆ gps_pose_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::gps_pose_publisher_
protected

Definition at line 110 of file pose_estimation_node.h.

◆ gps_subscriber_

message_filters::Subscriber<sensor_msgs::NavSatFix> hector_pose_estimation::PoseEstimationNode::gps_subscriber_
protected

Definition at line 106 of file pose_estimation_node.h.

◆ gps_synchronizer_

message_filters::TimeSynchronizer<sensor_msgs::NavSatFix,geometry_msgs::Vector3Stamped>* hector_pose_estimation::PoseEstimationNode::gps_synchronizer_
protected

Definition at line 108 of file pose_estimation_node.h.

◆ gps_velocity_subscriber_

message_filters::Subscriber<geometry_msgs::Vector3Stamped> hector_pose_estimation::PoseEstimationNode::gps_velocity_subscriber_
protected

Definition at line 107 of file pose_estimation_node.h.

◆ height_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::height_subscriber_
protected

Definition at line 105 of file pose_estimation_node.h.

◆ imu_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::imu_publisher_
protected

Definition at line 109 of file pose_estimation_node.h.

◆ imu_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::imu_subscriber_
protected

Definition at line 105 of file pose_estimation_node.h.

◆ linear_acceleration_bias_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::linear_acceleration_bias_publisher_
protected

Definition at line 110 of file pose_estimation_node.h.

◆ magnetic_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::magnetic_subscriber_
protected

Definition at line 105 of file pose_estimation_node.h.

◆ nh_

ros::NodeHandle hector_pose_estimation::PoseEstimationNode::nh_
protected

Definition at line 102 of file pose_estimation_node.h.

◆ other_frame_

std::string hector_pose_estimation::PoseEstimationNode::other_frame_
protected

Definition at line 123 of file pose_estimation_node.h.

◆ pose_estimation_

PoseEstimation* hector_pose_estimation::PoseEstimationNode::pose_estimation_
protected

Definition at line 100 of file pose_estimation_node.h.

◆ pose_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::pose_publisher_
protected

Definition at line 109 of file pose_estimation_node.h.

◆ poseupdate_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::poseupdate_subscriber_
protected

Definition at line 111 of file pose_estimation_node.h.

◆ private_nh_

ros::NodeHandle hector_pose_estimation::PoseEstimationNode::private_nh_
protected

Definition at line 103 of file pose_estimation_node.h.

◆ publish_covariances_

bool hector_pose_estimation::PoseEstimationNode::publish_covariances_
protected

Definition at line 121 of file pose_estimation_node.h.

◆ publish_world_nav_transform_

bool hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_
protected

Definition at line 125 of file pose_estimation_node.h.

◆ publish_world_nav_transform_period_

ros::Duration hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_period_
protected

Definition at line 128 of file pose_estimation_node.h.

◆ publish_world_nav_transform_timer_

ros::Timer hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_timer_
protected

Definition at line 127 of file pose_estimation_node.h.

◆ publish_world_other_transform_

bool hector_pose_estimation::PoseEstimationNode::publish_world_other_transform_
protected

Definition at line 122 of file pose_estimation_node.h.

◆ rollpitch_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::rollpitch_subscriber_
protected

Definition at line 105 of file pose_estimation_node.h.

◆ sensor_pose_

geometry_msgs::PoseStamped hector_pose_estimation::PoseEstimationNode::sensor_pose_
protected

Definition at line 131 of file pose_estimation_node.h.

◆ sensor_pose_pitch_

double hector_pose_estimation::PoseEstimationNode::sensor_pose_pitch_
protected

Definition at line 132 of file pose_estimation_node.h.

◆ sensor_pose_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::sensor_pose_publisher_
protected

Definition at line 110 of file pose_estimation_node.h.

◆ sensor_pose_roll_

double hector_pose_estimation::PoseEstimationNode::sensor_pose_roll_
protected

Definition at line 132 of file pose_estimation_node.h.

◆ sensor_pose_yaw_

double hector_pose_estimation::PoseEstimationNode::sensor_pose_yaw_
protected

Definition at line 132 of file pose_estimation_node.h.

◆ state_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::state_publisher_
protected

Definition at line 109 of file pose_estimation_node.h.

◆ syscommand_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::syscommand_subscriber_
protected

Definition at line 112 of file pose_estimation_node.h.

◆ tf_prefix_

std::string hector_pose_estimation::PoseEstimationNode::tf_prefix_
protected

Definition at line 120 of file pose_estimation_node.h.

◆ timing_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::timing_publisher_
protected

Definition at line 114 of file pose_estimation_node.h.

◆ transform_broadcaster_

tf::TransformBroadcaster hector_pose_estimation::PoseEstimationNode::transform_broadcaster_
protected

Definition at line 117 of file pose_estimation_node.h.

◆ transform_listener_

tf::TransformListener* hector_pose_estimation::PoseEstimationNode::transform_listener_
protected

Definition at line 118 of file pose_estimation_node.h.

◆ transforms_

std::vector<tf::StampedTransform> hector_pose_estimation::PoseEstimationNode::transforms_
protected

Definition at line 116 of file pose_estimation_node.h.

◆ twistupdate_subscriber_

ros::Subscriber hector_pose_estimation::PoseEstimationNode::twistupdate_subscriber_
protected

Definition at line 111 of file pose_estimation_node.h.

◆ velocity_publisher_

ros::Publisher hector_pose_estimation::PoseEstimationNode::velocity_publisher_
protected

Definition at line 109 of file pose_estimation_node.h.

◆ world_nav_transform_

geometry_msgs::TransformStamped hector_pose_estimation::PoseEstimationNode::world_nav_transform_
protected

Definition at line 126 of file pose_estimation_node.h.

◆ world_nav_transform_updated_

bool hector_pose_estimation::PoseEstimationNode::world_nav_transform_updated_
protected

Definition at line 129 of file pose_estimation_node.h.

◆ world_nav_transform_valid_

bool hector_pose_estimation::PoseEstimationNode::world_nav_transform_valid_
protected

Definition at line 129 of file pose_estimation_node.h.


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


hector_pose_estimation
Author(s): Johannes Meyer
autogenerated on Wed Mar 2 2022 00:24:50