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
6 changes: 3 additions & 3 deletions .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ _commands:
- restore_cache:
name: Restore Cache << parameters.key >>
keys:
- "<< parameters.key >>-v38\
- "<< parameters.key >>-v39\
-{{ arch }}\
-{{ .Branch }}\
-{{ .Environment.CIRCLE_PR_NUMBER }}\
-{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}"
- "<< parameters.key >>-v38\
- "<< parameters.key >>-v39\
-{{ arch }}\
-main\
-<no value>\
Expand All @@ -58,7 +58,7 @@ _commands:
steps:
- save_cache:
name: Save Cache << parameters.key >>
key: "<< parameters.key >>-v38\
key: "<< parameters.key >>-v39\
-{{ arch }}\
-{{ .Branch }}\
-{{ .Environment.CIRCLE_PR_NUMBER }}\
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/build_main_against_distros.yml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ jobs:

steps:
- name: Checkout repository
uses: actions/checkout@v4
uses: actions/checkout@v5

- name: Set up Docker build context
run: |
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/claude.yml
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ jobs:
id-token: write
steps:
- name: Checkout repository
uses: actions/checkout@v4
uses: actions/checkout@v5
with:
fetch-depth: 1

Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ jobs:
matrix:
linter: [xmllint, cpplint, uncrustify, pep257, flake8, mypy]
steps:
- uses: actions/checkout@v4
- uses: actions/checkout@v5

- name: Install typeshed for mypy
if: matrix.linter == 'mypy'
Expand All @@ -30,7 +30,7 @@ jobs:
name: pre-commit
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- uses: actions/checkout@v5
- uses: actions/setup-python@v5
- uses: pre-commit/action@v3.0.1
env:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/update_ci_image.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ jobs:
- check_ci_image
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- uses: actions/checkout@v5
- name: Set up Docker Buildx
uses: docker/setup-buildx-action@v3
- name: Login to Docker Hub
Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_amcl)

find_package(ament_cmake REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_behavior_tree CXX)

find_package(ament_cmake REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_behaviors)

find_package(ament_cmake REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_bringup)

find_package(ament_cmake REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_bt_navigator)

find_package(ament_cmake REQUIRED)
Expand Down
6 changes: 5 additions & 1 deletion nav2_collision_monitor/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_collision_monitor)

find_package(ament_cmake REQUIRED)
Expand All @@ -17,6 +17,7 @@ find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(nav2_ros_common REQUIRED)
find_package(point_cloud_transport REQUIRED)

nav2_package()

Expand Down Expand Up @@ -54,6 +55,7 @@ target_link_libraries(${monitor_library_name} PUBLIC
tf2::tf2
tf2_ros::tf2_ros
${visualization_msgs_TARGETS}
point_cloud_transport::point_cloud_transport
)
target_link_libraries(${monitor_library_name} PRIVATE
rclcpp_components::component
Expand Down Expand Up @@ -88,6 +90,7 @@ target_link_libraries(${detector_library_name} PUBLIC
tf2_ros::tf2_ros
tf2::tf2
${visualization_msgs_TARGETS}
point_cloud_transport::point_cloud_transport
)
target_link_libraries(${detector_library_name} PRIVATE
rclcpp_components::component
Expand Down Expand Up @@ -169,6 +172,7 @@ ament_export_dependencies(
tf2_ros
nav2_ros_common
visualization_msgs
point_cloud_transport
)
ament_export_targets(export_${PROJECT_NAME})

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <string>

#include "sensor_msgs/msg/point_cloud2.hpp"
#include "point_cloud_transport/point_cloud_transport.hpp"

#include "nav2_collision_monitor/source.hpp"

Expand Down Expand Up @@ -98,7 +99,15 @@ class PointCloud : public Source
// ----- Variables -----

/// @brief PointCloud data subscriber
#if RCLCPP_VERSION_GTE(30, 0, 0)
std::shared_ptr<point_cloud_transport::PointCloudTransport> pct_;
point_cloud_transport::Subscriber data_sub_;
#else
nav2::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr data_sub_;
#endif

// Transport type used for PointCloud messages (e.g., raw or compressed)
std::string transport_type_;

// Minimum and maximum height of PointCloud projected to 2D space
double min_height_, max_height_;
Expand Down
2 changes: 2 additions & 0 deletions nav2_collision_monitor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
<depend>tf2_ros</depend>
<depend>visualization_msgs</depend>
<depend>nav2_ros_common</depend>
<depend>point_cloud_transport</depend>
<depend>point_cloud_transport_plugins</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ collision_detector:
pointcloud:
type: "pointcloud"
topic: "/intel_realsense_r200_depth/points"
transport_type: "raw" # Options: raw, zlib, draco, zstd
min_height: 0.1
max_height: 0.5
enabled: True
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ collision_monitor:
pointcloud:
type: "pointcloud"
topic: "/intel_realsense_r200_depth/points"
transport_type: "raw" # Options: raw, zlib, draco, zstd
min_height: 0.1
max_height: 0.5
enabled: True
17 changes: 17 additions & 0 deletions nav2_collision_monitor/src/pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,11 @@ PointCloud::PointCloud(
PointCloud::~PointCloud()
{
RCLCPP_INFO(logger_, "[%s]: Destroying PointCloud", source_name_.c_str());
#if RCLCPP_VERSION_GTE(30, 0, 0)
data_sub_.shutdown();
#else
data_sub_.reset();
#endif
}

void PointCloud::configure()
Expand All @@ -60,10 +64,20 @@ void PointCloud::configure()

getParameters(source_topic);

#if RCLCPP_VERSION_GTE(30, 0, 0)
const point_cloud_transport::TransportHints hint(transport_type_);
pct_ = std::make_shared<point_cloud_transport::PointCloudTransport>(*node);
data_sub_ = pct_->subscribe(
source_topic, nav2::qos::SensorDataQoS(),
std::bind(&PointCloud::dataCallback, this, std::placeholders::_1),
{}, &hint
);
#else
data_sub_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
source_topic,
std::bind(&PointCloud::dataCallback, this, std::placeholders::_1),
nav2::qos::SensorDataQoS());
#endif

// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
Expand Down Expand Up @@ -131,6 +145,9 @@ void PointCloud::getParameters(std::string & source_topic)
nav2::declare_parameter_if_not_declared(
node, source_name_ + ".min_range", rclcpp::ParameterValue(0.0));
min_range_ = node->get_parameter(source_name_ + ".min_range").as_double();
nav2::declare_parameter_if_not_declared(
node, source_name_ + ".transport_type", rclcpp::ParameterValue(std::string("raw")));
transport_type_ = node->get_parameter(source_name_ + ".transport_type").as_string();
}

void PointCloud::dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
Expand Down
2 changes: 1 addition & 1 deletion nav2_common/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)

project(nav2_common NONE)

Expand Down
2 changes: 1 addition & 1 deletion nav2_constrained_smoother/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_constrained_smoother)

set(CMAKE_BUILD_TYPE Release) # significant Ceres optimization speedup
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_controller)

find_package(ament_cmake REQUIRED)
Expand Down
2 changes: 1 addition & 1 deletion nav2_core/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_core)

find_package(ament_cmake REQUIRED)
Expand Down
5 changes: 4 additions & 1 deletion nav2_costmap_2d/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(nav2_costmap_2d)

find_package(ament_cmake REQUIRED)
Expand Down Expand Up @@ -26,6 +26,7 @@ find_package(tf2_ros REQUIRED)
find_package(nav2_ros_common REQUIRED)
find_package(tf2_sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(point_cloud_transport REQUIRED)

nav2_package()

Expand Down Expand Up @@ -88,6 +89,7 @@ target_link_libraries(layers PUBLIC
nav2_ros_common::nav2_ros_common
tf2::tf2
nav2_ros_common::nav2_ros_common
point_cloud_transport::point_cloud_transport
)
target_link_libraries(layers PRIVATE
pluginlib::pluginlib
Expand Down Expand Up @@ -222,6 +224,7 @@ ament_export_dependencies(
tf2_ros
tf2_sensor_msgs
nav2_ros_common
point_cloud_transport
)
pluginlib_export_plugin_description_file(nav2_costmap_2d costmap_plugins.xml)
ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ class CostmapFilter : public Layer
*/
void updateBounds(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y, double * max_x, double * max_y) final;
double * min_x, double * min_y, double * max_x, double * max_y) override;

/**
* @brief Update the costs in the master costmap in the window
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,20 @@ class KeepoutFilter : public CostmapFilter
void initializeFilter(
const std::string & filter_info_topic);

/**
* @brief Update the bounds of the master costmap by this layer's update dimensions
* @param robot_x X pose of robot
* @param robot_y Y pose of robot
* @param robot_yaw Robot orientation
* @param min_x X min map coord of the window to update
* @param min_y Y min map coord of the window to update
* @param max_x X max map coord of the window to update
* @param max_y Y max map coord of the window to update
*/
void updateBounds(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y, double * max_x, double * max_y) override;

/**
* @brief Process the keepout layer at the current pose / bounds / grid
*/
Expand Down Expand Up @@ -106,8 +120,15 @@ class KeepoutFilter : public CostmapFilter
bool override_lethal_cost_{false}; // If true, lethal cost will be overridden
unsigned char lethal_override_cost_{252}; // Value to override lethal cost with
bool last_pose_lethal_{false}; // If true, last pose was lethal
unsigned int lethal_state_update_min_x_{999999u}, lethal_state_update_min_y_{999999u};
unsigned int lethal_state_update_max_x_{0u}, lethal_state_update_max_y_{0u};
bool is_pose_lethal_{false};
double lethal_state_update_min_x_, lethal_state_update_min_y_;
double lethal_state_update_max_x_, lethal_state_update_max_y_;

unsigned int x_{0};
unsigned int y_{0};
unsigned int width_{0};
unsigned int height_{0};
bool has_updated_data_{false};
};

} // namespace nav2_costmap_2d
Expand Down
1 change: 1 addition & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
#pragma GCC diagnostic pop

#include "message_filters/subscriber.hpp"
#include "point_cloud_transport/subscriber_filter.hpp"

#include "nav_msgs/msg/occupancy_grid.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
Expand Down
2 changes: 2 additions & 0 deletions nav2_costmap_2d/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@
<depend>tf2_sensor_msgs</depend>
<depend>visualization_msgs</depend>
<depend>nav2_ros_common</depend>
<depend>point_cloud_transport</depend>
<depend>point_cloud_transport_plugins</depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ unsigned char CostmapFilter::getMaskCost(
{
const unsigned int index = my * filter_mask->info.width + mx;

const char data = filter_mask->data[index];
const signed char data = filter_mask->data[index];
if (data == nav2_util::OCC_GRID_UNKNOWN) {
return NO_INFORMATION;
} else {
Expand Down
Loading
Loading