diff --git a/cartographer_ros/cartographer_ros/msg_conversion.cc b/cartographer_ros/cartographer_ros/msg_conversion.cc index 6ab6a6c..0cb30a5 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion.cc @@ -229,24 +229,6 @@ sensor_msgs::PointCloud2 ToPointCloud2Message( return proto; } -::cartographer::sensor::proto::LaserFan ToCartographer( - const pcl::PointCloud& pcl_points) { - ::cartographer::sensor::proto::LaserFan proto; - - auto* origin = proto.mutable_origin(); - origin->set_x(0.); - origin->set_y(0.); - origin->set_z(0.); - - auto* point_cloud = proto.mutable_point_cloud(); - for (const auto& point : pcl_points) { - point_cloud->add_x(point.x); - point_cloud->add_y(point.y); - point_cloud->add_z(point.z); - } - return proto; -} - Rigid3d ToRigid3d(const geometry_msgs::TransformStamped& transform) { return Rigid3d(ToEigen(transform.transform.translation), ToEigen(transform.transform.rotation)); diff --git a/cartographer_ros/cartographer_ros/msg_conversion.h b/cartographer_ros/cartographer_ros/msg_conversion.h index b3d9770..ed7c7b6 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.h +++ b/cartographer_ros/cartographer_ros/msg_conversion.h @@ -64,9 +64,6 @@ geometry_msgs::Pose ToGeometryMsgPose( ::cartographer::sensor::proto::LaserScan ToCartographer( const sensor_msgs::MultiEchoLaserScan& msg); -::cartographer::sensor::proto::LaserFan ToCartographer( - const pcl::PointCloud& pcl_points); - ::cartographer::transform::Rigid3d ToRigid3d( const geometry_msgs::TransformStamped& transform); diff --git a/cartographer_ros/cartographer_ros/sensor_bridge.cc b/cartographer_ros/cartographer_ros/sensor_bridge.cc index d78aaaa..cb5fb10 100644 --- a/cartographer_ros/cartographer_ros/sensor_bridge.cc +++ b/cartographer_ros/cartographer_ros/sensor_bridge.cc @@ -74,7 +74,7 @@ void SensorBridge::HandleOdometryMessage( const auto sensor_to_tracking = tf_bridge_->LookupToTracking( time, CheckNoLeadingSlash(msg->child_frame_id)); if (sensor_to_tracking != nullptr) { - trajectory_builder_->AddOdometerPose( + trajectory_builder_->AddOdometerData( topic, time, ToRigid3d(msg->pose.pose) * sensor_to_tracking->inverse(), covariance); } @@ -101,46 +101,39 @@ void SensorBridge::HandleImuMessage(const string& topic, void SensorBridge::HandleLaserScanMessage( const string& topic, const sensor_msgs::LaserScan::ConstPtr& msg) { - HandleLaserScanProto(topic, FromRos(msg->header.stamp), msg->header.frame_id, - ToCartographer(*msg)); + HandleRangefinder(topic, FromRos(msg->header.stamp), msg->header.frame_id, + carto::sensor::ToPointCloud(ToCartographer(*msg))); } void SensorBridge::HandleMultiEchoLaserScanMessage( const string& topic, const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg) { - HandleLaserScanProto(topic, FromRos(msg->header.stamp), msg->header.frame_id, - ToCartographer(*msg)); + HandleRangefinder(topic, FromRos(msg->header.stamp), msg->header.frame_id, + carto::sensor::ToPointCloud(ToCartographer(*msg))); } void SensorBridge::HandlePointCloud2Message( const string& topic, const sensor_msgs::PointCloud2::ConstPtr& msg) { pcl::PointCloud pcl_point_cloud; pcl::fromROSMsg(*msg, pcl_point_cloud); - const carto::common::Time time = FromRos(msg->header.stamp); - const auto sensor_to_tracking = tf_bridge_->LookupToTracking( - time, CheckNoLeadingSlash(msg->header.frame_id)); - if (sensor_to_tracking != nullptr) { - trajectory_builder_->AddLaserFan( - topic, time, - carto::sensor::TransformLaserFan( - carto::sensor::FromProto(ToCartographer(pcl_point_cloud)), - sensor_to_tracking->cast())); + carto::sensor::PointCloud point_cloud; + for (const auto& point : pcl_point_cloud) { + point_cloud.emplace_back(point.x, point.y, point.z); } + HandleRangefinder(topic, FromRos(msg->header.stamp), msg->header.frame_id, + point_cloud); } -void SensorBridge::HandleLaserScanProto( - const string& topic, const carto::common::Time time, const string& frame_id, - const carto::sensor::proto::LaserScan& laser_scan) { - const carto::sensor::LaserFan laser_fan = { - Eigen::Vector3f::Zero(), - carto::sensor::ToPointCloud(laser_scan), - {}, - {}}; +void SensorBridge::HandleRangefinder(const string& topic, + const carto::common::Time time, + const string& frame_id, + const carto::sensor::PointCloud& ranges) { const auto sensor_to_tracking = tf_bridge_->LookupToTracking(time, CheckNoLeadingSlash(frame_id)); if (sensor_to_tracking != nullptr) { - trajectory_builder_->AddLaserFan( - topic, time, carto::sensor::TransformLaserFan( - laser_fan, sensor_to_tracking->cast())); + trajectory_builder_->AddRangefinderData( + topic, time, sensor_to_tracking->translation().cast(), + carto::sensor::TransformPointCloud(ranges, + sensor_to_tracking->cast())); } } diff --git a/cartographer_ros/cartographer_ros/sensor_bridge.h b/cartographer_ros/cartographer_ros/sensor_bridge.h index acb6be4..7a7d271 100644 --- a/cartographer_ros/cartographer_ros/sensor_bridge.h +++ b/cartographer_ros/cartographer_ros/sensor_bridge.h @@ -63,10 +63,10 @@ class SensorBridge { const sensor_msgs::PointCloud2::ConstPtr& msg); private: - void HandleLaserScanProto( - const string& topic, const ::cartographer::common::Time time, - const string& frame_id, - const ::cartographer::sensor::proto::LaserScan& laser_scan); + void HandleRangefinder(const string& topic, + const ::cartographer::common::Time time, + const string& frame_id, + const ::cartographer::sensor::PointCloud& ranges); const SensorBridgeOptions options_; const TfBridge* const tf_bridge_;