sensor_bridge.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer_ros/sensor_bridge.h"
00018 
00019 #include "absl/memory/memory.h"
00020 #include "cartographer_ros/msg_conversion.h"
00021 #include "cartographer_ros/time_conversion.h"
00022 
00023 namespace cartographer_ros {
00024 
00025 namespace carto = ::cartographer;
00026 
00027 using carto::transform::Rigid3d;
00028 
00029 namespace {
00030 
00031 const std::string& CheckNoLeadingSlash(const std::string& frame_id) {
00032   if (frame_id.size() > 0) {
00033     CHECK_NE(frame_id[0], '/') << "The frame_id " << frame_id
00034                                << " should not start with a /. See 1.7 in "
00035                                   "http://wiki.ros.org/tf2/Migration.";
00036   }
00037   return frame_id;
00038 }
00039 
00040 }  // namespace
00041 
00042 SensorBridge::SensorBridge(
00043     const int num_subdivisions_per_laser_scan,
00044     const std::string& tracking_frame,
00045     const double lookup_transform_timeout_sec, tf2_ros::Buffer* const tf_buffer,
00046     carto::mapping::TrajectoryBuilderInterface* const trajectory_builder)
00047     : num_subdivisions_per_laser_scan_(num_subdivisions_per_laser_scan),
00048       tf_bridge_(tracking_frame, lookup_transform_timeout_sec, tf_buffer),
00049       trajectory_builder_(trajectory_builder) {}
00050 
00051 std::unique_ptr<carto::sensor::OdometryData> SensorBridge::ToOdometryData(
00052     const nav_msgs::Odometry::ConstPtr& msg) {
00053   const carto::common::Time time = FromRos(msg->header.stamp);
00054   const auto sensor_to_tracking = tf_bridge_.LookupToTracking(
00055       time, CheckNoLeadingSlash(msg->child_frame_id));
00056   if (sensor_to_tracking == nullptr) {
00057     return nullptr;
00058   }
00059   return absl::make_unique<carto::sensor::OdometryData>(
00060       carto::sensor::OdometryData{
00061           time, ToRigid3d(msg->pose.pose) * sensor_to_tracking->inverse()});
00062 }
00063 
00064 void SensorBridge::HandleOdometryMessage(
00065     const std::string& sensor_id, const nav_msgs::Odometry::ConstPtr& msg) {
00066   std::unique_ptr<carto::sensor::OdometryData> odometry_data =
00067       ToOdometryData(msg);
00068   if (odometry_data != nullptr) {
00069     trajectory_builder_->AddSensorData(
00070         sensor_id,
00071         carto::sensor::OdometryData{odometry_data->time, odometry_data->pose});
00072   }
00073 }
00074 
00075 void SensorBridge::HandleNavSatFixMessage(
00076     const std::string& sensor_id, const sensor_msgs::NavSatFix::ConstPtr& msg) {
00077   const carto::common::Time time = FromRos(msg->header.stamp);
00078   if (msg->status.status == sensor_msgs::NavSatStatus::STATUS_NO_FIX) {
00079     trajectory_builder_->AddSensorData(
00080         sensor_id,
00081         carto::sensor::FixedFramePoseData{time, absl::optional<Rigid3d>()});
00082     return;
00083   }
00084 
00085   if (!ecef_to_local_frame_.has_value()) {
00086     ecef_to_local_frame_ =
00087         ComputeLocalFrameFromLatLong(msg->latitude, msg->longitude);
00088     LOG(INFO) << "Using NavSatFix. Setting ecef_to_local_frame with lat = "
00089               << msg->latitude << ", long = " << msg->longitude << ".";
00090   }
00091 
00092   trajectory_builder_->AddSensorData(
00093       sensor_id, carto::sensor::FixedFramePoseData{
00094                      time, absl::optional<Rigid3d>(Rigid3d::Translation(
00095                                ecef_to_local_frame_.value() *
00096                                LatLongAltToEcef(msg->latitude, msg->longitude,
00097                                                 msg->altitude)))});
00098 }
00099 
00100 void SensorBridge::HandleLandmarkMessage(
00101     const std::string& sensor_id,
00102     const cartographer_ros_msgs::LandmarkList::ConstPtr& msg) {
00103   auto landmark_data = ToLandmarkData(*msg);
00104 
00105   auto tracking_from_landmark_sensor = tf_bridge_.LookupToTracking(
00106       landmark_data.time, CheckNoLeadingSlash(msg->header.frame_id));
00107   if (tracking_from_landmark_sensor != nullptr) {
00108     for (auto& observation : landmark_data.landmark_observations) {
00109       observation.landmark_to_tracking_transform =
00110           *tracking_from_landmark_sensor *
00111           observation.landmark_to_tracking_transform;
00112     }
00113   }
00114   trajectory_builder_->AddSensorData(sensor_id, landmark_data);
00115 }
00116 
00117 std::unique_ptr<carto::sensor::ImuData> SensorBridge::ToImuData(
00118     const sensor_msgs::Imu::ConstPtr& msg) {
00119   CHECK_NE(msg->linear_acceleration_covariance[0], -1)
00120       << "Your IMU data claims to not contain linear acceleration measurements "
00121          "by setting linear_acceleration_covariance[0] to -1. Cartographer "
00122          "requires this data to work. See "
00123          "http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html.";
00124   CHECK_NE(msg->angular_velocity_covariance[0], -1)
00125       << "Your IMU data claims to not contain angular velocity measurements "
00126          "by setting angular_velocity_covariance[0] to -1. Cartographer "
00127          "requires this data to work. See "
00128          "http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html.";
00129 
00130   const carto::common::Time time = FromRos(msg->header.stamp);
00131   const auto sensor_to_tracking = tf_bridge_.LookupToTracking(
00132       time, CheckNoLeadingSlash(msg->header.frame_id));
00133   if (sensor_to_tracking == nullptr) {
00134     return nullptr;
00135   }
00136   CHECK(sensor_to_tracking->translation().norm() < 1e-5)
00137       << "The IMU frame must be colocated with the tracking frame. "
00138          "Transforming linear acceleration into the tracking frame will "
00139          "otherwise be imprecise.";
00140   return absl::make_unique<carto::sensor::ImuData>(carto::sensor::ImuData{
00141       time, sensor_to_tracking->rotation() * ToEigen(msg->linear_acceleration),
00142       sensor_to_tracking->rotation() * ToEigen(msg->angular_velocity)});
00143 }
00144 
00145 void SensorBridge::HandleImuMessage(const std::string& sensor_id,
00146                                     const sensor_msgs::Imu::ConstPtr& msg) {
00147   std::unique_ptr<carto::sensor::ImuData> imu_data = ToImuData(msg);
00148   if (imu_data != nullptr) {
00149     trajectory_builder_->AddSensorData(
00150         sensor_id,
00151         carto::sensor::ImuData{imu_data->time, imu_data->linear_acceleration,
00152                                imu_data->angular_velocity});
00153   }
00154 }
00155 
00156 void SensorBridge::HandleLaserScanMessage(
00157     const std::string& sensor_id, const sensor_msgs::LaserScan::ConstPtr& msg) {
00158   carto::sensor::PointCloudWithIntensities point_cloud;
00159   carto::common::Time time;
00160   std::tie(point_cloud, time) = ToPointCloudWithIntensities(*msg);
00161   HandleLaserScan(sensor_id, time, msg->header.frame_id, point_cloud);
00162 }
00163 
00164 void SensorBridge::HandleMultiEchoLaserScanMessage(
00165     const std::string& sensor_id,
00166     const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg) {
00167   carto::sensor::PointCloudWithIntensities point_cloud;
00168   carto::common::Time time;
00169   std::tie(point_cloud, time) = ToPointCloudWithIntensities(*msg);
00170   HandleLaserScan(sensor_id, time, msg->header.frame_id, point_cloud);
00171 }
00172 
00173 void SensorBridge::HandlePointCloud2Message(
00174     const std::string& sensor_id,
00175     const sensor_msgs::PointCloud2::ConstPtr& msg) {
00176   carto::sensor::PointCloudWithIntensities point_cloud;
00177   carto::common::Time time;
00178   std::tie(point_cloud, time) = ToPointCloudWithIntensities(*msg);
00179   HandleRangefinder(sensor_id, time, msg->header.frame_id, point_cloud.points);
00180 }
00181 
00182 const TfBridge& SensorBridge::tf_bridge() const { return tf_bridge_; }
00183 
00184 void SensorBridge::HandleLaserScan(
00185     const std::string& sensor_id, const carto::common::Time time,
00186     const std::string& frame_id,
00187     const carto::sensor::PointCloudWithIntensities& points) {
00188   if (points.points.empty()) {
00189     return;
00190   }
00191   CHECK_LE(points.points.back().time, 0.f);
00192   // TODO(gaschler): Use per-point time instead of subdivisions.
00193   for (int i = 0; i != num_subdivisions_per_laser_scan_; ++i) {
00194     const size_t start_index =
00195         points.points.size() * i / num_subdivisions_per_laser_scan_;
00196     const size_t end_index =
00197         points.points.size() * (i + 1) / num_subdivisions_per_laser_scan_;
00198     carto::sensor::TimedPointCloud subdivision(
00199         points.points.begin() + start_index, points.points.begin() + end_index);
00200     if (start_index == end_index) {
00201       continue;
00202     }
00203     const double time_to_subdivision_end = subdivision.back().time;
00204     // `subdivision_time` is the end of the measurement so sensor::Collator will
00205     // send all other sensor data first.
00206     const carto::common::Time subdivision_time =
00207         time + carto::common::FromSeconds(time_to_subdivision_end);
00208     auto it = sensor_to_previous_subdivision_time_.find(sensor_id);
00209     if (it != sensor_to_previous_subdivision_time_.end() &&
00210         it->second >= subdivision_time) {
00211       LOG(WARNING) << "Ignored subdivision of a LaserScan message from sensor "
00212                    << sensor_id << " because previous subdivision time "
00213                    << it->second << " is not before current subdivision time "
00214                    << subdivision_time;
00215       continue;
00216     }
00217     sensor_to_previous_subdivision_time_[sensor_id] = subdivision_time;
00218     for (auto& point : subdivision) {
00219       point.time -= time_to_subdivision_end;
00220     }
00221     CHECK_EQ(subdivision.back().time, 0.f);
00222     HandleRangefinder(sensor_id, subdivision_time, frame_id, subdivision);
00223   }
00224 }
00225 
00226 void SensorBridge::HandleRangefinder(
00227     const std::string& sensor_id, const carto::common::Time time,
00228     const std::string& frame_id, const carto::sensor::TimedPointCloud& ranges) {
00229   if (!ranges.empty()) {
00230     CHECK_LE(ranges.back().time, 0.f);
00231   }
00232   const auto sensor_to_tracking =
00233       tf_bridge_.LookupToTracking(time, CheckNoLeadingSlash(frame_id));
00234   if (sensor_to_tracking != nullptr) {
00235     trajectory_builder_->AddSensorData(
00236         sensor_id, carto::sensor::TimedPointCloudData{
00237                        time, sensor_to_tracking->translation().cast<float>(),
00238                        carto::sensor::TransformTimedPointCloud(
00239                            ranges, sensor_to_tracking->cast<float>())});
00240   }
00241 }
00242 
00243 }  // namespace cartographer_ros


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28