Remove unused code. (#401)
parent
125aee3011
commit
1e76e8f4ae
|
@ -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<double, 36>& covariance) {
|
||||
return Eigen::Map<const Eigen::Matrix<double, 6, 6>>(covariance.data());
|
||||
}
|
||||
|
||||
geometry_msgs::Transform ToGeometryMsgTransform(const Rigid3d& rigid3d) {
|
||||
geometry_msgs::Transform transform;
|
||||
transform.translation.x = rigid3d.translation().x();
|
||||
|
|
|
@ -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<double, 36>& covariance);
|
||||
|
||||
} // namespace cartographer_ros
|
||||
|
||||
#endif // CARTOGRAPHER_ROS_MSG_CONVERSION_H_
|
||||
|
|
|
@ -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"
|
||||
|
||||
|
|
Loading…
Reference in New Issue