Go to the documentation of this file.
29 #ifndef HECTOR_POSE_ESTIMATION_NODE_H
30 #define HECTOR_POSE_ESTIMATION_NODE_H
36 #include <sensor_msgs/Imu.h>
37 #if defined(USE_MAV_MSGS)
38 #include <mav_msgs/Height.h>
39 #elif defined(USE_HECTOR_UAV_MSGS)
40 #include <hector_uav_msgs/Altimeter.h>
42 #include <geometry_msgs/PointStamped.h>
44 #include <sensor_msgs/NavSatFix.h>
45 #include <geometry_msgs/QuaternionStamped.h>
46 #include <geometry_msgs/PoseWithCovarianceStamped.h>
47 #include <geometry_msgs/TwistWithCovarianceStamped.h>
48 #include <geometry_msgs/Vector3Stamped.h>
49 #include <nav_msgs/Odometry.h>
50 #include <std_msgs/String.h>
71 void imuCallback(
const sensor_msgs::ImuConstPtr& imu);
75 #if defined(USE_MAV_MSGS)
77 #elif defined(USE_HECTOR_UAV_MSGS)
78 void baroCallback(
const hector_uav_msgs::AltimeterConstPtr& altimeter);
80 void heightCallback(
const geometry_msgs::PointStampedConstPtr& height);
83 void magneticCallback(
const geometry_msgs::Vector3StampedConstPtr& magnetic);
84 void gpsCallback(
const sensor_msgs::NavSatFixConstPtr& gps,
const geometry_msgs::Vector3StampedConstPtr& gps_velocity);
137 #endif // HECTOR_POSE_ESTIMATION_NODE_H
void imuCallback(const sensor_msgs::ImuConstPtr &imu)
ros::Publisher angular_velocity_bias_publisher_
bool publish_world_other_transform_
ros::Publisher pose_publisher_
ros::NodeHandle private_nh_
virtual ~PoseEstimationNode()
void globalReferenceUpdated()
message_filters::Subscriber< geometry_msgs::Vector3Stamped > gps_velocity_subscriber_
bool publish_covariances_
void poseupdateCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
bool world_nav_transform_valid_
void gpsCallback(const sensor_msgs::NavSatFixConstPtr &gps, const geometry_msgs::Vector3StampedConstPtr &gps_velocity)
double sensor_pose_pitch_
ros::Publisher global_reference_publisher_
ros::Publisher linear_acceleration_bias_publisher_
ros::Subscriber ahrs_subscriber_
virtual ros::NodeHandle & getPrivateNodeHandle()
void publishWorldNavTransform(const ros::TimerEvent &=ros::TimerEvent())
PoseEstimation * pose_estimation_
ros::Publisher velocity_publisher_
void syscommandCallback(const std_msgs::StringConstPtr &syscommand)
ros::Duration publish_world_nav_transform_period_
bool publish_world_nav_transform_
bool world_nav_transform_updated_
ros::Publisher imu_publisher_
PoseEstimationNode(const SystemPtr &system=SystemPtr(), const StatePtr &state=StatePtr())
ros::Timer publish_world_nav_transform_timer_
tf::TransformListener * getTransformListener()
ros::Publisher euler_publisher_
boost::shared_ptr< State > StatePtr
ros::Subscriber poseupdate_subscriber_
virtual ros::NodeHandle & getNodeHandle()
tf::TransformBroadcaster * getTransformBroadcaster()
ros::Publisher geopose_publisher_
void heightCallback(const geometry_msgs::PointStampedConstPtr &height)
ros::Subscriber magnetic_subscriber_
ros::Publisher timing_publisher_
message_filters::Subscriber< sensor_msgs::NavSatFix > gps_subscriber_
boost::shared_ptr< System > SystemPtr
void magneticCallback(const geometry_msgs::Vector3StampedConstPtr &magnetic)
ros::Publisher state_publisher_
ros::Publisher gps_pose_publisher_
message_filters::TimeSynchronizer< sensor_msgs::NavSatFix, geometry_msgs::Vector3Stamped > * gps_synchronizer_
ros::Subscriber height_subscriber_
ros::Subscriber rollpitch_subscriber_
void twistupdateCallback(const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
tf::TransformBroadcaster transform_broadcaster_
void ahrsCallback(const sensor_msgs::ImuConstPtr &ahrs)
void rollpitchCallback(const sensor_msgs::ImuConstPtr &attitude)
ros::Subscriber imu_subscriber_
ros::Publisher sensor_pose_publisher_
ros::Publisher global_fix_publisher_
ros::Subscriber twistupdate_subscriber_
ros::Subscriber syscommand_subscriber_
std::vector< tf::StampedTransform > transforms_
tf::TransformListener * transform_listener_
geometry_msgs::PoseStamped sensor_pose_
geometry_msgs::TransformStamped world_nav_transform_