25 #include "cartographer/transform/proto/transform.pb.h" 28 #include "geometry_msgs/Pose.h" 29 #include "geometry_msgs/Quaternion.h" 30 #include "geometry_msgs/Transform.h" 31 #include "geometry_msgs/TransformStamped.h" 32 #include "geometry_msgs/Vector3.h" 33 #include "glog/logging.h" 34 #include "nav_msgs/OccupancyGrid.h" 37 #include "sensor_msgs/Imu.h" 38 #include "sensor_msgs/LaserScan.h" 39 #include "sensor_msgs/MultiEchoLaserScan.h" 40 #include "sensor_msgs/PointCloud2.h" 48 constexpr
float kPointCloudComponentFourMagic = 1.;
50 using ::cartographer::sensor::LandmarkData;
51 using ::cartographer::sensor::LandmarkObservation;
52 using ::cartographer::sensor::PointCloudWithIntensities;
53 using ::cartographer::transform::Rigid3d;
54 using ::cartographer_ros_msgs::LandmarkEntry;
55 using ::cartographer_ros_msgs::LandmarkList;
57 sensor_msgs::PointCloud2 PreparePointCloud2Message(
const int64_t timestamp,
58 const std::string& frame_id,
59 const int num_points) {
60 sensor_msgs::PointCloud2 msg;
62 msg.header.frame_id = frame_id;
64 msg.width = num_points;
66 msg.fields[0].name =
"x";
67 msg.fields[0].offset = 0;
68 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
69 msg.fields[0].count = 1;
70 msg.fields[1].name =
"y";
71 msg.fields[1].offset = 4;
72 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
73 msg.fields[1].count = 1;
74 msg.fields[2].name =
"z";
75 msg.fields[2].offset = 8;
76 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
77 msg.fields[2].count = 1;
78 msg.is_bigendian =
false;
80 msg.row_step = 16 * msg.width;
82 msg.data.resize(16 * num_points);
87 bool HasEcho(
float) {
return true; }
89 float GetFirstEcho(
float range) {
return range; }
92 bool HasEcho(
const sensor_msgs::LaserEcho& echo) {
93 return !echo.echoes.empty();
96 float GetFirstEcho(
const sensor_msgs::LaserEcho& echo) {
97 return echo.echoes[0];
101 template <
typename LaserMessageType>
102 std::tuple<PointCloudWithIntensities, ::cartographer::common::Time>
103 LaserScanToPointCloudWithIntensities(
const LaserMessageType& msg) {
104 CHECK_GE(msg.range_min, 0.f);
105 CHECK_GE(msg.range_max, msg.range_min);
106 if (msg.angle_increment > 0.f) {
107 CHECK_GT(msg.angle_max, msg.angle_min);
109 CHECK_GT(msg.angle_min, msg.angle_max);
111 PointCloudWithIntensities point_cloud;
112 float angle = msg.angle_min;
113 for (
size_t i = 0; i < msg.ranges.size(); ++i) {
114 const auto& echoes = msg.ranges[i];
115 if (HasEcho(echoes)) {
116 const float first_echo = GetFirstEcho(echoes);
117 if (msg.range_min <= first_echo && first_echo <= msg.range_max) {
118 const Eigen::AngleAxisf rotation(angle, Eigen::Vector3f::UnitZ());
119 Eigen::Vector4f point;
120 point << rotation * (first_echo * Eigen::Vector3f::UnitX()),
121 i * msg.time_increment;
122 point_cloud.points.push_back(point);
123 if (msg.intensities.size() > 0) {
124 CHECK_EQ(msg.intensities.size(), msg.ranges.size());
125 const auto& echo_intensities = msg.intensities[i];
126 CHECK(HasEcho(echo_intensities));
127 point_cloud.intensities.push_back(GetFirstEcho(echo_intensities));
129 point_cloud.intensities.push_back(0.f);
133 angle += msg.angle_increment;
136 if (!point_cloud.points.empty()) {
137 const double duration = point_cloud.points.back()[3];
139 for (Eigen::Vector4f& point : point_cloud.points) {
140 point[3] -= duration;
143 return std::make_tuple(point_cloud, timestamp);
146 bool PointCloud2HasField(
const sensor_msgs::PointCloud2& pc2,
147 const std::string& field_name) {
148 for (
const auto& field : pc2.fields) {
149 if (field.name == field_name) {
159 const int64_t timestamp,
const std::string& frame_id,
160 const ::cartographer::sensor::TimedPointCloud& point_cloud) {
161 auto msg = PreparePointCloud2Message(timestamp, frame_id, point_cloud.size());
163 for (
const Eigen::Vector4f& point : point_cloud) {
164 stream.
next(point.x());
165 stream.next(point.y());
166 stream.next(point.z());
167 stream.next(kPointCloudComponentFourMagic);
175 return LaserScanToPointCloudWithIntensities(msg);
178 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
181 return LaserScanToPointCloudWithIntensities(msg);
184 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
187 PointCloudWithIntensities point_cloud;
190 if (PointCloud2HasField(message,
"intensity")) {
191 pcl::PointCloud<pcl::PointXYZI> pcl_point_cloud;
193 for (
const auto& point : pcl_point_cloud) {
194 point_cloud.points.emplace_back(point.x, point.y, point.z, 0.f);
195 point_cloud.intensities.push_back(point.intensity);
198 pcl::PointCloud<pcl::PointXYZ> pcl_point_cloud;
203 for (
const auto& point : pcl_point_cloud) {
204 point_cloud.points.emplace_back(point.x, point.y, point.z, 0.f);
205 point_cloud.intensities.push_back(1.0);
208 return std::make_tuple(point_cloud,
FromRos(message.header.stamp));
212 LandmarkData landmark_data;
213 landmark_data.time =
FromRos(landmark_list.header.stamp);
214 for (
const LandmarkEntry& entry : landmark_list.landmark) {
215 landmark_data.landmark_observations.push_back(
216 {entry.id,
ToRigid3d(entry.tracking_from_landmark_transform),
217 entry.translation_weight, entry.rotation_weight});
219 return landmark_data;
224 ToEigen(transform.transform.rotation));
228 return Rigid3d({pose.position.x, pose.position.y, pose.position.z},
232 Eigen::Vector3d
ToEigen(
const geometry_msgs::Vector3& vector3) {
233 return Eigen::Vector3d(vector3.x, vector3.y, vector3.z);
236 Eigen::Quaterniond
ToEigen(
const geometry_msgs::Quaternion& quaternion) {
237 return Eigen::Quaterniond(quaternion.w, quaternion.x, quaternion.y,
242 geometry_msgs::Transform transform;
243 transform.translation.x = rigid3d.translation().x();
244 transform.translation.y = rigid3d.translation().y();
245 transform.translation.z = rigid3d.translation().z();
246 transform.rotation.w = rigid3d.rotation().w();
247 transform.rotation.x = rigid3d.rotation().x();
248 transform.rotation.y = rigid3d.rotation().y();
249 transform.rotation.z = rigid3d.rotation().z();
254 geometry_msgs::Pose
pose;
256 pose.orientation.w = rigid3d.rotation().w();
257 pose.orientation.x = rigid3d.rotation().x();
258 pose.orientation.y = rigid3d.rotation().y();
259 pose.orientation.z = rigid3d.rotation().z();
264 geometry_msgs::Point point;
265 point.x = vector3d.x();
266 point.y = vector3d.y();
267 point.z = vector3d.z();
272 const double altitude) {
274 constexpr
double a = 6378137.;
275 constexpr
double f = 1. / 298.257223563;
276 constexpr
double b = a * (1. - f);
277 constexpr
double a_squared = a * a;
278 constexpr
double b_squared = b * b;
279 constexpr
double e_squared = (a_squared - b_squared) / a_squared;
284 const double N = a / std::sqrt(1 - e_squared * sin_phi * sin_phi);
285 const double x = (N + altitude) * cos_phi * cos_lambda;
286 const double y = (N + altitude) * cos_phi * sin_lambda;
287 const double z = (b_squared / a_squared * N + altitude) * sin_phi;
289 return Eigen::Vector3d(x, y, z);
293 const double latitude,
const double longitude) {
294 const Eigen::Vector3d translation =
LatLongAltToEcef(latitude, longitude, 0.);
295 const Eigen::Quaterniond rotation =
297 Eigen::Vector3d::UnitY()) *
299 Eigen::Vector3d::UnitZ());
305 const double resolution,
const std::string& frame_id,
307 auto occupancy_grid =
308 ::cartographer::common::make_unique<nav_msgs::OccupancyGrid>();
310 const int width = cairo_image_surface_get_width(painted_slices.
surface.get());
312 cairo_image_surface_get_height(painted_slices.
surface.get());
315 occupancy_grid->header.stamp = time;
316 occupancy_grid->header.frame_id = frame_id;
317 occupancy_grid->info.map_load_time = time;
318 occupancy_grid->info.resolution = resolution;
319 occupancy_grid->info.width = width;
320 occupancy_grid->info.height = height;
321 occupancy_grid->info.origin.position.x =
322 -painted_slices.
origin.x() * resolution;
323 occupancy_grid->info.origin.position.y =
324 (-height + painted_slices.
origin.y()) * resolution;
325 occupancy_grid->info.origin.position.z = 0.;
326 occupancy_grid->info.origin.orientation.w = 1.;
327 occupancy_grid->info.origin.orientation.x = 0.;
328 occupancy_grid->info.origin.orientation.y = 0.;
329 occupancy_grid->info.origin.orientation.z = 0.;
331 const uint32_t* pixel_data =
reinterpret_cast<uint32_t*
>(
332 cairo_image_surface_get_data(painted_slices.
surface.get()));
333 occupancy_grid->data.reserve(width * height);
334 for (
int y = height - 1; y >= 0; --y) {
335 for (
int x = 0; x < width; ++x) {
336 const uint32_t packed = pixel_data[y * width + x];
337 const unsigned char color = packed >> 16;
338 const unsigned char observed = packed >> 8;
342 : ::cartographer::common::RoundToInt((1. - color / 255.) * 100.);
344 CHECK_GE(100, value);
345 occupancy_grid->data.push_back(value);
349 return occupancy_grid;
sensor_msgs::PointCloud2 ToPointCloud2Message(const int64_t timestamp, const std::string &frame_id, const ::cartographer::sensor::TimedPointCloud &point_cloud)
std::unique_ptr< nav_msgs::OccupancyGrid > CreateOccupancyGridMsg(const cartographer::io::PaintSubmapSlicesResult &painted_slices, const double resolution, const std::string &frame_id, const ros::Time &time)
geometry_msgs::Pose ToGeometryMsgPose(const Rigid3d &rigid3d)
geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d &vector3d)
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
geometry_msgs::Transform ToGeometryMsgTransform(const Rigid3d &rigid3d)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
UniversalTimeScaleClock::time_point Time
Eigen::Vector3d ToEigen(const geometry_msgs::Vector3 &vector3)
LandmarkData ToLandmarkData(const LandmarkList &landmark_list)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
cartographer::transform::Rigid3d ComputeLocalFrameFromLatLong(const double latitude, const double longitude)
Eigen::Vector3d LatLongAltToEcef(const double latitude, const double longitude, const double altitude)
Time FromUniversal(const int64 ticks)
Duration FromSeconds(const double seconds)
::cartographer::io::UniqueCairoSurfacePtr surface
constexpr double DegToRad(double deg)
::cartographer::common::Time FromRos(const ::ros::Time &time)
ROS_FORCE_INLINE void next(const T &t)
std::tuple<::cartographer::sensor::PointCloudWithIntensities, ::cartographer::common::Time > ToPointCloudWithIntensities(const sensor_msgs::LaserScan &msg)
::ros::Time ToRos(::cartographer::common::Time time)