#include <pose_estimation_node.h>
Definition at line 59 of file pose_estimation_node.h.
◆ PoseEstimationNode()
◆ ~PoseEstimationNode()
hector_pose_estimation::PoseEstimationNode::~PoseEstimationNode |
( |
| ) |
|
|
virtual |
◆ ahrsCallback()
void hector_pose_estimation::PoseEstimationNode::ahrsCallback |
( |
const sensor_msgs::ImuConstPtr & |
ahrs | ) |
|
|
protected |
◆ cleanup()
void hector_pose_estimation::PoseEstimationNode::cleanup |
( |
| ) |
|
|
virtual |
◆ getNodeHandle()
virtual ros::NodeHandle& hector_pose_estimation::PoseEstimationNode::getNodeHandle |
( |
| ) |
|
|
inlineprotectedvirtual |
◆ getPrivateNodeHandle()
virtual ros::NodeHandle& hector_pose_estimation::PoseEstimationNode::getPrivateNodeHandle |
( |
| ) |
|
|
inlineprotectedvirtual |
◆ getTransformBroadcaster()
◆ getTransformListener()
◆ globalReferenceUpdated()
void hector_pose_estimation::PoseEstimationNode::globalReferenceUpdated |
( |
| ) |
|
|
protected |
◆ gpsCallback()
void hector_pose_estimation::PoseEstimationNode::gpsCallback |
( |
const sensor_msgs::NavSatFixConstPtr & |
gps, |
|
|
const geometry_msgs::Vector3StampedConstPtr & |
gps_velocity |
|
) |
| |
|
protected |
◆ heightCallback()
void hector_pose_estimation::PoseEstimationNode::heightCallback |
( |
const geometry_msgs::PointStampedConstPtr & |
height | ) |
|
|
protected |
◆ imuCallback()
void hector_pose_estimation::PoseEstimationNode::imuCallback |
( |
const sensor_msgs::ImuConstPtr & |
imu | ) |
|
|
protected |
◆ init()
bool hector_pose_estimation::PoseEstimationNode::init |
( |
| ) |
|
|
virtual |
◆ magneticCallback()
void hector_pose_estimation::PoseEstimationNode::magneticCallback |
( |
const geometry_msgs::Vector3StampedConstPtr & |
magnetic | ) |
|
|
protected |
◆ poseupdateCallback()
void hector_pose_estimation::PoseEstimationNode::poseupdateCallback |
( |
const geometry_msgs::PoseWithCovarianceStampedConstPtr & |
pose | ) |
|
|
protected |
◆ publish()
void hector_pose_estimation::PoseEstimationNode::publish |
( |
| ) |
|
|
virtual |
◆ publishWorldNavTransform()
◆ reset()
void hector_pose_estimation::PoseEstimationNode::reset |
( |
| ) |
|
|
virtual |
◆ rollpitchCallback()
void hector_pose_estimation::PoseEstimationNode::rollpitchCallback |
( |
const sensor_msgs::ImuConstPtr & |
attitude | ) |
|
|
protected |
◆ syscommandCallback()
void hector_pose_estimation::PoseEstimationNode::syscommandCallback |
( |
const std_msgs::StringConstPtr & |
syscommand | ) |
|
|
protected |
◆ twistupdateCallback()
void hector_pose_estimation::PoseEstimationNode::twistupdateCallback |
( |
const geometry_msgs::TwistWithCovarianceStampedConstPtr & |
twist | ) |
|
|
protected |
◆ ahrs_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::ahrs_subscriber_ |
|
protected |
◆ angular_velocity_bias_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::angular_velocity_bias_publisher_ |
|
protected |
◆ euler_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::euler_publisher_ |
|
protected |
◆ geopose_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::geopose_publisher_ |
|
protected |
◆ global_fix_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::global_fix_publisher_ |
|
protected |
◆ global_reference_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::global_reference_publisher_ |
|
protected |
◆ gps_pose_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::gps_pose_publisher_ |
|
protected |
◆ gps_subscriber_
◆ gps_synchronizer_
◆ gps_velocity_subscriber_
◆ height_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::height_subscriber_ |
|
protected |
◆ imu_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::imu_publisher_ |
|
protected |
◆ imu_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::imu_subscriber_ |
|
protected |
◆ linear_acceleration_bias_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::linear_acceleration_bias_publisher_ |
|
protected |
◆ magnetic_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::magnetic_subscriber_ |
|
protected |
◆ nh_
◆ other_frame_
std::string hector_pose_estimation::PoseEstimationNode::other_frame_ |
|
protected |
◆ pose_estimation_
PoseEstimation* hector_pose_estimation::PoseEstimationNode::pose_estimation_ |
|
protected |
◆ pose_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::pose_publisher_ |
|
protected |
◆ poseupdate_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::poseupdate_subscriber_ |
|
protected |
◆ private_nh_
◆ publish_covariances_
bool hector_pose_estimation::PoseEstimationNode::publish_covariances_ |
|
protected |
◆ publish_world_nav_transform_
bool hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_ |
|
protected |
◆ publish_world_nav_transform_period_
ros::Duration hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_period_ |
|
protected |
◆ publish_world_nav_transform_timer_
ros::Timer hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_timer_ |
|
protected |
◆ publish_world_other_transform_
bool hector_pose_estimation::PoseEstimationNode::publish_world_other_transform_ |
|
protected |
◆ rollpitch_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::rollpitch_subscriber_ |
|
protected |
◆ sensor_pose_
geometry_msgs::PoseStamped hector_pose_estimation::PoseEstimationNode::sensor_pose_ |
|
protected |
◆ sensor_pose_pitch_
double hector_pose_estimation::PoseEstimationNode::sensor_pose_pitch_ |
|
protected |
◆ sensor_pose_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::sensor_pose_publisher_ |
|
protected |
◆ sensor_pose_roll_
double hector_pose_estimation::PoseEstimationNode::sensor_pose_roll_ |
|
protected |
◆ sensor_pose_yaw_
double hector_pose_estimation::PoseEstimationNode::sensor_pose_yaw_ |
|
protected |
◆ state_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::state_publisher_ |
|
protected |
◆ syscommand_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::syscommand_subscriber_ |
|
protected |
◆ tf_prefix_
std::string hector_pose_estimation::PoseEstimationNode::tf_prefix_ |
|
protected |
◆ timing_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::timing_publisher_ |
|
protected |
◆ transform_broadcaster_
◆ transform_listener_
◆ transforms_
◆ twistupdate_subscriber_
ros::Subscriber hector_pose_estimation::PoseEstimationNode::twistupdate_subscriber_ |
|
protected |
◆ velocity_publisher_
ros::Publisher hector_pose_estimation::PoseEstimationNode::velocity_publisher_ |
|
protected |
◆ world_nav_transform_
geometry_msgs::TransformStamped hector_pose_estimation::PoseEstimationNode::world_nav_transform_ |
|
protected |
◆ world_nav_transform_updated_
bool hector_pose_estimation::PoseEstimationNode::world_nav_transform_updated_ |
|
protected |
◆ world_nav_transform_valid_
bool hector_pose_estimation::PoseEstimationNode::world_nav_transform_valid_ |
|
protected |
The documentation for this class was generated from the following files: