diff --git a/include/laser/capture/capture_laser_3d.h b/include/laser/capture/capture_laser_3d.h index 5eeb0e23622b0ec279b6b5621f5d96ad36110b3e..4e0e84f6f4deb54d8c8ae6cde43efd0b0dedd7dd 100644 --- a/include/laser/capture/capture_laser_3d.h +++ b/include/laser/capture/capture_laser_3d.h @@ -31,8 +31,6 @@ namespace wolf { -namespace laser -{ WOLF_PTR_TYPEDEFS(CaptureLaser3d); @@ -49,7 +47,6 @@ class CaptureLaser3d : public CaptureBase pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud_; }; -} // namespace laser } // namespace wolf #endif // CAPTURE_LASER_3d_H_ \ No newline at end of file diff --git a/include/laser/processor/processor_odom_icp_3d.h b/include/laser/processor/processor_odom_icp_3d.h index 8ac0c656b4646922a25fe4198f8bef57291f9c0f..8a4e7902b2b8f3c4a8760ef90ef5df03b7dbd756 100644 --- a/include/laser/processor/processor_odom_icp_3d.h +++ b/include/laser/processor/processor_odom_icp_3d.h @@ -44,9 +44,6 @@ namespace wolf { -namespace laser -{ - WOLF_STRUCT_PTR_TYPEDEFS(ParamsProcessorOdomIcp3d); struct ParamsProcessorOdomIcp3d : public ParamsProcessorTracker, public ParamsMotionProvider @@ -168,7 +165,7 @@ class ProcessorOdomIcp3d : public ProcessorTracker, public MotionProvider void establishFactors() override; }; -} // namespace laser + } // namespace wolf #endif // SRC_PROCESSOR_ODOM_ICP_3D_H_ diff --git a/include/laser/sensor/sensor_laser_3d.h b/include/laser/sensor/sensor_laser_3d.h index 771b96e061fd5bbe842169c6cac57c1458d3aaf3..9b9ca106bfbe6f220ea1e429ee140807d32528ec 100644 --- a/include/laser/sensor/sensor_laser_3d.h +++ b/include/laser/sensor/sensor_laser_3d.h @@ -27,8 +27,6 @@ namespace wolf { -namespace laser -{ WOLF_STRUCT_PTR_TYPEDEFS(ParamsSensorLaser3d); @@ -54,8 +52,6 @@ class SensorLaser3d : public SensorBase ParamsSensorLaser3dPtr params_laser3d_; }; - -} // namespace laser } // namespace wolf #endif // SENSOR_LASER_3d_H_ \ No newline at end of file diff --git a/include/laser/utils/laser3d_tools.h b/include/laser/utils/laser3d_tools.h index f1c19fa21b1b2c217bcb2647522441f265f527a2..b0e2dcfd510bc083ff9e73282b427482822990cc 100644 --- a/include/laser/utils/laser3d_tools.h +++ b/include/laser/utils/laser3d_tools.h @@ -37,8 +37,6 @@ namespace wolf { -namespace laser -{ // _cloud_ref: first PointCloud // _cloud_other: second PointCloud inline void pairAlign(const pcl::PointCloud<pcl::PointXYZ>::Ptr _cloud_ref, @@ -91,5 +89,4 @@ inline void pairAlign(const pcl::PointCloud<pcl::PointXYZ>::Ptr // _transform_final = _transform_final.inverse(); // Maybe we messed up } -} // namespace laser } // namespace wolf diff --git a/src/capture/capture_laser_3d.cpp b/src/capture/capture_laser_3d.cpp index 3377b2910ba37c076a45a6c6dae7487403fd64a6..7df9a1b1f8c1a95aedd6000668c819976923ffe5 100644 --- a/src/capture/capture_laser_3d.cpp +++ b/src/capture/capture_laser_3d.cpp @@ -23,8 +23,6 @@ namespace wolf { -namespace laser -{ CaptureLaser3d::CaptureLaser3d(const TimeStamp& _timestamp, SensorBasePtr _sensor, pcl::PointCloud<pcl::PointXYZ>::Ptr _point_cloud) : CaptureBase("CaptureLaser3d", _timestamp, _sensor), point_cloud_(_point_cloud) @@ -43,5 +41,4 @@ pcl::PointCloud<pcl::PointXYZ>::ConstPtr CaptureLaser3d::getPointCloud() const return point_cloud_; } -} // namespace laser } // namespace wolf \ No newline at end of file diff --git a/src/processor/processor_odom_icp_3d.cpp b/src/processor/processor_odom_icp_3d.cpp index 92e2dfdaf36b5c3b37581b6135a589e1228affab..c9104c9026b20e1f28ccb4f1d408851248e2c255 100644 --- a/src/processor/processor_odom_icp_3d.cpp +++ b/src/processor/processor_odom_icp_3d.cpp @@ -25,8 +25,7 @@ namespace wolf { -namespace laser -{ + ProcessorOdomIcp3d::ProcessorOdomIcp3d(ParamsProcessorOdomIcp3dPtr _params) : ProcessorTracker("ProcessorOdomIcp3d", "PO", 3, _params), MotionProvider("PO", _params) { @@ -187,5 +186,4 @@ void ProcessorOdomIcp3d::establishFactors() feature, feature, origin_laser_->getFrame(), shared_from_this(), false, TOP_MOTION); }; -} // namespace laser } // namespace wolf \ No newline at end of file diff --git a/src/sensor/sensor_laser_3d.cpp b/src/sensor/sensor_laser_3d.cpp index f72ae298bdcac594a40d3cff7e61eb3e8733715a..1cb46b8b355aa6df5d6b37e9228d10e4228f1fc2 100644 --- a/src/sensor/sensor_laser_3d.cpp +++ b/src/sensor/sensor_laser_3d.cpp @@ -23,8 +23,6 @@ namespace wolf { -namespace laser -{ SensorLaser3d::SensorLaser3d(StateBlockPtr _p_ptr, StateBlockPtr _o_ptr) : SensorBase("SensorLaser3d", _p_ptr, _o_ptr, nullptr, 0) @@ -44,5 +42,4 @@ SensorBase("SensorLaser3d", SensorLaser3d::~SensorLaser3d() {} -} // namespace laser } // namespace wolf \ No newline at end of file diff --git a/test/gtest_laser3d_tools.cpp b/test/gtest_laser3d_tools.cpp index d0cedb247a70c58e624f1bae5130e21646de5cc3..8c5541d5f51b220ebb2c56f1a702932fe629bd8b 100644 --- a/test/gtest_laser3d_tools.cpp +++ b/test/gtest_laser3d_tools.cpp @@ -86,7 +86,7 @@ TEST(pairAlign, identity) registration_solver.setMaximumIterations(200); // Alignment - wolf::laser::pairAlign(pcl_ref, + wolf::pairAlign(pcl_ref, pcl_other, transformation_guess, transformation_final, @@ -136,7 +136,7 @@ TEST(pairAlign, known_transformation) registration_solver.setMaximumIterations(100); // Alignment - wolf::laser::pairAlign(pcl_ref, + wolf::pairAlign(pcl_ref, pcl_other, transformation_guess, transformation_final,