Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(ground_segmentation)!: fix namespace and directory structure #7744

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -82,6 +82,12 @@ def create_additional_pipeline(self, lidar_name):
"margin_min_z"
]
)
# Get the plugin name from the full plugin path
ground_segmentation_plugin_name = self.ground_segmentation_param[
f"{lidar_name}_ground_filter"
]["plugin"]
ground_segmentation_plugin_name = ground_segmentation_plugin_name.split("::")[-1]

components = []
components.append(
ComposableNode(
@@ -110,7 +116,7 @@ def create_additional_pipeline(self, lidar_name):
components.append(
ComposableNode(
package="ground_segmentation",
plugin=self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["plugin"],
plugin="autoware::ground_segmentation::" + ground_segmentation_plugin_name,
name=f"{lidar_name}_ground_filter",
remappings=[
("input", f"{lidar_name}/range_cropped/pointcloud"),
@@ -203,7 +209,7 @@ def create_ransac_pipeline(self):
components.append(
ComposableNode(
package="ground_segmentation",
plugin="ground_segmentation::RANSACGroundFilterComponent",
plugin="autoware::ground_segmentation::" + "RANSACGroundFilterComponent",
name="ransac_ground_filter",
namespace="plane_fitting",
remappings=[
@@ -228,6 +234,12 @@ def create_common_pipeline(self, input_topic, output_topic):
self.vehicle_info["min_height_offset"]
+ self.ground_segmentation_param["common_crop_box_filter"]["parameters"]["margin_min_z"]
)
# Get the plugin name from the full plugin path
ground_segmentation_plugin_name = self.ground_segmentation_param["common_ground_filter"][
"plugin"
]
ground_segmentation_plugin_name = ground_segmentation_plugin_name.split("::")[-1]

components = []
components.append(
ComposableNode(
@@ -256,7 +268,7 @@ def create_common_pipeline(self, input_topic, output_topic):
components.append(
ComposableNode(
package="ground_segmentation",
plugin=self.ground_segmentation_param["common_ground_filter"]["plugin"],
plugin="autoware::ground_segmentation::" + ground_segmentation_plugin_name,
name="common_ground_filter",
remappings=[
("input", "range_cropped/pointcloud"),
28 changes: 14 additions & 14 deletions perception/ground_segmentation/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -21,39 +21,39 @@ include_directories(
${GRID_MAP_INCLUDE_DIR}
)

ament_auto_add_library(ground_segmentation SHARED
src/ray_ground_filter_nodelet.cpp
src/ransac_ground_filter_nodelet.cpp
src/scan_ground_filter_nodelet.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/ray_ground_filter/node.cpp
src/ransac_ground_filter/node.cpp
src/scan_ground_filter/node.cpp
)

target_link_libraries(ground_segmentation
target_link_libraries(${PROJECT_NAME}
${Boost_LIBRARIES}
${OpenCV_LIBRARIES}
${PCL_LIBRARIES}
)

if(OPENMP_FOUND)
set_target_properties(ground_segmentation PROPERTIES
set_target_properties(${PROJECT_NAME} PROPERTIES
COMPILE_FLAGS ${OpenMP_CXX_FLAGS}
LINK_FLAGS ${OpenMP_CXX_FLAGS}
)
endif()

# ========== Ground Filter ==========
# -- Ray Ground Filter --
rclcpp_components_register_node(ground_segmentation
PLUGIN "ground_segmentation::RayGroundFilterComponent"
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::ground_segmentation::RayGroundFilterComponent"
EXECUTABLE ray_ground_filter_node)

# -- RANSAC Ground Filter --
rclcpp_components_register_node(ground_segmentation
PLUGIN "ground_segmentation::RANSACGroundFilterComponent"
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::ground_segmentation::RANSACGroundFilterComponent"
EXECUTABLE ransac_ground_filter_node)

# -- Scan Ground Filter --
rclcpp_components_register_node(ground_segmentation
PLUGIN "ground_segmentation::ScanGroundFilterComponent"
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::ground_segmentation::ScanGroundFilterComponent"
EXECUTABLE scan_ground_filter_node)


@@ -88,7 +88,7 @@ if(BUILD_TESTING)
)

target_link_libraries(test_ray_ground_filter
ground_segmentation
${PROJECT_NAME}
${YAML_CPP_LIBRARIES}
)

@@ -97,7 +97,7 @@ if(BUILD_TESTING)
)

target_link_libraries(test_scan_ground_filter
ground_segmentation
${PROJECT_NAME}
${YAML_CPP_LIBRARIES}
)
ament_add_ros_isolated_gtest(test_ransac_ground_filter
Original file line number Diff line number Diff line change
@@ -16,7 +16,7 @@
negative: False

common_ground_filter:
plugin: "ground_segmentation::ScanGroundFilterComponent"
plugin: "autoware::ground_segmentation::ScanGroundFilterComponent"
parameters:
global_slope_max_angle_deg: 10.0
local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode
Original file line number Diff line number Diff line change
@@ -36,7 +36,7 @@ def launch_setup(context, *args, **kwargs):
nodes = [
ComposableNode(
package="ground_segmentation",
plugin="ground_segmentation::ScanGroundFilterComponent",
plugin="autoware::ground_segmentation::ScanGroundFilterComponent",
name="scan_ground_filter",
remappings=[
("input", LaunchConfiguration("input/pointcloud")),
Original file line number Diff line number Diff line change
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "ground_segmentation/ransac_ground_filter_nodelet.hpp"
#include "node.hpp"

#include <pcl_ros/transforms.hpp>

@@ -54,15 +54,6 @@ Eigen::Vector3d getArbitraryOrthogonalVector(const Eigen::Vector3d & input)
return unit_vec;
}

ground_segmentation::PlaneBasis getPlaneBasis(const Eigen::Vector3d & plane_normal)
{
ground_segmentation::PlaneBasis basis;
basis.e_z = plane_normal;
basis.e_x = getArbitraryOrthogonalVector(plane_normal);
basis.e_y = basis.e_x.cross(basis.e_z);
return basis;
}

geometry_msgs::msg::Pose getDebugPose(const Eigen::Affine3d & plane_affine)
{
geometry_msgs::msg::Pose debug_pose;
@@ -78,8 +69,17 @@ geometry_msgs::msg::Pose getDebugPose(const Eigen::Affine3d & plane_affine)
}
} // namespace

namespace ground_segmentation
namespace autoware::ground_segmentation
{
PlaneBasis getPlaneBasis(const Eigen::Vector3d & plane_normal)
{
PlaneBasis basis;
basis.e_z = plane_normal;
basis.e_x = getArbitraryOrthogonalVector(plane_normal);
basis.e_y = basis.e_x.cross(basis.e_z);
return basis;
}

using pointcloud_preprocessor::get_param;

RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptions & options)
@@ -203,7 +203,7 @@ Eigen::Affine3d RANSACGroundFilterComponent::getPlaneAffine(
pcl::PointXYZ centroid_point;
centroid.get(centroid_point);
Eigen::Translation<double, 3> trans(centroid_point.x, centroid_point.y, centroid_point.z);
const ground_segmentation::PlaneBasis basis = getPlaneBasis(plane_normal);
const PlaneBasis basis = getPlaneBasis(plane_normal);
Eigen::Matrix3d rot;
rot << basis.e_x.x(), basis.e_y.x(), basis.e_z.x(), basis.e_x.y(), basis.e_y.y(), basis.e_z.y(),
basis.e_x.z(), basis.e_y.z(), basis.e_z.z();
@@ -396,7 +396,7 @@ rcl_interfaces::msg::SetParametersResult RANSACGroundFilterComponent::paramCallb
return result;
}

} // namespace ground_segmentation
} // namespace autoware::ground_segmentation

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(ground_segmentation::RANSACGroundFilterComponent)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::ground_segmentation::RANSACGroundFilterComponent)
Original file line number Diff line number Diff line change
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef GROUND_SEGMENTATION__RANSAC_GROUND_FILTER_NODELET_HPP_
#define GROUND_SEGMENTATION__RANSAC_GROUND_FILTER_NODELET_HPP_
#ifndef RANSAC_GROUND_FILTER__NODE_HPP_
#define RANSAC_GROUND_FILTER__NODE_HPP_

#include "pointcloud_preprocessor/filter.hpp"

@@ -38,7 +38,7 @@
#include <string>
#include <vector>

namespace ground_segmentation
namespace autoware::ground_segmentation
{
struct PlaneBasis
{
@@ -129,6 +129,6 @@ class RANSACGroundFilterComponent : public pointcloud_preprocessor::Filter
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
explicit RANSACGroundFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace ground_segmentation
} // namespace autoware::ground_segmentation

#endif // GROUND_SEGMENTATION__RANSAC_GROUND_FILTER_NODELET_HPP_
#endif // RANSAC_GROUND_FILTER__NODE_HPP_
Original file line number Diff line number Diff line change
@@ -53,19 +53,18 @@
//
//M*/

#ifndef GROUND_SEGMENTATION__GENCOLORS_HPP_
#define GROUND_SEGMENTATION__GENCOLORS_HPP_
#ifndef RAY_GROUND_FILTER__GENCOLORS_HPP_
#define RAY_GROUND_FILTER__GENCOLORS_HPP_

#include <opencv2/core/core.hpp>
#include <opencv2/opencv.hpp>

#include <opencv2/core/core_c.h>

#include <iostream>
#include <vector>
// #include <precomp.hpp>
#include <opencv2/opencv.hpp>

namespace ray_ground_filter
namespace autoware::ray_ground_filter
{
using namespace cv; // NOLINT

@@ -159,5 +158,5 @@ inline void generateColors(std::vector<Scalar> & colors, size_t count, size_t fa
colors[i] = Scalar(c.x, c.y, c.z);
}
}
} // namespace ray_ground_filter
#endif // GROUND_SEGMENTATION__GENCOLORS_HPP_
} // namespace autoware::ray_ground_filter
#endif // RAY_GROUND_FILTER__GENCOLORS_HPP_
Original file line number Diff line number Diff line change
@@ -29,12 +29,12 @@
* v1.0: amc-nu (abrahammonrroy@yahoo.com)
*/

#include "ground_segmentation/ray_ground_filter_nodelet.hpp"
#include "node.hpp"

#include <string>
#include <vector>

namespace ground_segmentation
namespace autoware::ground_segmentation
{
using pointcloud_preprocessor::get_param;

@@ -250,8 +250,9 @@ void RayGroundFilterComponent::ClassifyPointCloud(
// // Enable the dynamic reconfigure service
// has_service = true;
// srv_ = boost::make_shared<
// dynamic_reconfigure::Server<ground_segmentation::RayGroundFilterConfig> >(nh);
// dynamic_reconfigure::Server<ground_segmentation::RayGroundFilterConfig>::CallbackType f =
// dynamic_reconfigure::Server<autoware::ground_segmentation::RayGroundFilterConfig> >(nh);
// dynamic_reconfigure::Server<autoware::ground_segmentation::RayGroundFilterConfig>::CallbackType
// f =
// boost::bind(&RayGroundFilterComponent::config_callback, this, _1, _2);
// srv_->setCallback(f);
// return (true);
@@ -394,7 +395,7 @@ rcl_interfaces::msg::SetParametersResult RayGroundFilterComponent::paramCallback
return result;
}

} // namespace ground_segmentation
} // namespace autoware::ground_segmentation

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(ground_segmentation::RayGroundFilterComponent)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::ground_segmentation::RayGroundFilterComponent)
Original file line number Diff line number Diff line change
@@ -42,8 +42,8 @@
* v1.0: amc-nu (abrahammonrroy@yahoo.com)
*/

#ifndef GROUND_SEGMENTATION__RAY_GROUND_FILTER_NODELET_HPP_
#define GROUND_SEGMENTATION__RAY_GROUND_FILTER_NODELET_HPP_
#ifndef RAY_GROUND_FILTER__NODE_HPP_
#define RAY_GROUND_FILTER__NODE_HPP_

#include <sensor_msgs/msg/point_cloud2.hpp>

@@ -58,14 +58,7 @@
#include <tf2_eigen/tf2_eigen.hpp>
#endif

#include <tf2_ros/transform_listener.h>

#include <chrono>
#include <string>
#include <vector>
// #include <pcl_ros/point_cloud.h>

#include "ground_segmentation/gencolors.hpp"
#include "gencolors.hpp"
#include "pointcloud_preprocessor/filter.hpp"

#include <opencv2/core.hpp>
@@ -76,11 +69,17 @@
#include <boost/geometry/geometries/point_xy.hpp>
#include <boost/optional.hpp>

#include <tf2_ros/transform_listener.h>

#include <chrono>
#include <string>
#include <vector>

namespace bg = boost::geometry;
using Point = bg::model::d2::point_xy<double>;
using Polygon = bg::model::polygon<Point>;

namespace ground_segmentation
namespace autoware::ground_segmentation
{
class RayGroundFilterComponent : public pointcloud_preprocessor::Filter
{
@@ -206,6 +205,6 @@ class RayGroundFilterComponent : public pointcloud_preprocessor::Filter
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
explicit RayGroundFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace ground_segmentation
} // namespace autoware::ground_segmentation

#endif // GROUND_SEGMENTATION__RAY_GROUND_FILTER_NODELET_HPP_
#endif // RAY_GROUND_FILTER__NODE_HPP_
Loading
Loading