sensor_bridge.h
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 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_SENSOR_BRIDGE_H
00018 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_SENSOR_BRIDGE_H
00019 
00020 #include <memory>
00021 
00022 #include "absl/types/optional.h"
00023 #include "cartographer/mapping/trajectory_builder_interface.h"
00024 #include "cartographer/sensor/imu_data.h"
00025 #include "cartographer/sensor/odometry_data.h"
00026 #include "cartographer/transform/rigid_transform.h"
00027 #include "cartographer/transform/transform.h"
00028 #include "cartographer_ros/tf_bridge.h"
00029 #include "cartographer_ros_msgs/LandmarkList.h"
00030 #include "geometry_msgs/Transform.h"
00031 #include "geometry_msgs/TransformStamped.h"
00032 #include "nav_msgs/OccupancyGrid.h"
00033 #include "nav_msgs/Odometry.h"
00034 #include "sensor_msgs/Imu.h"
00035 #include "sensor_msgs/LaserScan.h"
00036 #include "sensor_msgs/MultiEchoLaserScan.h"
00037 #include "sensor_msgs/NavSatFix.h"
00038 #include "sensor_msgs/PointCloud2.h"
00039 
00040 namespace cartographer_ros {
00041 
00042 // Converts ROS messages into SensorData in tracking frame for the MapBuilder.
00043 class SensorBridge {
00044  public:
00045   explicit SensorBridge(
00046       int num_subdivisions_per_laser_scan, const std::string& tracking_frame,
00047       double lookup_transform_timeout_sec, tf2_ros::Buffer* tf_buffer,
00048       ::cartographer::mapping::TrajectoryBuilderInterface* trajectory_builder);
00049 
00050   SensorBridge(const SensorBridge&) = delete;
00051   SensorBridge& operator=(const SensorBridge&) = delete;
00052 
00053   std::unique_ptr<::cartographer::sensor::OdometryData> ToOdometryData(
00054       const nav_msgs::Odometry::ConstPtr& msg);
00055   void HandleOdometryMessage(const std::string& sensor_id,
00056                              const nav_msgs::Odometry::ConstPtr& msg);
00057   void HandleNavSatFixMessage(const std::string& sensor_id,
00058                               const sensor_msgs::NavSatFix::ConstPtr& msg);
00059   void HandleLandmarkMessage(
00060       const std::string& sensor_id,
00061       const cartographer_ros_msgs::LandmarkList::ConstPtr& msg);
00062 
00063   std::unique_ptr<::cartographer::sensor::ImuData> ToImuData(
00064       const sensor_msgs::Imu::ConstPtr& msg);
00065   void HandleImuMessage(const std::string& sensor_id,
00066                         const sensor_msgs::Imu::ConstPtr& msg);
00067   void HandleLaserScanMessage(const std::string& sensor_id,
00068                               const sensor_msgs::LaserScan::ConstPtr& msg);
00069   void HandleMultiEchoLaserScanMessage(
00070       const std::string& sensor_id,
00071       const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
00072   void HandlePointCloud2Message(const std::string& sensor_id,
00073                                 const sensor_msgs::PointCloud2::ConstPtr& msg);
00074 
00075   const TfBridge& tf_bridge() const;
00076 
00077  private:
00078   void HandleLaserScan(
00079       const std::string& sensor_id, ::cartographer::common::Time start_time,
00080       const std::string& frame_id,
00081       const ::cartographer::sensor::PointCloudWithIntensities& points);
00082   void HandleRangefinder(const std::string& sensor_id,
00083                          ::cartographer::common::Time time,
00084                          const std::string& frame_id,
00085                          const ::cartographer::sensor::TimedPointCloud& ranges);
00086 
00087   const int num_subdivisions_per_laser_scan_;
00088   std::map<std::string, cartographer::common::Time>
00089       sensor_to_previous_subdivision_time_;
00090   const TfBridge tf_bridge_;
00091   ::cartographer::mapping::TrajectoryBuilderInterface* const
00092       trajectory_builder_;
00093 
00094   absl::optional<::cartographer::transform::Rigid3d> ecef_to_local_frame_;
00095 };
00096 
00097 }  // namespace cartographer_ros
00098 
00099 #endif  // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_SENSOR_BRIDGE_H


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