pose_estimation_node.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_POSE_ESTIMATION_NODE_H
30 #define HECTOR_POSE_ESTIMATION_NODE_H
31 
33 
34 #include <ros/ros.h>
35 
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>
41 #else
42  #include <geometry_msgs/PointStamped.h>
43 #endif
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>
52 #include <tf/transform_listener.h>
53 
56 
57 namespace hector_pose_estimation {
58 
60 public:
61  PoseEstimationNode(const SystemPtr& system = SystemPtr(), const StatePtr& state = StatePtr());
62  virtual ~PoseEstimationNode();
63 
64  virtual bool init();
65  virtual void reset();
66  virtual void cleanup();
67 
68  virtual void publish();
69 
70 protected:
71  void imuCallback(const sensor_msgs::ImuConstPtr& imu);
72  void ahrsCallback(const sensor_msgs::ImuConstPtr& ahrs);
73  void rollpitchCallback(const sensor_msgs::ImuConstPtr& attitude);
74 
75 #if defined(USE_MAV_MSGS)
76  void heightCallback(const mav_msgs::HeightConstPtr& height);
77 #elif defined(USE_HECTOR_UAV_MSGS)
78  void baroCallback(const hector_uav_msgs::AltimeterConstPtr& altimeter);
79 #else
80  void heightCallback(const geometry_msgs::PointStampedConstPtr& height);
81 #endif
82 
83  void magneticCallback(const geometry_msgs::Vector3StampedConstPtr& magnetic);
84  void gpsCallback(const sensor_msgs::NavSatFixConstPtr& gps, const geometry_msgs::Vector3StampedConstPtr& gps_velocity);
85  void poseupdateCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose);
86  void twistupdateCallback(const geometry_msgs::TwistWithCovarianceStampedConstPtr& twist);
87  void syscommandCallback(const std_msgs::StringConstPtr& syscommand);
88 
90 
92 
93  virtual ros::NodeHandle& getNodeHandle() { return nh_; }
95 
98 
99 protected:
101 
104 
115 
116  std::vector<tf::StampedTransform> transforms_;
119 
120  std::string tf_prefix_;
123  std::string other_frame_;
124 
126  geometry_msgs::TransformStamped world_nav_transform_;
130 
131  geometry_msgs::PoseStamped sensor_pose_;
133 };
134 
135 } // namespace hector_pose_estimation
136 
137 #endif // HECTOR_POSE_ESTIMATION_NODE_H
hector_pose_estimation::PoseEstimationNode::imuCallback
void imuCallback(const sensor_msgs::ImuConstPtr &imu)
Definition: pose_estimation_node.cpp:171
hector_pose_estimation::PoseEstimationNode::angular_velocity_bias_publisher_
ros::Publisher angular_velocity_bias_publisher_
Definition: pose_estimation_node.h:110
hector_pose_estimation::PoseEstimationNode::publish_world_other_transform_
bool publish_world_other_transform_
Definition: pose_estimation_node.h:122
hector_pose_estimation::PoseEstimationNode::pose_publisher_
ros::Publisher pose_publisher_
Definition: pose_estimation_node.h:109
hector_pose_estimation::PoseEstimationNode::private_nh_
ros::NodeHandle private_nh_
Definition: pose_estimation_node.h:103
hector_pose_estimation::PoseEstimationNode::~PoseEstimationNode
virtual ~PoseEstimationNode()
Definition: pose_estimation_node.cpp:67
hector_pose_estimation::PoseEstimationNode::globalReferenceUpdated
void globalReferenceUpdated()
Definition: pose_estimation_node.cpp:299
hector_pose_estimation::PoseEstimationNode::gps_velocity_subscriber_
message_filters::Subscriber< geometry_msgs::Vector3Stamped > gps_velocity_subscriber_
Definition: pose_estimation_node.h:107
ros::Publisher
hector_pose_estimation::PoseEstimationNode::publish_covariances_
bool publish_covariances_
Definition: pose_estimation_node.h:121
boost::shared_ptr
hector_pose_estimation::PoseEstimationNode::poseupdateCallback
void poseupdateCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
Definition: pose_estimation_node.cpp:270
hector_pose_estimation::PoseEstimationNode::world_nav_transform_valid_
bool world_nav_transform_valid_
Definition: pose_estimation_node.h:129
hector_pose_estimation::PoseEstimationNode::gpsCallback
void gpsCallback(const sensor_msgs::NavSatFixConstPtr &gps, const geometry_msgs::Vector3StampedConstPtr &gps_velocity)
Definition: pose_estimation_node.cpp:234
hector_pose_estimation::PoseEstimationNode::sensor_pose_roll_
double sensor_pose_roll_
Definition: pose_estimation_node.h:132
hector_pose_estimation::PoseEstimationNode::sensor_pose_pitch_
double sensor_pose_pitch_
Definition: pose_estimation_node.h:132
hector_pose_estimation::PoseEstimationNode::global_reference_publisher_
ros::Publisher global_reference_publisher_
Definition: pose_estimation_node.h:113
hector_pose_estimation::PoseEstimationNode::cleanup
virtual void cleanup()
Definition: pose_estimation_node.cpp:161
ros.h
hector_pose_estimation::PoseEstimationNode::linear_acceleration_bias_publisher_
ros::Publisher linear_acceleration_bias_publisher_
Definition: pose_estimation_node.h:110
hector_pose_estimation::PoseEstimationNode::ahrs_subscriber_
ros::Subscriber ahrs_subscriber_
Definition: pose_estimation_node.h:105
hector_pose_estimation::PoseEstimationNode::getPrivateNodeHandle
virtual ros::NodeHandle & getPrivateNodeHandle()
Definition: pose_estimation_node.h:94
hector_pose_estimation::PoseEstimationNode::init
virtual bool init()
Definition: pose_estimation_node.cpp:74
hector_pose_estimation::PoseEstimationNode::publishWorldNavTransform
void publishWorldNavTransform(const ros::TimerEvent &=ros::TimerEvent())
Definition: pose_estimation_node.cpp:308
hector_pose_estimation::PoseEstimationNode::pose_estimation_
PoseEstimation * pose_estimation_
Definition: pose_estimation_node.h:100
time_synchronizer.h
hector_pose_estimation::PoseEstimationNode::velocity_publisher_
ros::Publisher velocity_publisher_
Definition: pose_estimation_node.h:109
transform_broadcaster.h
message_filters::Subscriber< sensor_msgs::NavSatFix >
hector_pose_estimation::PoseEstimationNode::syscommandCallback
void syscommandCallback(const std_msgs::StringConstPtr &syscommand)
Definition: pose_estimation_node.cpp:291
hector_pose_estimation
hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_period_
ros::Duration publish_world_nav_transform_period_
Definition: pose_estimation_node.h:128
tf::TransformBroadcaster
hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_
bool publish_world_nav_transform_
Definition: pose_estimation_node.h:125
subscriber.h
hector_pose_estimation::PoseEstimationNode::world_nav_transform_updated_
bool world_nav_transform_updated_
Definition: pose_estimation_node.h:129
hector_pose_estimation::PoseEstimationNode::imu_publisher_
ros::Publisher imu_publisher_
Definition: pose_estimation_node.h:109
hector_pose_estimation::PoseEstimationNode::PoseEstimationNode
PoseEstimationNode(const SystemPtr &system=SystemPtr(), const StatePtr &state=StatePtr())
Definition: pose_estimation_node.cpp:47
hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_timer_
ros::Timer publish_world_nav_transform_timer_
Definition: pose_estimation_node.h:127
hector_pose_estimation::PoseEstimationNode::getTransformListener
tf::TransformListener * getTransformListener()
Definition: pose_estimation_node.cpp:419
hector_pose_estimation::PoseEstimationNode::euler_publisher_
ros::Publisher euler_publisher_
Definition: pose_estimation_node.h:109
hector_pose_estimation::PoseEstimationNode::tf_prefix_
std::string tf_prefix_
Definition: pose_estimation_node.h:120
hector_pose_estimation::StatePtr
boost::shared_ptr< State > StatePtr
hector_pose_estimation::PoseEstimationNode
Definition: pose_estimation_node.h:59
hector_pose_estimation::PoseEstimationNode::poseupdate_subscriber_
ros::Subscriber poseupdate_subscriber_
Definition: pose_estimation_node.h:111
hector_pose_estimation::PoseEstimationNode::getNodeHandle
virtual ros::NodeHandle & getNodeHandle()
Definition: pose_estimation_node.h:93
hector_pose_estimation::PoseEstimationNode::getTransformBroadcaster
tf::TransformBroadcaster * getTransformBroadcaster()
Definition: pose_estimation_node.cpp:415
ros::TimerEvent
hector_pose_estimation::PoseEstimationNode::geopose_publisher_
ros::Publisher geopose_publisher_
Definition: pose_estimation_node.h:109
hector_pose_estimation::PoseEstimationNode::nh_
ros::NodeHandle nh_
Definition: pose_estimation_node.h:102
hector_pose_estimation::PoseEstimationNode::heightCallback
void heightCallback(const geometry_msgs::PointStampedConstPtr &height)
Definition: pose_estimation_node.cpp:207
hector_pose_estimation::PoseEstimationNode::magnetic_subscriber_
ros::Subscriber magnetic_subscriber_
Definition: pose_estimation_node.h:105
hector_pose_estimation::PoseEstimationNode::timing_publisher_
ros::Publisher timing_publisher_
Definition: pose_estimation_node.h:114
hector_pose_estimation::PoseEstimationNode::gps_subscriber_
message_filters::Subscriber< sensor_msgs::NavSatFix > gps_subscriber_
Definition: pose_estimation_node.h:106
hector_pose_estimation::SystemPtr
boost::shared_ptr< System > SystemPtr
transform_listener.h
hector_pose_estimation::PoseEstimationNode::magneticCallback
void magneticCallback(const geometry_msgs::Vector3StampedConstPtr &magnetic)
Definition: pose_estimation_node.cpp:220
hector_pose_estimation::PoseEstimationNode::state_publisher_
ros::Publisher state_publisher_
Definition: pose_estimation_node.h:109
hector_pose_estimation::PoseEstimationNode::gps_pose_publisher_
ros::Publisher gps_pose_publisher_
Definition: pose_estimation_node.h:110
hector_pose_estimation::PoseEstimationNode::gps_synchronizer_
message_filters::TimeSynchronizer< sensor_msgs::NavSatFix, geometry_msgs::Vector3Stamped > * gps_synchronizer_
Definition: pose_estimation_node.h:108
hector_pose_estimation::PoseEstimationNode::height_subscriber_
ros::Subscriber height_subscriber_
Definition: pose_estimation_node.h:105
hector_pose_estimation::PoseEstimation
tf::TransformListener
hector_pose_estimation::PoseEstimationNode::rollpitch_subscriber_
ros::Subscriber rollpitch_subscriber_
Definition: pose_estimation_node.h:105
hector_pose_estimation::PoseEstimationNode::twistupdateCallback
void twistupdateCallback(const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
Definition: pose_estimation_node.cpp:287
hector_pose_estimation::PoseEstimationNode::sensor_pose_yaw_
double sensor_pose_yaw_
Definition: pose_estimation_node.h:132
hector_pose_estimation::PoseEstimationNode::transform_broadcaster_
tf::TransformBroadcaster transform_broadcaster_
Definition: pose_estimation_node.h:117
message_filters::TimeSynchronizer< sensor_msgs::NavSatFix, geometry_msgs::Vector3Stamped >
hector_pose_estimation::PoseEstimationNode::other_frame_
std::string other_frame_
Definition: pose_estimation_node.h:123
hector_pose_estimation::PoseEstimationNode::reset
virtual void reset()
Definition: pose_estimation_node.cpp:152
hector_pose_estimation::PoseEstimationNode::ahrsCallback
void ahrsCallback(const sensor_msgs::ImuConstPtr &ahrs)
Definition: pose_estimation_node.cpp:186
hector_pose_estimation::PoseEstimationNode::publish
virtual void publish()
Definition: pose_estimation_node.cpp:320
hector_pose_estimation::PoseEstimationNode::rollpitchCallback
void rollpitchCallback(const sensor_msgs::ImuConstPtr &attitude)
Definition: pose_estimation_node.cpp:193
pose_estimation.h
hector_pose_estimation::PoseEstimationNode::imu_subscriber_
ros::Subscriber imu_subscriber_
Definition: pose_estimation_node.h:105
ros::Duration
ros::Timer
hector_pose_estimation::PoseEstimationNode::sensor_pose_publisher_
ros::Publisher sensor_pose_publisher_
Definition: pose_estimation_node.h:110
hector_pose_estimation::PoseEstimationNode::global_fix_publisher_
ros::Publisher global_fix_publisher_
Definition: pose_estimation_node.h:109
hector_pose_estimation::PoseEstimationNode::twistupdate_subscriber_
ros::Subscriber twistupdate_subscriber_
Definition: pose_estimation_node.h:111
hector_pose_estimation::PoseEstimationNode::syscommand_subscriber_
ros::Subscriber syscommand_subscriber_
Definition: pose_estimation_node.h:112
hector_pose_estimation::PoseEstimationNode::transforms_
std::vector< tf::StampedTransform > transforms_
Definition: pose_estimation_node.h:116
hector_pose_estimation::PoseEstimationNode::transform_listener_
tf::TransformListener * transform_listener_
Definition: pose_estimation_node.h:118
ros::NodeHandle
ros::Subscriber
hector_pose_estimation::PoseEstimationNode::sensor_pose_
geometry_msgs::PoseStamped sensor_pose_
Definition: pose_estimation_node.h:131
hector_pose_estimation::PoseEstimationNode::world_nav_transform_
geometry_msgs::TransformStamped world_nav_transform_
Definition: pose_estimation_node.h:126


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