From 1e76e8f4aeb565dcda9415ea7f66e81e06fe4054 Mon Sep 17 00:00:00 2001 From: Wolfgang Hess Date: Thu, 29 Jun 2017 12:12:06 +0200 Subject: [PATCH] Remove unused code. (#401) --- cartographer_ros/cartographer_ros/msg_conversion.cc | 5 ----- cartographer_ros/cartographer_ros/msg_conversion.h | 4 ---- cartographer_ros/cartographer_ros/sensor_bridge.cc | 1 - 3 files changed, 10 deletions(-) diff --git a/cartographer_ros/cartographer_ros/msg_conversion.cc b/cartographer_ros/cartographer_ros/msg_conversion.cc index 85b7857..296adb9 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion.cc @@ -44,7 +44,6 @@ namespace { constexpr float kPointCloudComponentFourMagic = 1.; using ::cartographer::transform::Rigid3d; -using ::cartographer::kalman_filter::PoseCovariance; using ::cartographer::sensor::PointCloudWithIntensities; sensor_msgs::PointCloud2 PreparePointCloud2Message(const int64 timestamp, @@ -207,10 +206,6 @@ Eigen::Quaterniond ToEigen(const geometry_msgs::Quaternion& quaternion) { quaternion.z); } -PoseCovariance ToPoseCovariance(const boost::array& covariance) { - return Eigen::Map>(covariance.data()); -} - geometry_msgs::Transform ToGeometryMsgTransform(const Rigid3d& rigid3d) { geometry_msgs::Transform transform; transform.translation.x = rigid3d.translation().x(); diff --git a/cartographer_ros/cartographer_ros/msg_conversion.h b/cartographer_ros/cartographer_ros/msg_conversion.h index f89e57e..d175815 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.h +++ b/cartographer_ros/cartographer_ros/msg_conversion.h @@ -18,7 +18,6 @@ #define CARTOGRAPHER_ROS_MSG_CONVERSION_H_ #include "cartographer/common/port.h" -#include "cartographer/kalman_filter/pose_tracker.h" #include "cartographer/sensor/point_cloud.h" #include "cartographer/transform/rigid_transform.h" #include "geometry_msgs/Pose.h" @@ -64,9 +63,6 @@ Eigen::Vector3d ToEigen(const geometry_msgs::Vector3& vector3); Eigen::Quaterniond ToEigen(const geometry_msgs::Quaternion& quaternion); -::cartographer::kalman_filter::PoseCovariance ToPoseCovariance( - const boost::array& covariance); - } // namespace cartographer_ros #endif // CARTOGRAPHER_ROS_MSG_CONVERSION_H_ diff --git a/cartographer_ros/cartographer_ros/sensor_bridge.cc b/cartographer_ros/cartographer_ros/sensor_bridge.cc index 5cd5b97..63ed5d6 100644 --- a/cartographer_ros/cartographer_ros/sensor_bridge.cc +++ b/cartographer_ros/cartographer_ros/sensor_bridge.cc @@ -16,7 +16,6 @@ #include "cartographer_ros/sensor_bridge.h" -#include "cartographer/kalman_filter/pose_tracker.h" #include "cartographer_ros/msg_conversion.h" #include "cartographer_ros/time_conversion.h"