pose_estimation_node.cpp
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 
30 #include <hector_pose_estimation/ros/parameters.h>
31 
40 
41 #ifdef USE_HECTOR_TIMING
42  #include <hector_diagnostics/timing.h>
43 #endif
44 
45 namespace hector_pose_estimation {
46 
48  : pose_estimation_(new PoseEstimation(system, state))
49  , private_nh_("~")
50  , transform_listener_(0)
51  , world_nav_transform_updated_(true)
52  , world_nav_transform_valid_(false)
53  , sensor_pose_roll_(0), sensor_pose_pitch_(0), sensor_pose_yaw_(0)
54 {
56 
57  pose_estimation_->addInput(new ImuInput, "imu");
58  pose_estimation_->addMeasurement(new PoseUpdate("poseupdate"));
59 #if defined(USE_HECTOR_UAV_MSGS)
60  pose_estimation_->addMeasurement(new Baro("baro"));
61 #endif
62  pose_estimation_->addMeasurement(new Height("height"));
63  pose_estimation_->addMeasurement(new Magnetic("magnetic"));
64  pose_estimation_->addMeasurement(new GPS("gps"));
65 }
66 
68 {
69  cleanup();
70  delete pose_estimation_;
71  delete transform_listener_;
72 }
73 
75  // get parameters
77  getPrivateNodeHandle().getParam("publish_covariances", publish_covariances_ = false);
78  if (getPrivateNodeHandle().getParam("publish_world_map_transform", publish_world_other_transform_ = false)) {
79  ROS_WARN("Parameter 'publish_world_map_transform' is deprecated. Use 'publish_world_other_transform' and 'other_frame' instead.");
80  }
81  getPrivateNodeHandle().getParam("publish_world_other_transform", publish_world_other_transform_);
82  if (getPrivateNodeHandle().getParam("map_frame", other_frame_ = std::string())) {
83  ROS_WARN("Parameter 'map_frame' is deprecated. Use 'other_frame' instead.");
84  }
85  getPrivateNodeHandle().getParam("other_frame", other_frame_);
86  getPrivateNodeHandle().getParam("publish_world_nav_transform", publish_world_nav_transform_ = false);
87 
88  // search tf_prefix parameter
90  if (!tf_prefix_.empty()) ROS_INFO("Using tf_prefix '%s'", tf_prefix_.c_str());
91 
92  // initialize pose estimation
93  if (!pose_estimation_->init()) {
94  ROS_ERROR("Intitialization of pose estimation failed!");
95  return false;
96  }
97 
101 #if defined(USE_HECTOR_UAV_MSGS)
102  baro_subscriber_ = getNodeHandle().subscribe("altimeter", 10, &PoseEstimationNode::baroCallback, this);
103 #else
105 #endif
107 
109  gps_velocity_subscriber_.subscribe(getNodeHandle(), "fix_velocity", 10);
112 
113  state_publisher_ = getNodeHandle().advertise<nav_msgs::Odometry>("state", 10, false);
114  pose_publisher_ = getNodeHandle().advertise<geometry_msgs::PoseStamped>("pose", 10, false);
115  velocity_publisher_ = getNodeHandle().advertise<geometry_msgs::Vector3Stamped>("velocity", 10, false);
116  imu_publisher_ = getNodeHandle().advertise<sensor_msgs::Imu>("imu", 10, false);
117  geopose_publisher_ = getNodeHandle().advertise<geographic_msgs::GeoPose>("geopose", 10, false);
118  global_fix_publisher_ = getNodeHandle().advertise<sensor_msgs::NavSatFix>("global", 10, false);
119  euler_publisher_ = getNodeHandle().advertise<geometry_msgs::Vector3Stamped>("euler", 10, false);
120 
121  angular_velocity_bias_publisher_ = getNodeHandle().advertise<geometry_msgs::Vector3Stamped>("angular_velocity_bias", 10, false);
122  linear_acceleration_bias_publisher_ = getNodeHandle().advertise<geometry_msgs::Vector3Stamped>("linear_acceleration_bias", 10, false);
123  gps_pose_publisher_ = getNodeHandle().advertise<geometry_msgs::PoseStamped>("fix/pose", 10, false);
124  sensor_pose_publisher_ = getNodeHandle().advertise<geometry_msgs::PoseStamped>("sensor_pose", 10, false);
125 
129 
130 #ifdef USE_HECTOR_TIMING
131  timing_publisher_ = getPrivateNodeHandle().advertise<hector_diagnostics::TimingAggregator>("timing", 10, false);
132 #endif
133 
134  global_reference_publisher_ = getNodeHandle().advertise<geographic_msgs::GeoPose>("global/reference", 1, true);
135  pose_estimation_->globalReference()->addUpdateCallback(boost::bind(&PoseEstimationNode::globalReferenceUpdated, this));
136 
137  // setup publish_world_nav_transform timer
139  double period = 0.1;
140  getPrivateNodeHandle().getParam("publish_world_nav_transform_period", period);
143  /* oneshot = */ false, /* autostart = */ true);
144  }
145 
146  // publish initial state
147  publish();
148 
149  return true;
150 }
151 
154 
155  sensor_pose_ = geometry_msgs::PoseStamped();
156  sensor_pose_roll_ = 0.0;
157  sensor_pose_pitch_ = 0.0;
158  sensor_pose_yaw_ = 0.0;
159 }
160 
162  if (gps_synchronizer_) {
163  delete gps_synchronizer_;
164  gps_synchronizer_ = 0;
165  }
167 
169 }
170 
171 void PoseEstimationNode::imuCallback(const sensor_msgs::ImuConstPtr& imu) {
173  pose_estimation_->update(imu->header.stamp);
174 
175  // calculate roll and pitch purely from acceleration
177  tf::Vector3 linear_acceleration_body(imu->linear_acceleration.x, imu->linear_acceleration.y, imu->linear_acceleration.z);
178  linear_acceleration_body.normalize();
179  sensor_pose_roll_ = atan2(linear_acceleration_body.y(), linear_acceleration_body.z());
180  sensor_pose_pitch_ = -asin(linear_acceleration_body.x());
181  }
182 
183  publish();
184 }
185 
186 void PoseEstimationNode::ahrsCallback(const sensor_msgs::ImuConstPtr& ahrs) {
187  pose_estimation_->state().setOrientation(Quaternion(ahrs->orientation.w, ahrs->orientation.x, ahrs->orientation.y, ahrs->orientation.z));
189  pose_estimation_->update(ahrs->header.stamp);
190  publish();
191 }
192 
193 void PoseEstimationNode::rollpitchCallback(const sensor_msgs::ImuConstPtr& attitude) {
194  pose_estimation_->state().setRollPitch(Quaternion(attitude->orientation.w, attitude->orientation.x, attitude->orientation.y, attitude->orientation.z));
195  pose_estimation_->setInput(ImuInput(*attitude));
196  pose_estimation_->update(attitude->header.stamp);
197  publish();
198 }
199 
200 #if defined(USE_HECTOR_UAV_MSGS)
201 void PoseEstimationNode::baroCallback(const hector_uav_msgs::AltimeterConstPtr& altimeter) {
202  boost::shared_ptr<Baro> m = boost::static_pointer_cast<Baro>(pose_estimation_->getMeasurement("baro"));
203  m->add(Baro::Update(altimeter->pressure, altimeter->qnh));
204 }
205 
206 #else
207 void PoseEstimationNode::heightCallback(const geometry_msgs::PointStampedConstPtr& height) {
208  boost::shared_ptr<Height> m = boost::static_pointer_cast<Height>(pose_estimation_->getMeasurement("height"));
209 
211  update(0) = height->point.z;
212  m->add(Height::Update(update));
213 
215  sensor_pose_.pose.position.z = height->point.z - m->getElevation();
216  }
217 }
218 #endif
219 
220 void PoseEstimationNode::magneticCallback(const geometry_msgs::Vector3StampedConstPtr& magnetic) {
221  boost::shared_ptr<Magnetic> m = boost::static_pointer_cast<Magnetic>(pose_estimation_->getMeasurement("magnetic"));
222 
224  update.x() = magnetic->vector.x;
225  update.y() = magnetic->vector.y;
226  update.z() = magnetic->vector.z;
227  m->add(Magnetic::Update(update));
228 
230  sensor_pose_yaw_ = -(m->getModel()->getTrueHeading(pose_estimation_->state(), update) - pose_estimation_->globalReference()->heading());
231  }
232 }
233 
234 void PoseEstimationNode::gpsCallback(const sensor_msgs::NavSatFixConstPtr& gps, const geometry_msgs::Vector3StampedConstPtr& gps_velocity) {
235  boost::shared_ptr<GPS> m = boost::static_pointer_cast<GPS>(pose_estimation_->getMeasurement("gps"));
236 
237  if (gps->status.status == sensor_msgs::NavSatStatus::STATUS_NO_FIX) {
238  if (m->getStatusFlags() > 0) m->reset(pose_estimation_->state());
239  return;
240  }
241 
243  update.latitude = gps->latitude * M_PI/180.0;
244  update.longitude = gps->longitude * M_PI/180.0;
245  update.velocity_north = gps_velocity->vector.x;
246  update.velocity_east = -gps_velocity->vector.y;
247  m->add(update);
248 
250  geometry_msgs::PoseStamped gps_pose;
251  pose_estimation_->getHeader(gps_pose.header);
252  gps_pose.header.stamp = gps->header.stamp;
253  GPSModel::MeasurementVector y = m->getVector(update, pose_estimation_->state());
254 
255  if (gps_pose_publisher_) {
256  gps_pose.pose.position.x = y(0);
257  gps_pose.pose.position.y = y(1);
258  gps_pose.pose.position.z = gps->altitude - pose_estimation_->globalReference()->position().altitude;
259  double track = atan2(gps_velocity->vector.y, gps_velocity->vector.x);
260  gps_pose.pose.orientation.w = cos(track/2);
261  gps_pose.pose.orientation.z = sin(track/2);
262  gps_pose_publisher_.publish(gps_pose);
263  }
264 
265  sensor_pose_.pose.position.x = y(0);
266  sensor_pose_.pose.position.y = y(1);
267  }
268 }
269 
270 void PoseEstimationNode::poseupdateCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose) {
271  pose_estimation_->getMeasurement("poseupdate")->add(PoseUpdate::Update(pose));
272 
274  if (pose->pose.covariance[0] > 0) sensor_pose_.pose.position.x = pose->pose.pose.position.x;
275  if (pose->pose.covariance[7] > 0) sensor_pose_.pose.position.y = pose->pose.pose.position.y;
276  if (pose->pose.covariance[14] > 0) sensor_pose_.pose.position.z = pose->pose.pose.position.z;
277  tf::Quaternion q;
278  double yaw, pitch, roll;
279  tf::quaternionMsgToTF(pose->pose.pose.orientation, q);
280  tf::Matrix3x3(q).getEulerYPR(yaw, pitch, roll);
281  if (pose->pose.covariance[21] > 0) sensor_pose_roll_ = roll;
282  if (pose->pose.covariance[28] > 0) sensor_pose_pitch_ = pitch;
283  if (pose->pose.covariance[35] > 0) sensor_pose_yaw_ = yaw;
284  }
285 }
286 
287 void PoseEstimationNode::twistupdateCallback(const geometry_msgs::TwistWithCovarianceStampedConstPtr& twist) {
288  pose_estimation_->getMeasurement("poseupdate")->add(PoseUpdate::Update(twist));
289 }
290 
291 void PoseEstimationNode::syscommandCallback(const std_msgs::StringConstPtr& syscommand) {
292  if (syscommand->data == "reset") {
293  ROS_INFO("Resetting pose_estimation");
295  publish();
296  }
297 }
298 
300  geographic_msgs::GeoPose geopose;
301  pose_estimation_->globalReference()->getGeoPose(geopose);
303 
304  // update world nav transform
306 }
307 
312  }
313 
317  }
318 }
319 
322  nav_msgs::Odometry state;
324  state_publisher_.publish(state);
325  }
326 
328  geometry_msgs::PoseStamped pose_msg;
329  pose_estimation_->getPose(pose_msg);
330  pose_publisher_.publish(pose_msg);
331  }
332 
334  sensor_msgs::Imu imu_msg;
335  pose_estimation_->getHeader(imu_msg.header);
336  pose_estimation_->getOrientation(imu_msg.orientation);
337  pose_estimation_->getImuWithBiases(imu_msg.linear_acceleration, imu_msg.angular_velocity);
338  imu_publisher_.publish(imu_msg);
339  }
340 
342  geometry_msgs::Vector3Stamped velocity_msg;
343  pose_estimation_->getVelocity(velocity_msg);
344  velocity_publisher_.publish(velocity_msg);
345  }
346 
348  geographic_msgs::GeoPose geopose_msg;
349  pose_estimation_->getGlobal(geopose_msg);
350  geopose_publisher_.publish(geopose_msg);
351  }
352 
354  sensor_msgs::NavSatFix global_msg;
355  pose_estimation_->getGlobal(global_msg);
356  global_fix_publisher_.publish(global_msg);
357  }
358 
360  geometry_msgs::Vector3Stamped euler_msg;
361  pose_estimation_->getHeader(euler_msg.header);
362  pose_estimation_->getOrientation(euler_msg.vector.z, euler_msg.vector.y, euler_msg.vector.x);
363  euler_publisher_.publish(euler_msg);
364  }
365 
368  geometry_msgs::Vector3Stamped angular_velocity_msg, linear_acceleration_msg;
369  pose_estimation_->getBias(angular_velocity_msg, linear_acceleration_msg);
372  }
373 
376  tf::Quaternion orientation;
378  tf::quaternionTFToMsg(orientation, sensor_pose_.pose.orientation);
380  }
381 
383  {
384  transforms_.clear();
385 
387 
389  tf::StampedTransform world_to_other_transform;
390  std::string nav_frame = pose_estimation_->parameters().getAs<std::string>("nav_frame");
391  try {
392  getTransformListener()->lookupTransform(nav_frame, other_frame_, ros::Time(), world_to_other_transform);
393  pose_estimation_->updateWorldToOtherTransform(world_to_other_transform);
394  transforms_.push_back(world_to_other_transform);
395 
396  } catch (tf::TransformException& e) {
397  ROS_WARN("Could not find a transformation from %s to %s to publish the world transformation", nav_frame.c_str(), other_frame_.c_str());
398  }
399  }
400 
401  // resolve tf frames
402  for(std::vector<tf::StampedTransform>::iterator t = transforms_.begin(); t != transforms_.end(); t++) {
403  t->frame_id_ = tf::resolve(tf_prefix_, t->frame_id_);
404  t->child_frame_id_ = tf::resolve(tf_prefix_, t->child_frame_id_);
405  }
406 
408  }
409 
410 #ifdef USE_HECTOR_TIMING
411  timing_publisher_.publish(*hector_diagnostics::TimingAggregator::Instance());
412 #endif
413 }
414 
416  return &transform_broadcaster_;
417 }
418 
421  return transform_listener_;
422 }
423 
424 } // namespace hector_pose_estimation
tf::Matrix3x3
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::~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
hector_pose_estimation::PoseEstimation::getTransforms
virtual void getTransforms(std::vector< tf::StampedTransform > &transforms)
hector_pose_estimation::Height
hector_pose_estimation::PoseUpdate
hector_pose_estimation::Baro
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
hector_pose_estimation::PoseEstimation::getWorldToNavTransform
virtual bool getWorldToNavTransform(geometry_msgs::TransformStamped &transform)
hector_pose_estimation::PoseEstimationNode::publish_covariances_
bool publish_covariances_
Definition: pose_estimation_node.h:121
boost::shared_ptr
gps.h
hector_pose_estimation::PoseEstimationNode::poseupdateCallback
void poseupdateCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
Definition: pose_estimation_node.cpp:270
hector_pose_estimation::PoseEstimation::getImuWithBiases
virtual void getImuWithBiases(geometry_msgs::Vector3 &linear_acceleration, geometry_msgs::Vector3 &angular_velocity)
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::PoseEstimation::addMeasurement
const MeasurementPtr & addMeasurement(ConcreteMeasurementModel *model, const std::string &name)
hector_pose_estimation::PoseEstimationNode::sensor_pose_pitch_
double sensor_pose_pitch_
Definition: pose_estimation_node.h:132
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
generic_quaternion_system_model.h
hector_pose_estimation::PoseEstimationNode::global_reference_publisher_
ros::Publisher global_reference_publisher_
Definition: pose_estimation_node.h:113
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
hector_pose_estimation::PoseEstimationNode::cleanup
virtual void cleanup()
Definition: pose_estimation_node.cpp:161
hector_pose_estimation::PoseEstimationNode::linear_acceleration_bias_publisher_
ros::Publisher linear_acceleration_bias_publisher_
Definition: pose_estimation_node.h:110
hector_pose_estimation::ParameterList::initialize
void initialize(ParameterRegisterFunc func) const
hector_pose_estimation::PoseEstimation::getOrientation
virtual void getOrientation(double &yaw, double &pitch, double &roll)
ros::Timer::stop
void stop()
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::PoseEstimation::update
void update(double dt)
tf::quaternionMsgToTF
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
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
hector_pose_estimation::GenericQuaternionSystemModel
hector_pose_estimation::PoseEstimation::init
bool init()
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
imu_input.h
hector_pose_estimation::State::setOrientation
void setOrientation(const Eigen::MatrixBase< Derived > &orientation)
hector_pose_estimation::PoseEstimation::getState
virtual void getState(nav_msgs::Odometry &state, bool with_covariances=true)
hector_pose_estimation::PoseEstimation::getGlobal
virtual void getGlobal(double &latitude, double &longitude, double &altitude)
tf::StampedTransform
hector_pose_estimation::PoseEstimation::state
virtual State & state()
hector_pose_estimation::PoseUpdate::Update
hector_pose_estimation::PoseEstimationNode::velocity_publisher_
ros::Publisher velocity_publisher_
Definition: pose_estimation_node.h:109
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
baro.h
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
hector_pose_estimation::PoseEstimation::addSystem
const SystemPtr & addSystem(ConcreteSystemModel *model, const std::string &name="system")
hector_pose_estimation::ParameterRegistryROS
height.h
hector_pose_estimation::PoseEstimation::addInput
InputPtr addInput(const InputPtr &input, const std::string &name=std::string())
hector_pose_estimation::PoseEstimation::getMeasurement
MeasurementPtr getMeasurement(const std::string &name) const
hector_pose_estimation::PoseEstimationNode::syscommandCallback
void syscommandCallback(const std_msgs::StringConstPtr &syscommand)
Definition: pose_estimation_node.cpp:291
hector_pose_estimation::PoseEstimation::globalReference
virtual const GlobalReferencePtr & globalReference()
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
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
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
hector_pose_estimation::PoseEstimationNode::publish_world_nav_transform_
bool publish_world_nav_transform_
Definition: pose_estimation_node.h:125
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::GPS
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::Magnetic
hector_pose_estimation::PoseEstimationNode::getTransformListener
tf::TransformListener * getTransformListener()
Definition: pose_estimation_node.cpp:419
poseupdate.h
hector_pose_estimation::PoseEstimationNode::euler_publisher_
ros::Publisher euler_publisher_
Definition: pose_estimation_node.h:109
magnetic.h
hector_pose_estimation::PoseEstimation::getBias
virtual void getBias(geometry_msgs::Vector3 &angular_velocity, geometry_msgs::Vector3 &linear_acceleration)
hector_pose_estimation::PoseEstimationNode::tf_prefix_
std::string tf_prefix_
Definition: pose_estimation_node.h:120
hector_pose_estimation::PoseEstimationNode::poseupdate_subscriber_
ros::Subscriber poseupdate_subscriber_
Definition: pose_estimation_node.h:111
ROS_WARN
#define ROS_WARN(...)
hector_pose_estimation::State::setRollPitch
void setRollPitch(const Quaternion &orientation)
hector_pose_estimation::PoseEstimationNode::getNodeHandle
virtual ros::NodeHandle & getNodeHandle()
Definition: pose_estimation_node.h:93
Measurement_< HeightModel >::MeasurementVector
Model::MeasurementVector MeasurementVector
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
imu_model.h
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::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
tf::Matrix3x3::getEulerYPR
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
message_filters::Subscriber::subscribe
void subscribe()
hector_pose_estimation::PoseEstimationNode::magneticCallback
void magneticCallback(const geometry_msgs::Vector3StampedConstPtr &magnetic)
Definition: pose_estimation_node.cpp:220
hector_pose_estimation::ImuInput
hector_pose_estimation::PoseEstimationNode::state_publisher_
ros::Publisher state_publisher_
Definition: pose_estimation_node.h:109
ros::Time
message_filters::TimeSynchronizer::registerCallback
Connection registerCallback(C &callback)
hector_pose_estimation::PoseEstimationNode::gps_pose_publisher_
ros::Publisher gps_pose_publisher_
Definition: pose_estimation_node.h:110
hector_pose_estimation::PoseEstimation::reset
void reset()
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::PoseEstimation::getHeader
virtual void getHeader(std_msgs::Header &header)
hector_pose_estimation::PoseEstimationNode::height_subscriber_
ros::Subscriber height_subscriber_
Definition: pose_estimation_node.h:105
hector_pose_estimation::PoseEstimation
tf::quaternionTFToMsg
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
hector_pose_estimation::PoseEstimation::setInput
InputPtr setInput(const Input &input, std::string name=std::string())
ROS_ERROR
#define ROS_ERROR(...)
pose_estimation_node.h
hector_pose_estimation::ParameterList::getAs
T & getAs(const std::string &key) const
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
Measurement_< BaroModel >::Update
traits::Update< BaroModel >::type Update
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::PoseEstimation::updateWorldToOtherTransform
virtual void updateWorldToOtherTransform(tf::StampedTransform &world_to_other_transform)
hector_pose_estimation::PoseEstimation::parameters
virtual ParameterList & parameters()
hector_pose_estimation::PoseEstimationNode::rollpitchCallback
void rollpitchCallback(const sensor_msgs::ImuConstPtr &attitude)
Definition: pose_estimation_node.cpp:193
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
hector_pose_estimation::Quaternion
Eigen::Quaternion< ScalarType > Quaternion
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
hector_pose_estimation::PoseEstimation::cleanup
void cleanup()
hector_pose_estimation::PoseEstimationNode::imu_subscriber_
ros::Subscriber imu_subscriber_
Definition: pose_estimation_node.h:105
ros::Duration
tf::Quaternion
hector_pose_estimation::PoseEstimation::getPose
virtual void getPose(geometry_msgs::Pose &pose)
hector_pose_estimation::PoseEstimationNode::sensor_pose_publisher_
ros::Publisher sensor_pose_publisher_
Definition: pose_estimation_node.h:110
hector_pose_estimation::PoseEstimation::getVelocity
virtual void getVelocity(geometry_msgs::Vector3 &vector)
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
hector_pose_estimation::PoseEstimationNode::sensor_pose_
geometry_msgs::PoseStamped sensor_pose_
Definition: pose_estimation_node.h:131
ros::Time::now
static Time now()
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