navsat_transform.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.
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
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  * 3. Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
38 
40 #include <XmlRpcException.h>
41 
42 #include <string>
43 
44 namespace RobotLocalization
45 {
47  magnetic_declination_(0.0),
48  utm_odom_tf_yaw_(0.0),
49  yaw_offset_(0.0),
50  transform_timeout_(ros::Duration(0)),
51  broadcast_utm_transform_(false),
52  broadcast_utm_transform_as_parent_frame_(false),
53  has_transform_odom_(false),
54  has_transform_gps_(false),
55  has_transform_imu_(false),
56  transform_good_(false),
57  gps_frame_id_(""),
58  gps_updated_(false),
59  odom_updated_(false),
60  publish_gps_(false),
61  use_odometry_yaw_(false),
62  use_manual_datum_(false),
63  zero_altitude_(false),
64  world_frame_id_("odom"),
65  base_link_frame_id_("base_link"),
66  utm_zone_(""),
67  tf_listener_(tf_buffer_)
68  {
69  ROS_INFO("Waiting for valid clock time...");
71  ROS_INFO("Valid clock time received. Starting node.");
72 
75 
76  double frequency;
77  double delay = 0.0;
78  double transform_timeout = 0.0;
79 
80  // Load the parameters we need
81  nh_priv.getParam("magnetic_declination_radians", magnetic_declination_);
82  nh_priv.param("yaw_offset", yaw_offset_, 0.0);
83  nh_priv.param("broadcast_utm_transform", broadcast_utm_transform_, false);
84  nh_priv.param("broadcast_utm_transform_as_parent_frame", broadcast_utm_transform_as_parent_frame_, false);
85  nh_priv.param("zero_altitude", zero_altitude_, false);
86  nh_priv.param("publish_filtered_gps", publish_gps_, false);
87  nh_priv.param("use_odometry_yaw", use_odometry_yaw_, false);
88  nh_priv.param("wait_for_datum", use_manual_datum_, false);
89  nh_priv.param("frequency", frequency, 10.0);
90  nh_priv.param("delay", delay, 0.0);
91  nh_priv.param("transform_timeout", transform_timeout, 0.0);
92  transform_timeout_.fromSec(transform_timeout);
93 
94  // Subscribe to the messages and services we need
96 
97  if (use_manual_datum_ && nh_priv.hasParam("datum"))
98  {
99  XmlRpc::XmlRpcValue datum_config;
100 
101  try
102  {
103  double datum_lat;
104  double datum_lon;
105  double datum_yaw;
106 
107  nh_priv.getParam("datum", datum_config);
108 
109  // Handle datum specification. Users should always specify a baseLinkFrameId_ in the
110  // datum config, but we had a release where it wasn't used, so we'll maintain compatibility.
112  ROS_ASSERT(datum_config.size() >= 3);
113 
114  if (datum_config.size() > 3)
115  {
116  ROS_WARN_STREAM("Deprecated datum parameter configuration detected. Only the first three parameters "
117  "(latitude, longitude, yaw) will be used. frame_ids will be derived from odometry and navsat inputs.");
118  }
119 
120  std::ostringstream ostr;
121  ostr << std::setprecision(20) << datum_config[0] << " " << datum_config[1] << " " << datum_config[2];
122  std::istringstream istr(ostr.str());
123  istr >> datum_lat >> datum_lon >> datum_yaw;
124 
125  // Try to resolve tf_prefix
126  std::string tf_prefix = "";
127  std::string tf_prefix_path = "";
128  if (nh_priv.searchParam("tf_prefix", tf_prefix_path))
129  {
130  nh_priv.getParam(tf_prefix_path, tf_prefix);
131  }
132 
133  // Append the tf prefix in a tf2-friendly manner
136 
137  robot_localization::SetDatum::Request request;
138  request.geo_pose.position.latitude = datum_lat;
139  request.geo_pose.position.longitude = datum_lon;
140  request.geo_pose.position.altitude = 0.0;
141  tf2::Quaternion quat;
142  quat.setRPY(0.0, 0.0, datum_yaw);
143  request.geo_pose.orientation = tf2::toMsg(quat);
144  robot_localization::SetDatum::Response response;
145  datumCallback(request, response);
146  }
147  catch (XmlRpc::XmlRpcException &e)
148  {
149  ROS_ERROR_STREAM("ERROR reading sensor config: " << e.getMessage() <<
150  " for process_noise_covariance (type: " << datum_config.getType() << ")");
151  }
152  }
153 
154  odom_sub_ = nh.subscribe("odometry/filtered", 1, &NavSatTransform::odomCallback, this);
155  gps_sub_ = nh.subscribe("gps/fix", 1, &NavSatTransform::gpsFixCallback, this);
156 
158  {
159  imu_sub_ = nh.subscribe("imu/data", 1, &NavSatTransform::imuCallback, this);
160  }
161 
162  gps_odom_pub_ = nh.advertise<nav_msgs::Odometry>("odometry/gps", 10);
163 
164  if (publish_gps_)
165  {
166  filtered_gps_pub_ = nh.advertise<sensor_msgs::NavSatFix>("gps/filtered", 10);
167  }
168 
169  // Sleep for the parameterized amount of time, to give
170  // other nodes time to start up (not always necessary)
171  ros::Duration start_delay(delay);
172  start_delay.sleep();
173 
175  }
176 
178  {
179  }
180 
181 // void NavSatTransform::run()
183  {
184  if (!transform_good_)
185  {
187 
189  {
190  // Once we have the transform, we don't need the IMU
191  imu_sub_.shutdown();
192  }
193  }
194  else
195  {
196  nav_msgs::Odometry gps_odom;
197  if (prepareGpsOdometry(gps_odom))
198  {
199  gps_odom_pub_.publish(gps_odom);
200  }
201 
202  if (publish_gps_)
203  {
204  sensor_msgs::NavSatFix odom_gps;
205  if (prepareFilteredGps(odom_gps))
206  {
207  filtered_gps_pub_.publish(odom_gps);
208  }
209  }
210  }
211  }
212 
214  {
215  // Only do this if:
216  // 1. We haven't computed the odom_frame->utm_frame transform before
217  // 2. We've received the data we need
218  if (!transform_good_ &&
222  {
223  // The UTM pose we have is given at the location of the GPS sensor on the robot. We need to get the UTM pose of
224  // the robot's origin.
225  tf2::Transform transform_utm_pose_corrected;
226  if (!use_manual_datum_)
227  {
228  getRobotOriginUtmPose(transform_utm_pose_, transform_utm_pose_corrected, ros::Time(0));
229  }
230  else
231  {
232  transform_utm_pose_corrected = transform_utm_pose_;
233  }
234 
235  // Get the IMU's current RPY values. Need the raw values (for yaw, anyway).
237 
238  // Convert to RPY
239  double imu_roll;
240  double imu_pitch;
241  double imu_yaw;
242  mat.getRPY(imu_roll, imu_pitch, imu_yaw);
243 
244  /* The IMU's heading was likely originally reported w.r.t. magnetic north.
245  * However, all the nodes in robot_localization assume that orientation data,
246  * including that reported by IMUs, is reported in an ENU frame, with a 0 yaw
247  * value being reported when facing east and increasing counter-clockwise (i.e.,
248  * towards north). To make the world frame ENU aligned, where X is east
249  * and Y is north, we have to take into account three additional considerations:
250  * 1. The IMU may have its non-ENU frame data transformed to ENU, but there's
251  * a possibility that its data has not been corrected for magnetic
252  * declination. We need to account for this. A positive magnetic
253  * declination is counter-clockwise in an ENU frame. Therefore, if
254  * we have a magnetic declination of N radians, then when the sensor
255  * is facing a heading of N, it reports 0. Therefore, we need to add
256  * the declination angle.
257  * 2. To account for any other offsets that may not be accounted for by the
258  * IMU driver or any interim processing node, we expose a yaw offset that
259  * lets users work with navsat_transform_node.
260  * 3. UTM grid isn't aligned with True East\North. To account for the difference
261  * we need to add meridian convergence angle.
262  */
264 
265  ROS_INFO_STREAM("Corrected for magnetic declination of " << std::fixed << magnetic_declination_ <<
266  ", user-specified offset of " << yaw_offset_ <<
267  " and meridian convergence of " << utm_meridian_convergence_ << "." <<
268  " Transform heading factor is now " << imu_yaw);
269 
270  // Convert to tf-friendly structures
271  tf2::Quaternion imu_quat;
272  imu_quat.setRPY(0.0, 0.0, imu_yaw);
273 
274  // The transform order will be orig_odom_pos * orig_utm_pos_inverse * cur_utm_pos.
275  // Doing it this way will allow us to cope with having non-zero odometry position
276  // when we get our first GPS message.
277  tf2::Transform utm_pose_with_orientation;
278  utm_pose_with_orientation.setOrigin(transform_utm_pose_corrected.getOrigin());
279  utm_pose_with_orientation.setRotation(imu_quat);
280 
281  utm_world_transform_.mult(transform_world_pose_, utm_pose_with_orientation.inverse());
282 
284 
285  ROS_INFO_STREAM("Transform world frame pose is: " << transform_world_pose_);
286  ROS_INFO_STREAM("World frame->utm transform is " << utm_world_transform_);
287 
288  transform_good_ = true;
289 
290  // Send out the (static) UTM transform in case anyone else would like to use it.
292  {
293  geometry_msgs::TransformStamped utm_transform_stamped;
294  utm_transform_stamped.header.stamp = ros::Time::now();
295  utm_transform_stamped.header.frame_id = (broadcast_utm_transform_as_parent_frame_ ? "utm" : world_frame_id_);
296  utm_transform_stamped.child_frame_id = (broadcast_utm_transform_as_parent_frame_ ? world_frame_id_ : "utm");
297  utm_transform_stamped.transform = (broadcast_utm_transform_as_parent_frame_ ?
299  utm_transform_stamped.transform.translation.z = (zero_altitude_ ?
300  0.0 : utm_transform_stamped.transform.translation.z);
301  utm_broadcaster_.sendTransform(utm_transform_stamped);
302  }
303  }
304  }
305 
306  bool NavSatTransform::datumCallback(robot_localization::SetDatum::Request& request,
307  robot_localization::SetDatum::Response&)
308  {
309  // If we get a service call with a manual datum, even if we already computed the transform using the robot's
310  // initial pose, then we want to assume that we are using a datum from now on, and we want other methods to
311  // not attempt to transform the values we are specifying here.
312  use_manual_datum_ = true;
313 
314  transform_good_ = false;
315 
316  sensor_msgs::NavSatFix *fix = new sensor_msgs::NavSatFix();
317  fix->latitude = request.geo_pose.position.latitude;
318  fix->longitude = request.geo_pose.position.longitude;
319  fix->altitude = request.geo_pose.position.altitude;
320  fix->header.stamp = ros::Time::now();
321  fix->position_covariance[0] = 0.1;
322  fix->position_covariance[4] = 0.1;
323  fix->position_covariance[8] = 0.1;
324  fix->position_covariance_type = sensor_msgs::NavSatStatus::STATUS_FIX;
325  sensor_msgs::NavSatFixConstPtr fix_ptr(fix);
326  setTransformGps(fix_ptr);
327 
328  nav_msgs::Odometry *odom = new nav_msgs::Odometry();
329  odom->pose.pose.orientation.x = 0;
330  odom->pose.pose.orientation.y = 0;
331  odom->pose.pose.orientation.z = 0;
332  odom->pose.pose.orientation.w = 1;
333  odom->pose.pose.position.x = 0;
334  odom->pose.pose.position.y = 0;
335  odom->pose.pose.position.z = 0;
336  odom->header.frame_id = world_frame_id_;
337  odom->child_frame_id = base_link_frame_id_;
338  nav_msgs::OdometryConstPtr odom_ptr(odom);
339  setTransformOdometry(odom_ptr);
340 
341  sensor_msgs::Imu *imu = new sensor_msgs::Imu();
342  imu->orientation = request.geo_pose.orientation;
343  imu->header.frame_id = base_link_frame_id_;
344  sensor_msgs::ImuConstPtr imu_ptr(imu);
345  imuCallback(imu_ptr);
346 
347  return true;
348  }
349 
351  tf2::Transform &robot_utm_pose,
352  const ros::Time &transform_time)
353  {
354  robot_utm_pose.setIdentity();
355 
356  // Get linear offset from origin for the GPS
357  tf2::Transform offset;
361  transform_time,
363  offset);
364 
365  if (can_transform)
366  {
367  // Get the orientation we'll use for our UTM->world transform
368  tf2::Quaternion utm_orientation = transform_orientation_;
369  tf2::Matrix3x3 mat(utm_orientation);
370 
371  // Add the offsets
372  double roll;
373  double pitch;
374  double yaw;
375  mat.getRPY(roll, pitch, yaw);
377  utm_orientation.setRPY(roll, pitch, yaw);
378 
379  // Rotate the GPS linear offset by the orientation
380  // Zero out the orientation, because the GPS orientation is meaningless, and if it's non-zero, it will make the
381  // the computation of robot_utm_pose erroneous.
382  offset.setOrigin(tf2::quatRotate(utm_orientation, offset.getOrigin()));
384 
385  // Update the initial pose
386  robot_utm_pose = offset.inverse() * gps_utm_pose;
387  }
388  else
389  {
390  if (gps_frame_id_ != "")
391  {
392  ROS_WARN_STREAM_ONCE("Unable to obtain " << base_link_frame_id_ << "->" << gps_frame_id_ <<
393  " transform. Will assume navsat device is mounted at robot's origin");
394  }
395 
396  robot_utm_pose = gps_utm_pose;
397  }
398  }
399 
401  tf2::Transform &robot_odom_pose,
402  const ros::Time &transform_time)
403  {
404  robot_odom_pose.setIdentity();
405 
406  // Remove the offset from base_link
407  tf2::Transform gps_offset_rotated;
411  transform_time,
413  gps_offset_rotated);
414 
415  if (can_transform)
416  {
417  tf2::Transform robot_orientation;
421  transform_time,
423  robot_orientation);
424 
425  if (can_transform)
426  {
427  // Zero out rotation because we don't care about the orientation of the
428  // GPS receiver relative to base_link
429  gps_offset_rotated.setOrigin(tf2::quatRotate(robot_orientation.getRotation(), gps_offset_rotated.getOrigin()));
430  gps_offset_rotated.setRotation(tf2::Quaternion::getIdentity());
431  robot_odom_pose = gps_offset_rotated.inverse() * gps_odom_pose;
432  }
433  else
434  {
435  ROS_WARN_STREAM_THROTTLE(5.0, "Could not obtain " << world_frame_id_ << "->" << base_link_frame_id_ <<
436  " transform. Will not remove offset of navsat device from robot's origin.");
437  }
438  }
439  else
440  {
441  ROS_WARN_STREAM_THROTTLE(5.0, "Could not obtain " << base_link_frame_id_ << "->" << gps_frame_id_ <<
442  " transform. Will not remove offset of navsat device from robot's origin.");
443  }
444  }
445 
446  void NavSatTransform::gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg)
447  {
448  gps_frame_id_ = msg->header.frame_id;
449 
450  if (gps_frame_id_.empty())
451  {
452  ROS_WARN_STREAM_ONCE("NavSatFix message has empty frame_id. Will assume navsat device is mounted at robot's "
453  "origin.");
454  }
455 
456  // Make sure the GPS data is usable
457  bool good_gps = (msg->status.status != sensor_msgs::NavSatStatus::STATUS_NO_FIX &&
458  !std::isnan(msg->altitude) &&
459  !std::isnan(msg->latitude) &&
460  !std::isnan(msg->longitude));
461 
462  if (good_gps)
463  {
464  // If we haven't computed the transform yet, then
465  // store this message as the initial GPS data to use
467  {
468  setTransformGps(msg);
469  }
470 
471  double utmX = 0;
472  double utmY = 0;
473  std::string utm_zone_tmp;
474  NavsatConversions::LLtoUTM(msg->latitude, msg->longitude, utmY, utmX, utm_zone_tmp);
475  latest_utm_pose_.setOrigin(tf2::Vector3(utmX, utmY, msg->altitude));
476  latest_utm_covariance_.setZero();
477 
478  // Copy the measurement's covariance matrix so that we can rotate it later
479  for (size_t i = 0; i < POSITION_SIZE; i++)
480  {
481  for (size_t j = 0; j < POSITION_SIZE; j++)
482  {
483  latest_utm_covariance_(i, j) = msg->position_covariance[POSITION_SIZE * i + j];
484  }
485  }
486 
487  gps_update_time_ = msg->header.stamp;
488  gps_updated_ = true;
489  }
490  }
491 
492  void NavSatTransform::imuCallback(const sensor_msgs::ImuConstPtr& msg)
493  {
494  // We need the baseLinkFrameId_ from the odometry message, so
495  // we need to wait until we receive it.
497  {
498  /* This method only gets called if we don't yet have the
499  * IMU data (the subscriber gets shut down once we compute
500  * the transform), so we can assumed that every IMU message
501  * that comes here is meant to be used for that purpose. */
502  tf2::fromMsg(msg->orientation, transform_orientation_);
503 
504  // Correct for the IMU's orientation w.r.t. base_link
505  tf2::Transform target_frame_trans;
508  msg->header.frame_id,
509  msg->header.stamp,
511  target_frame_trans);
512 
513  if (can_transform)
514  {
515  double roll_offset = 0;
516  double pitch_offset = 0;
517  double yaw_offset = 0;
518  double roll = 0;
519  double pitch = 0;
520  double yaw = 0;
521  RosFilterUtilities::quatToRPY(target_frame_trans.getRotation(), roll_offset, pitch_offset, yaw_offset);
523 
524  ROS_DEBUG_STREAM("Initial orientation is " << transform_orientation_);
525 
526  // Apply the offset (making sure to bound them), and throw them in a vector
527  tf2::Vector3 rpy_angles(FilterUtilities::clampRotation(roll - roll_offset),
528  FilterUtilities::clampRotation(pitch - pitch_offset),
529  FilterUtilities::clampRotation(yaw - yaw_offset));
530 
531  // Now we need to rotate the roll and pitch by the yaw offset value.
532  // Imagine a case where an IMU is mounted facing sideways. In that case
533  // pitch for the IMU's world frame is roll for the robot.
534  tf2::Matrix3x3 mat;
535  mat.setRPY(0.0, 0.0, yaw_offset);
536  rpy_angles = mat * rpy_angles;
537  transform_orientation_.setRPY(rpy_angles.getX(), rpy_angles.getY(), rpy_angles.getZ());
538 
539  ROS_DEBUG_STREAM("Initial corrected orientation roll, pitch, yaw is (" <<
540  rpy_angles.getX() << ", " << rpy_angles.getY() << ", " << rpy_angles.getZ() << ")");
541 
542  has_transform_imu_ = true;
543  }
544  }
545  }
546 
547  void NavSatTransform::odomCallback(const nav_msgs::OdometryConstPtr& msg)
548  {
549  world_frame_id_ = msg->header.frame_id;
550  base_link_frame_id_ = msg->child_frame_id;
551 
553  {
555  }
556 
557  tf2::fromMsg(msg->pose.pose, latest_world_pose_);
558  latest_odom_covariance_.setZero();
559  for (size_t row = 0; row < POSE_SIZE; ++row)
560  {
561  for (size_t col = 0; col < POSE_SIZE; ++col)
562  {
563  latest_odom_covariance_(row, col) = msg->pose.covariance[row * POSE_SIZE + col];
564  }
565  }
566 
567  odom_update_time_ = msg->header.stamp;
568  odom_updated_ = true;
569  }
570 
571 
572  bool NavSatTransform::prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps)
573  {
574  bool new_data = false;
575 
577  {
578  tf2::Transform odom_as_utm;
579 
582 
583  // Rotate the covariance as well
585  Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE);
586  rot_6d.setIdentity();
587 
588  for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)
589  {
590  rot_6d(rInd, 0) = rot.getRow(rInd).getX();
591  rot_6d(rInd, 1) = rot.getRow(rInd).getY();
592  rot_6d(rInd, 2) = rot.getRow(rInd).getZ();
593  rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();
594  rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();
595  rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();
596  }
597 
598  // Rotate the covariance
599  latest_odom_covariance_ = rot_6d * latest_odom_covariance_.eval() * rot_6d.transpose();
600 
601  // Now convert the data back to lat/long and place into the message
602  NavsatConversions::UTMtoLL(odom_as_utm.getOrigin().getY(),
603  odom_as_utm.getOrigin().getX(),
604  utm_zone_,
605  filtered_gps.latitude,
606  filtered_gps.longitude);
607  filtered_gps.altitude = odom_as_utm.getOrigin().getZ();
608 
609  // Copy the measurement's covariance matrix back
610  for (size_t i = 0; i < POSITION_SIZE; i++)
611  {
612  for (size_t j = 0; j < POSITION_SIZE; j++)
613  {
614  filtered_gps.position_covariance[POSITION_SIZE * i + j] = latest_odom_covariance_(i, j);
615  }
616  }
617 
618  filtered_gps.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
619  filtered_gps.status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
620  filtered_gps.header.frame_id = "gps";
621  filtered_gps.header.stamp = odom_update_time_;
622 
623  // Mark this GPS as used
624  odom_updated_ = false;
625  new_data = true;
626  }
627 
628  return new_data;
629  }
630 
631  bool NavSatTransform::prepareGpsOdometry(nav_msgs::Odometry &gps_odom)
632  {
633  bool new_data = false;
634 
636  {
637  tf2::Transform transformed_utm_gps;
638 
639  transformed_utm_gps.mult(utm_world_transform_, latest_utm_pose_);
640  transformed_utm_gps.setRotation(tf2::Quaternion::getIdentity());
641 
642  // Set header information stamp because we would like to know the robot's position at that timestamp
643  gps_odom.header.frame_id = world_frame_id_;
644  gps_odom.header.stamp = gps_update_time_;
645 
646  // Want the pose of the vehicle origin, not the GPS
647  tf2::Transform transformed_utm_robot;
648  getRobotOriginWorldPose(transformed_utm_gps, transformed_utm_robot, gps_odom.header.stamp);
649 
650  // Rotate the covariance as well
652  Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE);
653  rot_6d.setIdentity();
654 
655  for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)
656  {
657  rot_6d(rInd, 0) = rot.getRow(rInd).getX();
658  rot_6d(rInd, 1) = rot.getRow(rInd).getY();
659  rot_6d(rInd, 2) = rot.getRow(rInd).getZ();
660  rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();
661  rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();
662  rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();
663  }
664 
665  // Rotate the covariance
666  latest_utm_covariance_ = rot_6d * latest_utm_covariance_.eval() * rot_6d.transpose();
667 
668  // Now fill out the message. Set the orientation to the identity.
669  tf2::toMsg(transformed_utm_robot, gps_odom.pose.pose);
670  gps_odom.pose.pose.position.z = (zero_altitude_ ? 0.0 : gps_odom.pose.pose.position.z);
671 
672  // Copy the measurement's covariance matrix so that we can rotate it later
673  for (size_t i = 0; i < POSE_SIZE; i++)
674  {
675  for (size_t j = 0; j < POSE_SIZE; j++)
676  {
677  gps_odom.pose.covariance[POSE_SIZE * i + j] = latest_utm_covariance_(i, j);
678  }
679  }
680 
681  // Mark this GPS as used
682  gps_updated_ = false;
683  new_data = true;
684  }
685 
686  return new_data;
687  }
688 
689  void NavSatTransform::setTransformGps(const sensor_msgs::NavSatFixConstPtr& msg)
690  {
691  double utm_x = 0;
692  double utm_y = 0;
693  NavsatConversions::LLtoUTM(msg->latitude, msg->longitude, utm_y, utm_x, utm_zone_, utm_meridian_convergence_);
695 
696  ROS_INFO_STREAM("Datum (latitude, longitude, altitude) is (" << std::fixed << msg->latitude << ", " <<
697  msg->longitude << ", " << msg->altitude << ")");
698  ROS_INFO_STREAM("Datum UTM coordinate is (" << std::fixed << utm_x << ", " << utm_y << ")");
699 
700  transform_utm_pose_.setOrigin(tf2::Vector3(utm_x, utm_y, msg->altitude));
702  has_transform_gps_ = true;
703  }
704 
705  void NavSatTransform::setTransformOdometry(const nav_msgs::OdometryConstPtr& msg)
706  {
707  tf2::fromMsg(msg->pose.pose, transform_world_pose_);
708  has_transform_odom_ = true;
709 
710  ROS_INFO_STREAM("Initial odometry pose is " << transform_world_pose_);
711 
712  // Users can optionally use the (potentially fused) heading from
713  // the odometry source, which may have multiple fused sources of
714  // heading data, and so would act as a better heading for the
715  // UTM->world_frame transform.
717  {
718  sensor_msgs::Imu *imu = new sensor_msgs::Imu();
719  imu->orientation = msg->pose.pose.orientation;
720  imu->header.frame_id = msg->child_frame_id;
721  imu->header.stamp = msg->header.stamp;
722  sensor_msgs::ImuConstPtr imuPtr(imu);
723  imuCallback(imuPtr);
724  }
725  }
726 
727 } // namespace RobotLocalization
tf2_ros::Buffer tf_buffer_
Transform buffer for managing coordinate transforms.
tf2::Transform transform_world_pose_
Latest IMU orientation.
bool zero_altitude_
Whether or not to report 0 altitude.
std::string world_frame_id_
Frame ID of the GPS odometry output.
tf2_ros::StaticTransformBroadcaster utm_broadcaster_
Used for publishing the static world_frame->utm transform.
const std::string & getMessage() const
void setTransformGps(const sensor_msgs::NavSatFixConstPtr &msg)
Used for setting the GPS data that will be used to compute the transform.
ros::Subscriber odom_sub_
Odometry subscriber.
NavSatTransform(ros::NodeHandle nh, ros::NodeHandle nh_priv)
Constructor.
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
Eigen::MatrixXd latest_odom_covariance_
Covariance for most recent odometry data.
bool datumCallback(robot_localization::SetDatum::Request &request, robot_localization::SetDatum::Response &)
Callback for the datum service.
void getRPY(tf2Scalar &roll, tf2Scalar &pitch, tf2Scalar &yaw, unsigned int solution_number=1) const
void appendPrefix(std::string tfPrefix, std::string &frameId)
Utility method for appending tf2 prefixes cleanly.
bool publish_gps_
Whether or not we publish filtered GPS messages.
void getRobotOriginUtmPose(const tf2::Transform &gps_utm_pose, tf2::Transform &robot_utm_pose, const ros::Time &transform_time)
Given the pose of the navsat sensor in the UTM frame, removes the offset from the vehicle&#39;s centroid ...
#define ROS_WARN_STREAM_THROTTLE(period, args)
static const Quaternion & getIdentity()
bool has_transform_gps_
Whether or not the GPS fix is usable.
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher filtered_gps_pub_
Publiser for filtered gps data.
ros::Duration transform_timeout_
Parameter that specifies the how long we wait for a transform to become available.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Quaternion getRotation() const
TF2SIMD_FORCE_INLINE void setRotation(const Quaternion &q)
double utm_meridian_convergence_
UTM&#39;s meridian convergence.
int size() const
std::string base_link_frame_id_
Frame ID of the robot&#39;s body frame.
bool has_transform_imu_
Signifies that we have received a usable IMU message.
std::string utm_zone_
UTM zone as determined after transforming GPS message.
tf2::Transform utm_world_transform_
Holds the UTM->odom transform.
ros::Time gps_update_time_
Timestamp of the latest good GPS message.
ros::Subscriber gps_sub_
GPS subscriber.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Type const & getType() const
tf2::Transform utm_world_trans_inverse_
Holds the odom->UTM transform for filtered GPS broadcast.
tf2::Transform latest_world_pose_
Latest odometry pose data.
void setIdentity()
ros::Subscriber imu_sub_
Subscribes to imu topic.
void setRPY(tf2Scalar roll, tf2Scalar pitch, tf2Scalar yaw)
bool prepareGpsOdometry(nav_msgs::Odometry &gps_odom)
Prepares the GPS odometry message before sending.
Duration & fromSec(double t)
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
#define ROS_INFO(...)
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool use_odometry_yaw_
Whether we get the transform&#39;s yaw from the odometry or IMU source.
void fromMsg(const A &, B &b)
void computeTransform()
Computes the transform from the UTM frame to the odom frame.
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Transform inverse() const
bool use_manual_datum_
Whether we get our datum from the first GPS message or from the set_datum service/parameter.
static void LLtoUTM(const double Lat, const double Long, double &UTMNorthing, double &UTMEasting, std::string &UTMZone, double &gamma)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const int POSITION_SIZE
Definition: filter_common.h:86
TF2SIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
TF2SIMD_FORCE_INLINE void mult(const Transform &t1, const Transform &t2)
bool odom_updated_
Whether or not we have new odometry data.
tf2::Transform latest_utm_pose_
Latest GPS data, stored as UTM coords.
double clampRotation(double rotation)
Utility method keeping RPY angles in the range [-pi, pi].
double yaw_offset_
IMU&#39;s yaw offset.
Eigen::MatrixXd latest_utm_covariance_
Covariance for most recent GPS/UTM data.
bool gps_updated_
Whether or not we have new GPS data.
void getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose, tf2::Transform &robot_odom_pose, const ros::Time &transform_time)
Given the pose of the navsat sensor in the world frame, removes the offset from the vehicle&#39;s centroi...
B toMsg(const A &a)
void setTransformOdometry(const nav_msgs::OdometryConstPtr &msg)
Used for setting the odometry data that will be used to compute the transform.
bool has_transform_odom_
Signifies that we have received a usable odometry message.
TF2SIMD_FORCE_INLINE Vector3 quatRotate(const Quaternion &rotation, const Vector3 &v)
#define ROS_INFO_STREAM(args)
tf2::Quaternion transform_orientation_
Latest IMU orientation.
const int POSE_SIZE
Pose and twist messages each contain six variables.
Definition: filter_common.h:84
void imuCallback(const sensor_msgs::ImuConstPtr &msg)
Callback for the IMU data.
#define ROS_WARN_STREAM_ONCE(args)
bool getParam(const std::string &key, std::string &s) const
double magnetic_declination_
Parameter that specifies the magnetic declination for the robot&#39;s environment.
ros::Publisher gps_odom_pub_
Publisher for gps data.
static Time now()
bool transform_good_
Whether or not we&#39;ve computed a good heading.
ros::Timer periodicUpdateTimer_
timer calling periodicUpdate
bool lookupTransformSafe(const tf2_ros::Buffer &buffer, const std::string &targetFrame, const std::string &sourceFrame, const ros::Time &time, const ros::Duration &timeout, tf2::Transform &targetFrameTrans, const bool silent=false)
Method for safely obtaining transforms.
bool prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps)
Converts the odometry data back to GPS and broadcasts it.
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
void gpsFixCallback(const sensor_msgs::NavSatFixConstPtr &msg)
Callback for the GPS fix data.
void sendTransform(const geometry_msgs::TransformStamped &transform)
static void UTMtoLL(const double UTMNorthing, const double UTMEasting, const std::string &UTMZone, double &Lat, double &Long, double &gamma)
static bool waitForValid()
void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw)
Utility method for converting quaternion to RPY.
tf2::Transform transform_utm_pose_
Holds the UTM pose that is used to compute the transform.
bool broadcast_utm_transform_as_parent_frame_
Whether to broadcast the UTM transform as parent frame, default as child.
void odomCallback(const nav_msgs::OdometryConstPtr &msg)
Callback for the odom data.
bool broadcast_utm_transform_
Whether or not we broadcast the UTM transform.
std::string gps_frame_id_
The frame_id of the GPS message (specifies mounting location)
const std::string response
void periodicUpdate(const ros::TimerEvent &event)
callback function which is called for periodic updates
ros::Time odom_update_time_
Timestamp of the latest good odometry message.


robot_localization
Author(s): Tom Moore
autogenerated on Sun Feb 17 2019 03:15:37