Skip to content
Merged
Show file tree
Hide file tree
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
24 changes: 18 additions & 6 deletions pointcloud_crop_box/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ set(PACKAGE_DEPENDENCIES
pcl_conversions
pcl_ros
rclcpp
rclcpp_components
sensor_msgs
tf2
tf2_geometry_msgs
Expand All @@ -30,18 +31,29 @@ include_directories(include ${PCL_INCLUDE_DIRS})
generate_parameter_library(pointcloud_crop_box_params
src/pointcloud_crop_box_params.yaml)

add_executable(pointcloud_crop_box_node src/main.cpp
src/pointcloud_crop_box_node.cpp)
add_library(pointcloud_crop_box_node_component SHARED
src/pointcloud_crop_box_node.cpp)

ament_target_dependencies(pointcloud_crop_box_node ${PACKAGE_DEPENDENCIES})
ament_target_dependencies(pointcloud_crop_box_node_component
${PACKAGE_DEPENDENCIES})

target_link_libraries(pointcloud_crop_box_node ${PCL_LIBRARIES}
target_link_libraries(pointcloud_crop_box_node_component ${PCL_LIBRARIES}
pointcloud_crop_box_params)
target_include_directories(
pointcloud_crop_box_node
pointcloud_crop_box_node_component
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}/include>)

install(TARGETS pointcloud_crop_box_node DESTINATION lib/${PROJECT_NAME})
rclcpp_components_register_node(
pointcloud_crop_box_node_component PLUGIN
"pointcloud_crop_box::PointCloudCropBoxNode" EXECUTABLE
pointcloud_crop_box_node)

install(
TARGETS pointcloud_crop_box_node_component pointcloud_crop_box_params
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME})

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,16 @@

#include "pointcloud_crop_box/pointcloud_crop_box_params.hpp"

class PointcloudCropBoxNode : public rclcpp::Node
namespace pointcloud_crop_box
{

class PointCloudCropBoxNode : public rclcpp::Node
{
public:
PointcloudCropBoxNode();
PointCloudCropBoxNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

private:
void PointcloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg);
void PointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg);
void LaserScanCallback(const sensor_msgs::msg::LaserScan::SharedPtr msg);

geometry_msgs::msg::TransformStamped GetTransform(const std::string & source_frame);
Expand Down Expand Up @@ -71,4 +74,6 @@ class PointcloudCropBoxNode : public rclcpp::Node
laser_geometry::LaserProjection projector_;
};

} // namespace pointcloud_crop_box

#endif // POINTCLOUD_CROP_BOX_POINTCLOUD_CROP_BOX_POINTCLOUD_CROP_BOX_NODE_HPP_
6 changes: 5 additions & 1 deletion pointcloud_crop_box/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<package format="3">
<name>pointcloud_crop_box</name>
<version>0.1.0</version>
<description>3D box filter for Pointcloud2</description>
<description>3D box filter for PointCloud2</description>
<maintainer email="[email protected]">Husarion</maintainer>
<license>Apache License 2.0</license>

Expand All @@ -12,6 +12,7 @@
<url type="bugtracker">https://github.com/husarion/husarion_ugv_ros/issues</url>

<author email="[email protected]">Jakub Delicat</author>
<author email="[email protected]">Dawid Kmak</author>

<buildtool_depend>ament_cmake</buildtool_depend>

Expand All @@ -20,13 +21,16 @@
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tf2_sensor_msgs</depend>
<depend>vision_msgs</depend>

<exec_depend>vision_msgs_rviz_plugins</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
38 changes: 0 additions & 38 deletions pointcloud_crop_box/src/main.cpp

This file was deleted.

34 changes: 22 additions & 12 deletions pointcloud_crop_box/src/pointcloud_crop_box_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,13 @@
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

PointcloudCropBoxNode::PointcloudCropBoxNode()
: rclcpp::Node("pointcloud_crop_box"), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_)
namespace pointcloud_crop_box
{

PointCloudCropBoxNode::PointCloudCropBoxNode(const rclcpp::NodeOptions & options)
: rclcpp::Node("pointcloud_crop_box", options),
tf_buffer_(this->get_clock()),
tf_listener_(tf_buffer_)
{
param_listener_ =
std::make_shared<pointcloud_crop_box_params::ParamListener>(get_node_parameters_interface());
Expand All @@ -36,11 +41,11 @@ PointcloudCropBoxNode::PointcloudCropBoxNode()
if (params_.message_type == "pointcloud") {
pc2_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
params_.input_topic, 10,
std::bind(&PointcloudCropBoxNode::PointcloudCallback, this, std::placeholders::_1));
std::bind(&PointCloudCropBoxNode::PointCloudCallback, this, std::placeholders::_1));
} else {
ls_sub_ = this->create_subscription<sensor_msgs::msg::LaserScan>(
params_.input_topic, 10,
std::bind(&PointcloudCropBoxNode::LaserScanCallback, this, std::placeholders::_1));
std::bind(&PointCloudCropBoxNode::LaserScanCallback, this, std::placeholders::_1));
}

if (params_.visualize_bounding_box) {
Expand All @@ -54,7 +59,7 @@ PointcloudCropBoxNode::PointcloudCropBoxNode()
RCLCPP_INFO(this->get_logger(), "Initialized successfully.");
}

void PointcloudCropBoxNode::PointcloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
void PointCloudCropBoxNode::PointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
{
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>());

Expand Down Expand Up @@ -96,15 +101,15 @@ void PointcloudCropBoxNode::PointcloudCallback(const sensor_msgs::msg::PointClou
}
}

void PointcloudCropBoxNode::LaserScanCallback(const sensor_msgs::msg::LaserScan::SharedPtr msg)
void PointCloudCropBoxNode::LaserScanCallback(const sensor_msgs::msg::LaserScan::SharedPtr msg)
{
auto cloud_msg = std::make_shared<sensor_msgs::msg::PointCloud2>();

projector_.projectLaser(*msg, *cloud_msg);
PointcloudCallback(cloud_msg);
PointCloudCallback(cloud_msg);
}

geometry_msgs::msg::TransformStamped PointcloudCropBoxNode::GetTransform(
geometry_msgs::msg::TransformStamped PointCloudCropBoxNode::GetTransform(
const std::string & source_frame)
{
geometry_msgs::msg::TransformStamped transform_stamped;
Expand All @@ -121,7 +126,7 @@ geometry_msgs::msg::TransformStamped PointcloudCropBoxNode::GetTransform(
return transform_stamped;
}

pcl::PointCloud<pcl::PointXYZ>::Ptr PointcloudCropBoxNode::TransformCloud(
pcl::PointCloud<pcl::PointXYZ>::Ptr PointCloudCropBoxNode::TransformCloud(
const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
const geometry_msgs::msg::TransformStamped & transform_stamped)
{
Expand All @@ -137,7 +142,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr PointcloudCropBoxNode::TransformCloud(
return transformed_cloud;
}

pcl::PointCloud<pcl::PointXYZ>::Ptr PointcloudCropBoxNode::Crop(
pcl::PointCloud<pcl::PointXYZ>::Ptr PointCloudCropBoxNode::Crop(
const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud)
{
pcl::CropBox<pcl::PointXYZ> crop_box_filter;
Expand All @@ -151,7 +156,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr PointcloudCropBoxNode::Crop(
return filtered_cloud;
}

geometry_msgs::msg::TransformStamped PointcloudCropBoxNode::InverseTransform(
geometry_msgs::msg::TransformStamped PointCloudCropBoxNode::InverseTransform(
const geometry_msgs::msg::TransformStamped & transform_stamped)
{
tf2::Transform tf2_transform;
Expand Down Expand Up @@ -180,7 +185,7 @@ geometry_msgs::msg::TransformStamped PointcloudCropBoxNode::InverseTransform(
return inverse_transform_stamped;
}

vision_msgs::msg::BoundingBox3D PointcloudCropBoxNode::CreateBoundingBox()
vision_msgs::msg::BoundingBox3D PointCloudCropBoxNode::CreateBoundingBox()
{
vision_msgs::msg::BoundingBox3D bbox;

Expand All @@ -194,3 +199,8 @@ vision_msgs::msg::BoundingBox3D PointcloudCropBoxNode::CreateBoundingBox()

return bbox;
}

} // namespace pointcloud_crop_box

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_crop_box::PointCloudCropBoxNode)