Skip to content

Commit

Permalink
Renamed pkg mrpt_local_obstacles -> mrpt_pointcloud_pipeline to refle…
Browse files Browse the repository at this point in the history
…ct new capabilities
  • Loading branch information
jlblancoc committed Jan 3, 2024
1 parent 68ec68a commit 828eb83
Show file tree
Hide file tree
Showing 13 changed files with 25 additions and 23 deletions.
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,9 @@ Related to localization:
* [mrpt_pf_localization](mrpt_pf_localization): A node for particle filter-based localization of a robot from any kind of metric map (gridmap, points, range-only sensors, ...).

Related to sensor pipelines:
* [mrpt_local_obstacles](mrpt_local_obstacles): A node that maintains a local obstacle map, mostly needed for 2D lidars to keep a memory of obstacles that get out of the sensor field of view.
* [mrpt_pointcloud_pipeline](mrpt_pointcloud_pipeline): A node that maintains a local obstacle map from recent sensor readings, including optional point cloud pipeline filtering or processing. For example,
- For 3D LIDARs, to filter by a volume or area, downsample the number of points, etc.
- For 2D laser scanners, to keep a memory of obstacles that get out of the sensor field of view.

Related to autonomous navigation:
* [mrpt_reactivenav2d](mrpt_reactivenav2d): A pure reactive navigator for polygonal robots on 2D worlds.
Expand Down
2 changes: 2 additions & 0 deletions mrpt_map/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ find_package(nav_msgs REQUIRED)

find_package(mrpt-maps REQUIRED)
find_package(mrpt-ros2bridge REQUIRED)
find_package(mp2p_icp_map REQUIRED)

message(STATUS "MRPT_VERSION: ${MRPT_VERSION}")

Expand Down Expand Up @@ -54,6 +55,7 @@ target_include_directories(map_server_node
target_link_libraries(map_server_node
mrpt::maps
mrpt::ros2bridge
mola::mp2p_icp_map
)

ament_target_dependencies(
Expand Down
1 change: 1 addition & 0 deletions mrpt_map/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>mrpt2</depend>
<depend>mp2p_icp</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>nav_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion mrpt_navigation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>mrpt_local_obstacles</depend>
<depend>mrpt_pointcloud_pipeline</depend>
<depend>mrpt_pf_localization</depend>
<depend>mrpt_map</depend>
<depend>mrpt_rawlog</depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package mrpt_local_obstacles
Changelog for package mrpt_pointcloud_pipeline
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.0.3 (2022-06-25)
Expand Down Expand Up @@ -129,7 +129,7 @@ Changelog for package mrpt_local_obstacles

0.1.5 (2015-04-29)
------------------
* mrpt_local_obstacles: Fix wrong report of number of scan sources
* mrpt_pointcloud_pipeline: Fix wrong report of number of scan sources
* Fix build against mrpt 1.3.0
* Contributors: Jose Luis Blanco

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
project(mrpt_local_obstacles)
project(mrpt_pointcloud_pipeline)

# find dependencies
find_package(ament_cmake REQUIRED)
Expand Down Expand Up @@ -39,12 +39,11 @@ IF(CMAKE_COMPILER_IS_GNUCXX AND NOT CMAKE_BUILD_TYPE MATCHES "Debug")
ENDIF()


find_package(mp2p_icp REQUIRED)
find_package(mp2p_icp_filters REQUIRED)

add_executable(${PROJECT_NAME}_node
src/mrpt_local_obstacles_node.cpp
include/mrpt_local_obstacles/mrpt_local_obstacles_node.hpp)
src/mrpt_pointcloud_pipeline_node.cpp
include/mrpt_pointcloud_pipeline/mrpt_pointcloud_pipeline_node.h)

target_include_directories(${PROJECT_NAME}_node
PUBLIC
Expand All @@ -58,7 +57,7 @@ target_link_libraries(
mrpt::obs
mrpt::gui
mrpt::ros2bridge
mp2p_icp_filters
mola::mp2p_icp_filters
)

ament_target_dependencies(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!-- Node: Local obstacles builder -->
<node pkg="mrpt_local_obstacles" type="mrpt_local_obstacles_node" name="mrpt_local_obstacles_node" output="screen">
<node pkg="mrpt_pointcloud_pipeline" type="mrpt_pointcloud_pipeline_node" name="mrpt_pointcloud_pipeline_node" output="screen">
<param name="source_topics_2dscan" value="laser1,laser2"/>
</node>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ def generate_launch_description():
)

# Node: Local obstacles builder
mrpt_local_obstacles_node = Node(
package='mrpt_local_obstacles',
executable='mrpt_local_obstacles_node',
name='mrpt_local_obstacles_node',
mrpt_pointcloud_pipeline_node = Node(
package='mrpt_pointcloud_pipeline',
executable='mrpt_pointcloud_pipeline_node',
name='mrpt_pointcloud_pipeline_node',
output='screen',
parameters=[
{'source_topics_2dscan': LaunchConfiguration('lidar_topic_name')},
Expand Down Expand Up @@ -70,5 +70,5 @@ def generate_launch_description():
time_window_arg,
filter_yaml_file_arg,
filter_output_layer_name_arg,
mrpt_local_obstacles_node
mrpt_pointcloud_pipeline_node
])
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
<?xml version="1.0"?>
<package format="3">
<name>mrpt_local_obstacles</name>
<name>mrpt_pointcloud_pipeline</name>
<version>1.0.3</version>
<description>Maintains a local obstacle map (point cloud,
voxels or occupancy grid) from recent sensor readings within a
configurable time window.</description>
<description>Maintains a local obstacle map from recent sensor readings, including optional point cloud pipeline filtering or processing.</description>

<maintainer email="[email protected]">Jose-Luis Blanco-Claraco</maintainer>
<maintainer email="[email protected]">Shravan S Rai</maintainer>
Expand All @@ -16,7 +14,6 @@

<url type="website">https://github.com/mrpt-ros-pkg/mrpt_navigation</url>


<buildtool_depend>ament_cmake</buildtool_depend>

<depend>mrpt2</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@
| All rights reserved. Released under BSD 3-Clause license. See LICENSE |
+------------------------------------------------------------------------+ */

#include <mrpt_local_obstacles/mrpt_local_obstacles_node.hpp>
#include <mrpt_pointcloud_pipeline/mrpt_pointcloud_pipeline_node.h>

#include <sstream>

#include "rclcpp_components/register_node_macro.hpp"
Expand All @@ -18,7 +19,7 @@ using namespace mrpt::maps;
using namespace mrpt::obs;

LocalObstaclesNode::LocalObstaclesNode(const rclcpp::NodeOptions& options)
: Node("mrpt_local_obstacles", options)
: Node("mrpt_pointcloud_pipeline", options)
{
read_parameters();

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!-- Node: Local obstacles builder -->
<node pkg="mrpt_local_obstacles" type="mrpt_local_obstacles_node" name="mrpt_local_obstacles_node" output="screen">
<node pkg="mrpt_pointcloud_pipeline" type="mrpt_pointcloud_pipeline_node" name="mrpt_pointcloud_pipeline_node" output="screen">
<param name="source_topics_2dscan" value="laser1,laser2"/>
<param name="show_gui" value="false"/>
</node>
Expand Down

0 comments on commit 828eb83

Please sign in to comment.