pose_estimation.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Johannes Meyer and Martin Nowara, 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 
32 
35 
36 #include <boost/weak_ptr.hpp>
37 
38 namespace hector_pose_estimation {
39 
40 namespace {
41  static PoseEstimation *the_instance = 0;
42 }
43 
45  : state_(state ? state : StatePtr(new OrientationPositionVelocityState))
46  , rate_update_(new Rate("rate"))
47  , gravity_update_(new Gravity ("gravity"))
48  , zerorate_update_(new ZeroRate("zerorate"))
49 {
50  if (!the_instance) the_instance = this;
51  if (system) addSystem(system);
52 
53  world_frame_ = "/world";
54  nav_frame_ = "nav";
55  base_frame_ = "base_link";
56  stabilized_frame_ = "base_stabilized";
57  footprint_frame_ = "base_footprint";
58  // position_frame_ = "base_position";
59  alignment_time_ = 0.0;
60  gravity_ = -9.8065;
61 
62  parameters().add("world_frame", world_frame_);
63  parameters().add("nav_frame", nav_frame_);
64  parameters().add("base_frame", base_frame_);
65  parameters().add("stabilized_frame", stabilized_frame_);
66  parameters().add("footprint_frame", footprint_frame_);
67  parameters().add("position_frame", position_frame_);
69  parameters().add("alignment_time", alignment_time_);
70  parameters().add("gravity_magnitude", gravity_);
71 
72  // add default measurements
76 }
77 
79 {
80  cleanup();
81 }
82 
84  if (!the_instance) the_instance = new PoseEstimation();
85  return the_instance;
86 }
87 
89 {
90 #ifdef EIGEN_RUNTIME_NO_MALLOC
91  Eigen::internal::set_is_malloc_allowed(true);
92 #endif
93 
94  // initialize global reference
95  globalReference()->reset();
96 
97  // check if system is initialized
98  if (systems_.empty()) return false;
99 
100  // create new filter
101  filter_.reset(new filter::EKF(*state_));
102 
103  // initialize systems (new systems could be added during initialization!)
104  for(Systems::iterator it = systems_.begin(); it != systems_.end(); ++it)
105  if (!(*it)->init(*this, state())) return false;
106 
107  // initialize measurements (new systems could be added during initialization!)
108  for(Measurements::iterator it = measurements_.begin(); it != measurements_.end(); ++it)
109  if (!(*it)->init(*this, state())) return false;
110 
111  // initialize filter
112  filter_->init(*this);
113 
114  // call setFilter for each system and each measurement
115  for(Systems::iterator it = systems_.begin(); it != systems_.end(); ++it)
116  (*it)->setFilter(filter_.get());
117  for(Measurements::iterator it = measurements_.begin(); it != measurements_.end(); ++it)
118  (*it)->setFilter(filter_.get());
119 
120  // reset (or initialize) filter and measurements
121  reset();
122 
123  return true;
124 }
125 
127 {
128  // cleanup system
129  for(Systems::iterator it = systems_.begin(); it != systems_.end(); ++it) (*it)->cleanup();
130 
131  // cleanup measurements
132  for(Measurements::iterator it = measurements_.begin(); it != measurements_.end(); ++it) (*it)->cleanup();
133 
134  // delete filter instance
135  if (filter_) filter_.reset();
136 }
137 
139 {
140  // check if system is initialized
141  if (systems_.empty()) return;
142 
143  // set initial status
144  if (filter_) filter_->reset();
145 
146  // restart alignment
148  if (alignment_time_ > 0) {
150  }
151 
152  // reset systems and measurements
153  for(Systems::iterator it = systems_.begin(); it != systems_.end(); ++it) {
154  (*it)->reset(state());
155  (*it)->getPrior(state());
156  }
157 
158  for(Measurements::iterator it = measurements_.begin(); it != measurements_.end(); ++it) {
159  (*it)->reset(state());
160  }
161 
162  updated();
163 }
164 
166 {
167  // check if system is initialized
168  if (systems_.empty()) return;
169 
170  ros::Duration dt;
171  if (!getTimestamp().isZero()) {
172  if (new_timestamp.isZero()) new_timestamp = ros::Time::now();
173  dt = new_timestamp - getTimestamp();
174  }
175  setTimestamp(new_timestamp);
176 
177  // do the update step
178  update(dt.toSec());
179 }
180 
181 void PoseEstimation::update(double dt)
182 {
183  // check dt
184  if (dt < -1.0)
185  reset();
186  else if (dt < 0.0)
187  return;
188  else if (dt > 1.0)
189  dt = 1.0;
190 
191  // check if system and filter is initialized
192  if (systems_.empty() || !filter_) return;
193 
194  // filter rate measurement first
195  boost::shared_ptr<ImuInput> imu = getInputType<ImuInput>("imu");
196  if (imu) {
197  // Should the biases already be integrated here?
198  // Note: The state set here only has an effect if the state vector does not have a rate/acceleration component.
199  state().setRate(imu->getRate());
200  state().setAcceleration(imu->getAcceleration() + state().R().row(2).transpose() * gravity_);
201 
202  if (state().rate() && rate_update_) {
203  rate_update_->update(Rate::Update(imu->getRate()));
204  }
205  }
206 
207  // time update step
208  filter_->predict(systems_, dt);
209 
210  // pseudo measurement updates (if required)
211  if (imu && !(getSystemStatus() & STATE_ROLLPITCH)) {
212  gravity_update_->enable();
213  gravity_update_->update(Gravity::Update(imu->getAcceleration()));
214  } else {
215  gravity_update_->disable();
216  }
217  if (!(getSystemStatus() & STATE_RATE_Z)) {
218  zerorate_update_->enable();
220  } else {
221  zerorate_update_->disable();
222  }
223 
224  // measurement updates
225  filter_->correct(measurements_);
226 
227  // updated hook
228  updated();
229 
230  // set measurement status and increase timers
231  SystemStatus measurement_status = 0;
232  for(Measurements::iterator it = measurements_.begin(); it != measurements_.end(); it++) {
233  const MeasurementPtr& measurement = *it;
234  measurement_status |= measurement->getStatusFlags();
235  measurement->increase_timer(dt);
236  }
237  setMeasurementStatus(measurement_status);
238 
239  // set system status
240  SystemStatus system_status = 0;
241  for(Systems::iterator it = systems_.begin(); it != systems_.end(); it++) {
242  const SystemPtr& system = *it;
243  system_status |= system->getStatusFlags();
244  }
246 
247  // check for invalid state
248  if (!state().valid()) {
249  ROS_FATAL("Invalid state, resetting...");
250  reset();
251  return;
252  }
253 
254  // switch overall system status
257  if ((getTimestamp() - alignment_start_).toSec() >= alignment_time_) {
259  }
262  } else {
264  }
265 
266 
267 #ifdef EIGEN_RUNTIME_NO_MALLOC
268  // No memory allocations allowed after the first update!
269  Eigen::internal::set_is_malloc_allowed(false);
270 #endif
271 }
272 
274  for(Systems::iterator it = systems_.begin(); it != systems_.end(); ++it) {
275  (*it)->limitState(state());
276  }
277 }
278 
279 const SystemPtr& PoseEstimation::addSystem(const SystemPtr& system, const std::string& name) {
280  if (!name.empty() && system->getName().empty()) system->setName(name);
281  parameters().add(system->getName(), system->parameters());
282  return systems_.add(system, system->getName());
283 }
284 
285 InputPtr PoseEstimation::addInput(const InputPtr& input, const std::string& name)
286 {
287  if (!name.empty()) input->setName(name);
288  return inputs_.add(input, input->getName());
289 }
290 
291 InputPtr PoseEstimation::setInput(const Input& value, std::string name)
292 {
293  if (name.empty()) name = value.getName();
294  InputPtr input = inputs_.get(name);
295  if (!input) {
296  ROS_WARN("Set input \"%s\", but this input is not registered by any system model.", name.c_str());
297  return InputPtr();
298  }
299 
300  *input = value;
301  return input;
302 }
303 
304 const MeasurementPtr& PoseEstimation::addMeasurement(const MeasurementPtr& measurement, const std::string& name) {
305  if (!name.empty()) measurement->setName(name);
306  parameters().add(measurement->getName(), measurement->parameters());
307  return measurements_.add(measurement, measurement->getName());
308 }
309 
311 // if (state_is_dirty_) {
312 // state_ = filter_->PostGet()->ExpectedValueGet();
313 // state_is_dirty_ = false;
314 // }
315  return state().getVector();
316 }
317 
319 // if (covariance_is_dirty_) {
320 // covariance_ = filter_->PostGet()->CovarianceGet();
321 // covariance_is_dirty_ = false;
322 // }
323  return state().getCovariance();
324 }
325 
327  return state().getSystemStatus();
328 }
329 
331  return state().getMeasurementStatus();
332 }
333 
335  return state().inSystemStatus(test_status);
336 }
337 
339  return state().setSystemStatus(new_status);
340 }
341 
343  return state().setMeasurementStatus(new_measurement_status);
344 }
345 
347  return state().updateSystemStatus(set, clear);
348 }
349 
351  return state().updateMeasurementStatus(set, clear);
352 }
353 
355  return state().getTimestamp();
356 }
357 
358 void PoseEstimation::setTimestamp(const ros::Time& timestamp) {
359  state().setTimestamp(timestamp);
360 }
361 
362 void PoseEstimation::getHeader(std_msgs::Header& header) {
363  header.stamp = getTimestamp();
364  header.frame_id = nav_frame_;
365 }
366 
367 void PoseEstimation::getState(nav_msgs::Odometry& msg, bool with_covariances) {
368  getHeader(msg.header);
369  getPose(msg.pose.pose);
370  getVelocity(msg.twist.twist.linear);
371  getRate(msg.twist.twist.angular);
372  msg.child_frame_id = base_frame_;
373 
374  // rotate body vectors to nav frame
375  ColumnVector3 rate_nav = state().R() * ColumnVector3(msg.twist.twist.angular.x, msg.twist.twist.angular.y, msg.twist.twist.angular.z);
376  msg.twist.twist.angular.x = rate_nav.x();
377  msg.twist.twist.angular.y = rate_nav.y();
378  msg.twist.twist.angular.z = rate_nav.z();
379 
380  // fill covariances
381  if (with_covariances) {
382  Eigen::Map< Eigen::Matrix<geometry_msgs::PoseWithCovariance::_covariance_type::value_type,6,6> > pose_covariance_msg(msg.pose.covariance.data());
383  Eigen::Map< Eigen::Matrix<geometry_msgs::TwistWithCovariance::_covariance_type::value_type,6,6> > twist_covariance_msg(msg.twist.covariance.data());
384 
385  // position covariance
386  if (state().position()) {
387  pose_covariance_msg.block<3,3>(0,0) = state().position()->getCovariance();
388  }
389 
390  // rotation covariance (world-fixed)
391  if (state().orientation()) {
392  pose_covariance_msg.block<3,3>(3,3) = state().orientation()->getCovariance();
393  }
394 
395  // position/orientation cross variance
396  if (state().position() && state().orientation()) {
397  pose_covariance_msg.block<3,3>(0,3) = state().orientation()->getCrossVariance(*state().position());
398  pose_covariance_msg.block<3,3>(3,0) = pose_covariance_msg.block<3,3>(0,3).transpose();
399  }
400 
401  // velocity covariance
402  if (state().velocity()) {
403  twist_covariance_msg.block<3,3>(0,0) = state().velocity()->getCovariance();
404  }
405 
406  // angular rate covariance
407  if (state().rate()) {
408  twist_covariance_msg.block<3,3>(3,3) = state().rate()->getCovariance();
409  }
410 
411  // cross velocity/angular_rate variance
412  if (state().velocity() && state().rate()) {
413  pose_covariance_msg.block<3,3>(0,3) = state().velocity()->getCrossVariance(*state().rate());
414  pose_covariance_msg.block<3,3>(3,0) = pose_covariance_msg.block<3,3>(0,3).transpose();
415  }
416  }
417 }
418 
420  tf::Quaternion quaternion;
421  getPosition(pose.getOrigin());
422  getOrientation(quaternion);
423  pose.setRotation(quaternion);
424 }
425 
427  getPose(static_cast<tf::Pose &>(pose));
428  pose.stamp_ = getTimestamp();
429  pose.frame_id_ = nav_frame_;
430 }
431 
432 void PoseEstimation::getPose(geometry_msgs::Pose& pose) {
433  getPosition(pose.position);
434  getOrientation(pose.orientation);
435 }
436 
437 void PoseEstimation::getPose(geometry_msgs::PoseStamped& pose) {
438  getHeader(pose.header);
439  getPose(pose.pose);
440 }
441 
444  point = tf::Point(position.x(), position.y(), position.z());
445 }
446 
448  getPosition(static_cast<tf::Point &>(point));
449  point.stamp_ = getTimestamp();
450  point.frame_id_ = nav_frame_;
451 }
452 
453 void PoseEstimation::getPosition(geometry_msgs::Point& point) {
455  point.x = position.x();
456  point.y = position.y();
457  point.z = position.z();
458 }
459 
460 void PoseEstimation::getPosition(geometry_msgs::PointStamped& point) {
461  getHeader(point.header);
462  getPosition(point.point);
463 }
464 
465 void PoseEstimation::getGlobal(double &latitude, double &longitude, double &altitude) {
467  double north = position.x() * globalReference()->heading().cos - position.y() * globalReference()->heading().sin;
468  double east = -position.x() * globalReference()->heading().sin - position.y() * globalReference()->heading().cos;
469  latitude = globalReference()->position().latitude + north / globalReference()->radius().north;
470  longitude = globalReference()->position().longitude + east / globalReference()->radius().east;
471  altitude = globalReference()->position().altitude + position.z();
472 }
473 
474 void PoseEstimation::getGlobalPosition(double &latitude, double &longitude, double &altitude) {
475  getGlobal(latitude, longitude, altitude);
476 }
477 
478 void PoseEstimation::getGlobal(geographic_msgs::GeoPoint& global)
479 {
480  getGlobalPosition(global.latitude, global.longitude, global.altitude);
481  global.latitude *= 180.0/M_PI;
482  global.longitude *= 180.0/M_PI;
483 }
484 
485 void PoseEstimation::getGlobal(sensor_msgs::NavSatFix& global)
486 {
487  getHeader(global.header);
488  global.header.frame_id = world_frame_;
489 
490  if ((getSystemStatus() & STATE_POSITION_XY) && globalReference()->hasPosition()) {
491  global.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
492  } else {
493  global.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
494  }
495 
496  getGlobalPosition(global.latitude, global.longitude, global.altitude);
497  global.latitude *= 180.0/M_PI;
498  global.longitude *= 180.0/M_PI;
499 
501  global.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
502  } else {
503  global.status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
504  }
505 }
506 
507 void PoseEstimation::getGlobalPosition(sensor_msgs::NavSatFix& global)
508 {
509  getGlobal(global);
510 }
511 
512 void PoseEstimation::getGlobal(geographic_msgs::GeoPoint& position, geometry_msgs::Quaternion& quaternion)
513 {
514  getGlobal(position);
515  Quaternion global_orientation = globalReference()->heading().quaternion() * Quaternion(state().getOrientation());
516  quaternion.w = global_orientation.w();
517  quaternion.x = global_orientation.x();
518  quaternion.y = global_orientation.y();
519  quaternion.z = global_orientation.z();
520 }
521 
522 void PoseEstimation::getGlobal(geographic_msgs::GeoPose& global)
523 {
524  getGlobal(global.position, global.orientation);
525 }
526 
528  Quaternion orientation(state().getOrientation());
529  quaternion = tf::Quaternion(orientation.x(), orientation.y(), orientation.z(), orientation.w());
530 }
531 
533  getOrientation(static_cast<tf::Quaternion &>(quaternion));
534  quaternion.stamp_ = getTimestamp();
535  quaternion.frame_id_ = nav_frame_;
536 }
537 
539  Quaternion orientation(state().getOrientation());
540  quaternion.w = orientation.w();
541  quaternion.x = orientation.x();
542  quaternion.y = orientation.y();
543  quaternion.z = orientation.z();
544 }
545 
546 void PoseEstimation::getOrientation(geometry_msgs::QuaternionStamped& quaternion) {
547  getHeader(quaternion.header);
548  getOrientation(quaternion.quaternion);
549 }
550 
551 void PoseEstimation::getOrientation(double &yaw, double &pitch, double &roll) {
552  tf::Quaternion quaternion;
553  getOrientation(quaternion);
554 #ifdef TF_MATRIX3x3_H
555  tf::Matrix3x3(quaternion).getRPY(roll, pitch, yaw);
556 #else
557  btMatrix3x3(quaternion).getRPY(roll, pitch, yaw);
558 #endif
559 }
560 
561 void PoseEstimation::getImuWithBiases(geometry_msgs::Vector3& linear_acceleration, geometry_msgs::Vector3& angular_velocity) {
562  boost::shared_ptr<const ImuInput> input = boost::dynamic_pointer_cast<const ImuInput>(getInput("imu"));
563  boost::shared_ptr<const Accelerometer> accel = boost::dynamic_pointer_cast<const Accelerometer>(getSystem("accelerometer"));
564 
565  if (input) {
566  linear_acceleration.x = input->getAcceleration().x();
567  linear_acceleration.y = input->getAcceleration().y();
568  linear_acceleration.z = input->getAcceleration().z();
569  } else {
570  linear_acceleration.x = 0.0;
571  linear_acceleration.y = 0.0;
572  linear_acceleration.z = 0.0;
573  }
574 
575  if (accel) {
576  linear_acceleration.x -= accel->getModel()->getError().x();
577  linear_acceleration.y -= accel->getModel()->getError().y();
578  linear_acceleration.z -= accel->getModel()->getError().z();
579  }
580 
581  getRate(angular_velocity);
582 }
583 
586  vector = tf::Vector3(velocity.x(), velocity.y(), velocity.z());
587 }
588 
590  getVelocity(static_cast<tf::Vector3 &>(vector));
591  vector.stamp_ = getTimestamp();
592  vector.frame_id_ = nav_frame_;
593 }
594 
595 void PoseEstimation::getVelocity(geometry_msgs::Vector3& vector) {
597  vector.x = velocity.x();
598  vector.y = velocity.y();
599  vector.z = velocity.z();
600 }
601 
602 void PoseEstimation::getVelocity(geometry_msgs::Vector3Stamped& vector) {
603  getHeader(vector.header);
604  getVelocity(vector.vector);
605 }
606 
608  geometry_msgs::Vector3 rate;
609  getRate(rate);
610  vector = tf::Vector3(rate.x, rate.y, rate.z);
611 }
612 
614  getRate(static_cast<tf::Vector3 &>(vector));
615  vector.stamp_ = getTimestamp();
616  vector.frame_id_ = base_frame_;
617 }
618 
619 void PoseEstimation::getRate(geometry_msgs::Vector3& vector) {
620  if (state().rate()) {
622  vector.x = rate.x();
623  vector.y = rate.y();
624  vector.z = rate.z();
625 
626  } else {
627  boost::shared_ptr<const ImuInput> input = boost::dynamic_pointer_cast<const ImuInput>(getInput("imu"));
628  boost::shared_ptr<const Gyro> gyro = boost::dynamic_pointer_cast<const Gyro>(getSystem("gyro"));
629 
630  if (input) {
631  vector.x = input->getRate().x();
632  vector.y = input->getRate().y();
633  vector.z = input->getRate().z();
634  } else {
635  vector.x = 0.0;
636  vector.y = 0.0;
637  vector.z = 0.0;
638  }
639 
640  if (gyro) {
641  vector.x -= gyro->getModel()->getError().x();
642  vector.y -= gyro->getModel()->getError().y();
643  vector.z -= gyro->getModel()->getError().z();
644  }
645  }
646 }
647 
648 void PoseEstimation::getRate(geometry_msgs::Vector3Stamped& vector) {
649  getHeader(vector.header);
650  getRate(vector.vector);
651  vector.header.frame_id = base_frame_;
652 }
653 
654 void PoseEstimation::getBias(geometry_msgs::Vector3& angular_velocity, geometry_msgs::Vector3& linear_acceleration) {
655  boost::shared_ptr<const Accelerometer> accel = boost::dynamic_pointer_cast<const Accelerometer>(getSystem("accelerometer"));
656  boost::shared_ptr<const Gyro> gyro = boost::dynamic_pointer_cast<const Gyro>(getSystem("gyro"));
657 
658  if (gyro) {
659  angular_velocity.x = gyro->getModel()->getError().x();
660  angular_velocity.y = gyro->getModel()->getError().y();
661  angular_velocity.z = gyro->getModel()->getError().z();
662  } else {
663  angular_velocity.x = 0.0;
664  angular_velocity.y = 0.0;
665  angular_velocity.z = 0.0;
666  }
667 
668  if (accel) {
669  linear_acceleration.x = accel->getModel()->getError().x();
670  linear_acceleration.y = accel->getModel()->getError().y();
671  linear_acceleration.z = accel->getModel()->getError().z();
672  } else {
673  linear_acceleration.x = 0.0;
674  linear_acceleration.y = 0.0;
675  linear_acceleration.z = 0.0;
676  }
677 }
678 
679 void PoseEstimation::getBias(geometry_msgs::Vector3Stamped& angular_velocity, geometry_msgs::Vector3Stamped& linear_acceleration) {
680  getBias(angular_velocity.vector, linear_acceleration.vector);
681  angular_velocity.header.stamp = getTimestamp();
682  angular_velocity.header.frame_id = base_frame_;
683  linear_acceleration.header.stamp = getTimestamp();
684  linear_acceleration.header.frame_id = base_frame_;
685 }
686 
687 void PoseEstimation::getTransforms(std::vector<tf::StampedTransform>& transforms) {
688  tf::Quaternion orientation;
689  tf::Point position;
690  getOrientation(orientation);
691  getPosition(position);
692 
693  tf::Transform transform(orientation, position);
694  double y,p,r;
695  transform.getBasis().getEulerYPR(y,p,r);
696 
697  std::string parent_frame = nav_frame_;
698 
699  if(!position_frame_.empty()) {
700  tf::Transform position_transform;
701  position_transform.getBasis().setIdentity();
702  position_transform.setOrigin(tf::Point(position.x(), position.y(), position.z()));
703  transforms.push_back(tf::StampedTransform(position_transform, getTimestamp(), parent_frame, position_frame_ ));
704  }
705 
706  if (!footprint_frame_.empty()) {
707  tf::Transform footprint_transform;
708  footprint_transform.getBasis().setEulerYPR(y, 0.0, 0.0);
709  footprint_transform.setOrigin(tf::Point(position.x(), position.y(), 0.0));
710  transforms.push_back(tf::StampedTransform(footprint_transform, getTimestamp(), parent_frame, footprint_frame_));
711 
712  parent_frame = footprint_frame_;
713  transform = footprint_transform.inverseTimes(transform);
714  }
715 
716  if (!stabilized_frame_.empty()) {
717  tf::Transform stabilized_transform(transform);
718 #ifdef TF_MATRIX3x3_H
719  tf::Matrix3x3 rollpitch_rotation; rollpitch_rotation.setEulerYPR(0.0, p, r);
720 #else
721  btMatrix3x3 rollpitch_rotation; rollpitch_rotation.setEulerYPR(0.0, p, r);
722 #endif
723  stabilized_transform = stabilized_transform * tf::Transform(rollpitch_rotation.inverse());
724  transforms.push_back(tf::StampedTransform(stabilized_transform, getTimestamp(), parent_frame, stabilized_frame_));
725 
726  parent_frame = stabilized_frame_;
727  transform = stabilized_transform.inverseTimes(transform);
728  }
729 
730  transforms.push_back(tf::StampedTransform(transform, getTimestamp(), parent_frame, base_frame_));
731 
732 // transforms.resize(3);
733 
734 // transforms[0].stamp_ = getTimestamp();
735 // transforms[0].frame_id_ = nav_frame_;
736 // transforms[0].child_frame_id_ = footprint_frame_;
737 // transforms[0].setOrigin(tf::Point(position.x(), position.y(), 0.0));
738 // rotation.setEulerYPR(y,0.0,0.0);
739 // transforms[0].setBasis(rotation);
740 
741 // transforms[1].stamp_ = getTimestamp();
742 // transforms[1].frame_id_ = footprint_frame_;
743 // transforms[1].child_frame_id_ = stabilized_frame_;
744 // transforms[1].setIdentity();
745 // transforms[1].setOrigin(tf::Point(0.0, 0.0, position.z()));
746 
747 // transforms[2].stamp_ = getTimestamp();
748 // transforms[2].frame_id_ = stabilized_frame_;
749 // transforms[2].child_frame_id_ = base_frame_;
750 // transforms[2].setIdentity();
751 // rotation.setEulerYPR(0.0,p,r);
752 // transforms[2].setBasis(rotation);
753 }
754 
756  world_to_other_transform.frame_id_ = world_frame_;
757 
758  double y,p,r;
759  world_to_other_transform.getBasis().getEulerYPR(y,p,r);
760  if (!(getSystemStatus() & (STATE_ROLLPITCH | STATE_PSEUDO_ROLLPITCH))) { r = p = 0.0; }
761  if (!(getSystemStatus() & (STATE_YAW | STATE_PSEUDO_YAW))) { y = 0.0; }
762  if (!(getSystemStatus() & (STATE_POSITION_XY | STATE_PSEUDO_POSITION_XY))) { world_to_other_transform.getOrigin().setX(0.0); world_to_other_transform.getOrigin().setY(0.0); }
763  if (!(getSystemStatus() & (STATE_POSITION_Z | STATE_PSEUDO_POSITION_Z))) { world_to_other_transform.getOrigin().setZ(0.0); }
764  world_to_other_transform.getBasis().setEulerYPR(y, p, r);
765 }
766 
767 bool PoseEstimation::getWorldToNavTransform(geometry_msgs::TransformStamped& transform) {
768  return globalReference()->getWorldToNavTransform(transform, world_frame_, nav_frame_, getTimestamp());
769 }
770 
772  return GlobalReference::Instance();
773 }
774 
775 } // namespace hector_pose_estimation
virtual bool setSystemStatus(SystemStatus new_status)
const SystemPtr & addSystem(const SystemPtr &system, const std::string &name="system")
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
#define ROS_FATAL(...)
virtual void getRate(tf::Vector3 &vector)
boost::shared_ptr< ZeroRate > zerorate_update_
TFSIMD_FORCE_INLINE void setX(tfScalar x)
virtual const GlobalReferencePtr & globalReference()
virtual bool updateMeasurementStatus(SystemStatus set, SystemStatus clear)
TFSIMD_FORCE_INLINE void setY(tfScalar y)
virtual const boost::shared_ptr< OrientationStateType > & orientation() const
Definition: state.h:112
virtual ParameterList & parameters()
virtual const State & state() const
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
SymmetricMatrix Covariance
Definition: state.h:45
InputPtr getInput(const std::string &name) const
static const GlobalReferencePtr & Instance()
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
virtual const std::string & getName() const
Definition: input.h:44
virtual void getPose(tf::Pose &pose)
const Ptr & add(const Ptr &p, const key_type &key)
Definition: collection.h:51
PoseEstimation(const SystemPtr &system=SystemPtr(), const StatePtr &state=StatePtr())
virtual void updateWorldToOtherTransform(tf::StampedTransform &world_to_other_transform)
const_iterator end() const
Definition: collection.h:93
const_iterator begin() const
Definition: collection.h:92
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
const State::RotationMatrix & R() const
Definition: state.cpp:131
void setEulerYPR(tfScalar eulerZ, tfScalar eulerY, tfScalar eulerX)
virtual const boost::shared_ptr< PositionStateType > & position() const
Definition: state.h:114
void setRate(const Eigen::MatrixBase< Derived > &rate)
tf::Vector3 Point
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
void setIdentity()
InputPtr setInput(const Input &input, std::string name=std::string())
Ptr get(const key_type &key) const
Definition: collection.h:75
SystemPtr getSystem(const std::string &name) const
ParameterList & add(const std::string &key, T &value, const T &default_value)
Definition: parameters.h:148
TFSIMD_FORCE_INLINE const tfScalar & x() const
Eigen::Quaternion< ScalarType > Quaternion
Definition: matrix.h:49
virtual const Covariance & getCovariance() const
Definition: state.h:89
virtual void getImuWithBiases(geometry_msgs::Vector3 &linear_acceleration, geometry_msgs::Vector3 &angular_velocity)
virtual void getTransforms(std::vector< tf::StampedTransform > &transforms)
TFSIMD_FORCE_INLINE const tfScalar & z() const
virtual const ros::Time & getTimestamp() const
boost::shared_ptr< Gravity > gravity_update_
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
virtual void getHeader(std_msgs::Header &header)
virtual void getPosition(tf::Point &point)
virtual SystemStatus getMeasurementStatus() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
virtual const Vector & getVector() const
Definition: state.h:88
virtual bool inSystemStatus(SystemStatus test_status) const
Definition: state.cpp:211
const MeasurementPtr & addMeasurement(const MeasurementPtr &measurement, const std::string &name=std::string())
unsigned int SystemStatus
Definition: types.h:70
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
virtual const boost::shared_ptr< VelocityStateType > & velocity() const
Definition: state.h:115
virtual void getState(nav_msgs::Odometry &state, bool with_covariances=true)
boost::shared_ptr< InputType > addInput(const std::string &name=std::string())
virtual bool updateSystemStatus(SystemStatus set, SystemStatus clear)
Definition: state.cpp:241
virtual SystemStatus getSystemStatus() const
Definition: state.h:100
virtual bool setMeasurementStatus(SystemStatus new_status)
Definition: state.cpp:231
ros::Time stamp_
void setTimestamp(const ros::Time &timestamp)
Definition: state.h:148
boost::shared_ptr< Rate > rate_update_
virtual bool getWorldToNavTransform(geometry_msgs::TransformStamped &transform)
std::string frame_id_
virtual void getGlobalPosition(double &latitude, double &longitude, double &altitude)
virtual bool setSystemStatus(SystemStatus new_status)
Definition: state.cpp:215
virtual Model * getModel() const
Definition: system.h:118
virtual bool inSystemStatus(SystemStatus test_status) const
virtual void setTimestamp(const ros::Time &timestamp)
static Time now()
virtual const boost::shared_ptr< RateStateType > & rate() const
Definition: state.h:113
virtual void getVelocity(tf::Vector3 &vector)
VectorBlock< const Vector, 3 > ConstRateType
Definition: state.h:58
virtual const State::Covariance & getCovariance()
void setAcceleration(const Eigen::MatrixBase< Derived > &acceleration)
virtual const State::Vector & getStateVector()
virtual SystemStatus getSystemStatus() const
virtual bool setMeasurementStatus(SystemStatus new_status)
virtual bool updateSystemStatus(SystemStatus set, SystemStatus clear)
VectorBlock< const Vector, 3 > ConstPositionType
Definition: state.h:61
virtual void getBias(geometry_msgs::Vector3 &angular_velocity, geometry_msgs::Vector3 &linear_acceleration)
boost::shared_ptr< Input > InputPtr
Definition: types.h:94
virtual SystemStatus getMeasurementStatus() const
Definition: state.h:101
const ros::Time & getTimestamp() const
Definition: state.h:147
virtual bool updateMeasurementStatus(SystemStatus set, SystemStatus clear)
Definition: state.cpp:245
Transform inverseTimes(const Transform &t) const
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
ColumnVector_< 3 >::type ColumnVector3
Definition: matrix.h:59
virtual void getGlobal(double &latitude, double &longitude, double &altitude)
VectorBlock< const Vector, 3 > ConstVelocityType
Definition: state.h:64
std::string frame_id_
virtual void getOrientation(tf::Quaternion &quaternion)


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:30