Skip to content

Commit f72d95b

Browse files
SteveMacenskiGoesMGoesMjwallace42pepisg
authored andcommitted
Humble sync 10: April 4, 2024 (ros-navigation#4241)
* change pointer free order in amcl to avoid use-after-free bug mentioned in ros-navigation#4068 (ros-navigation#4070) Signed-off-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> * Allow path end pose deviation revive (ros-navigation#4065) * Support stitching paths in compute path to poses * Update nav2_planner/src/planner_server.cpp Co-authored-by: Steve Macenski <[email protected]> * Rename parameter to allow_path_through_poses_goal_deviation * Fix description * restore nav2_params * missing whitespace * lint fix * removed parameter Signed-off-by: gg <[email protected]> * Update planner_server.hpp * Update planner_server.cpp --------- Signed-off-by: gg <[email protected]> Co-authored-by: pepisg <[email protected]> Co-authored-by: Pedro Alejandro González <[email protected]> Co-authored-by: Steve Macenski <[email protected]> * Change costmap_queue to shared library (ros-navigation#4072) Signed-off-by: cybaol <[email protected]> * free `map_sub_` before `map_free(map_)` to avoid UAF&&NullPtr bug mentioned in ros-navigation#4078 (ros-navigation#4079) * free `map_sub_` before `map_free(map_)` Signed-off-by: GoesM <[email protected]> * reformat Signed-off-by: GoesM <[email protected]> --------- Signed-off-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> * adding progress checker selector BT node (ros-navigation#4109) * New MPPI Cost Critic (Contrib: Brice Renaudeau) (ros-navigation#4090) * Share code Signed-off-by: Brice <[email protected]> * Update inflation_cost_critic.hpp - copyright - ifndef Signed-off-by: Brice <[email protected]> * fix lint cpp - extra space Signed-off-by: Brice <[email protected]> * Fix Smac Planner confined collision checker (ros-navigation#4055) * Update collision_checker.cpp Signed-off-by: Steve Macenski <[email protected]> * Fix tests Signed-off-by: Steve Macenski <[email protected]> * Update test_a_star.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Brice <[email protected]> * Prevent analytic expansions from shortcutting Smac Planner feasible paths (ros-navigation#3962) * a potential solution to smac shortcutting * costmap reoslution * some fixes * completed prototype * some fixes for collision detection and performance * completing shortcutting fix * updating tests * adding readme --------- Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Brice <[email protected]> * change pointer free order in amcl to avoid use-after-free bug mentioned in ros-navigation#4068 (ros-navigation#4070) Signed-off-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> Signed-off-by: Brice <[email protected]> * [Smac Planner] Massive Improvement of Behavior for SE2 Footprint Checking (ie non-circular robots) In Confined Settings (ros-navigation#4067) * prototype to test SE2 footprint H improvements * some fixes * fixed * invert logic * Working final prototype to be tested * complete unit test conversions * Update inflation_layer.hpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Brice <[email protected]> * Adding new Smac paper to readme Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Brice <[email protected]> * Update README.md Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Brice <[email protected]> * [behavior_tree] don't repeat yourself in "blackboard->set" (ros-navigation#4074) * don't repeat yourself: templates in tests Signed-off-by: Davide Faconti <[email protected]> * misse change Signed-off-by: Davide Faconti <[email protected]> --------- Signed-off-by: Davide Faconti <[email protected]> Signed-off-by: Brice <[email protected]> * Allow path end pose deviation revive (ros-navigation#4065) * Support stitching paths in compute path to poses * Update nav2_planner/src/planner_server.cpp Co-authored-by: Steve Macenski <[email protected]> * Rename parameter to allow_path_through_poses_goal_deviation * Fix description * restore nav2_params * missing whitespace * lint fix * removed parameter Signed-off-by: gg <[email protected]> * Update planner_server.hpp * Update planner_server.cpp --------- Signed-off-by: gg <[email protected]> Co-authored-by: pepisg <[email protected]> Co-authored-by: Pedro Alejandro González <[email protected]> Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Brice <[email protected]> * Updated code to use getInflationLayer() method (ros-navigation#4076) * updated code to use getInflationLayer method Signed-off-by: Jose Faria <[email protected]> * Fix linting Signed-off-by: Jose Faria <[email protected]> --------- Signed-off-by: Jose Faria <[email protected]> Signed-off-by: Brice <[email protected]> * 1594 twist stamped publisher (ros-navigation#4077) * Add TwistStamped to controller_server via TwistPublisher util * Add a new util class for publishing either Twist or TwistStamped * Add a new parameter for selecting to stamp the twist data * Consume TwistPublisher in nav2_controller Signed-off-by: Ryan Friedman <[email protected]> * Fix small issues * Unused variable * Incorrect doxygen Signed-off-by: Ryan Friedman <[email protected]> * Remove stored node and assert Signed-off-by: Ryan Friedman <[email protected]> * Add tests for node * Facing timeout even though it does the same thing as velocity smoother test Signed-off-by: Ryan Friedman <[email protected]> * Add missing spin call to solve timeout Signed-off-by: Ryan Friedman <[email protected]> * Fix copyright (me instead of intel) Signed-off-by: Ryan Friedman <[email protected]> * Add full test coverage with subscriber Signed-off-by: Ryan Friedman <[email protected]> * Remove unused rclcpp fixture * Can't use it due to needing to join the pub thread after rclcpp shuts down Signed-off-by: Ryan Friedman <[email protected]> * Use TwistStamped in nav2_behaviors Signed-off-by: Ryan Friedman <[email protected]> * Use TwistStamped in collision monitor node Signed-off-by: Ryan Friedman <[email protected]> * Add TwistStamped readme updates to velocity smoother Signed-off-by: Ryan Friedman <[email protected]> * Add TwistSubscriber implementation Signed-off-by: Ryan Friedman <[email protected]> * Fix syntax errors Signed-off-by: Ryan Friedman <[email protected]> * Use TwistSubscriber in test_velocity_smoother Signed-off-by: Ryan Friedman <[email protected]> * Use TwistSubscriber in assisted_teleop Signed-off-by: Ryan Friedman <[email protected]> * Use TwistSubscriber in collision monitor node Signed-off-by: Ryan Friedman <[email protected]> * Use TwistSubscriber in velocity smoother Signed-off-by: Ryan Friedman <[email protected]> * Remove unused code Signed-off-by: Ryan Friedman <[email protected]> * add timestamp and frame_id to TwistStamped message * Add missing utility include Signed-off-by: Ryan Friedman <[email protected]> * Document TwistPublisher and TwistSubscriber usage Signed-off-by: Ryan Friedman <[email protected]> * Use pass-by-reference * Instead of std::move(std::unique_ptr<TwistStamped>) Signed-off-by: Ryan Friedman <[email protected]> * Finish twist subscriber tests Signed-off-by: Ryan Friedman <[email protected]> * Add other constructor and docs Signed-off-by: Ryan Friedman <[email protected]> * Fix linter issues Signed-off-by: Ryan Friedman <[email protected]> * Manually fix paren alignment Signed-off-by: Ryan Friedman <[email protected]> * Remove GSoC reference Signed-off-by: Ryan Friedman <[email protected]> * Document twist bool param in README Signed-off-by: Ryan Friedman <[email protected]> * Handle twistPublisher in collision monitor * Implement behavior in the stamped callback * Unstamped callback calls the stamped callback * Switch to unique pointer for publisher Signed-off-by: Ryan Friedman <[email protected]> * Convert to using TwistStamped interally * Use incoming twistStamped timestamp if available * Convert all internal representations to use TwistStamped Signed-off-by: Ryan Friedman <[email protected]> * Remove nav2_util usage instructions Signed-off-by: Ryan Friedman <[email protected]> * Remove unused Twist only subscriber Signed-off-by: Ryan Friedman <[email protected]> * More linter fixes Signed-off-by: Ryan Friedman <[email protected]> * Prefer working with unique_ptr for cmd_vel * This makes it easier to switch to std::move instead of dereference on publish Signed-off-by: Ryan Friedman <[email protected]> * Completing twist stamped migration * shared to unique ptr Signed-off-by: Steve Macenski <[email protected]> * twist add stamps and properly propogated * nav2_util: fix for compiling with clang - Resolve error: moving a temporary object prevents copy elision [-Werror,-Wpessimizing-move] Signed-off-by: Rhys Mainwaring <[email protected]> --------- Signed-off-by: Ryan Friedman <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Rhys Mainwaring <[email protected]> Co-authored-by: pedro-fuoco <[email protected]> Co-authored-by: Steve Macenski <[email protected]> Co-authored-by: Rhys Mainwaring <[email protected]> Signed-off-by: Brice <[email protected]> * Change costmap_queue to shared library (ros-navigation#4072) Signed-off-by: cybaol <[email protected]> Signed-off-by: Brice <[email protected]> * fix include of hpp Signed-off-by: Brice Renaudeau <[email protected]> * inflation cost optmiizations and cleanu * rename, add defaults, and docs * smoke test addition * lintg * normalize weight * update readme * increment cache * Update cost_critic.hpp Signed-off-by: Steve Macenski <[email protected]> * Update cost_critic.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Brice <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: GoesM <[email protected]> Signed-off-by: Davide Faconti <[email protected]> Signed-off-by: gg <[email protected]> Signed-off-by: Jose Faria <[email protected]> Signed-off-by: Ryan Friedman <[email protected]> Signed-off-by: Rhys Mainwaring <[email protected]> Signed-off-by: cybaol <[email protected]> Signed-off-by: Brice Renaudeau <[email protected]> Co-authored-by: BriceRenaudeau <[email protected]> Co-authored-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> Co-authored-by: Davide Faconti <[email protected]> Co-authored-by: Joshua Wallace <[email protected]> Co-authored-by: pepisg <[email protected]> Co-authored-by: Pedro Alejandro González <[email protected]> Co-authored-by: jncfa <[email protected]> Co-authored-by: Ryan <[email protected]> Co-authored-by: pedro-fuoco <[email protected]> Co-authored-by: Rhys Mainwaring <[email protected]> Co-authored-by: Kino <[email protected]> * Use ament_export_targets for all targets (ros-navigation#4112) * Matches new internal ALIAS targets * Use ALIAS targets for all internal linkage * Remove unnecessary calls to ament_target_dependencies in test code * Export includes in proper folders for overlays in colcon Signed-off-by: Ryan Friedman <[email protected]> * Update default recommendation from Obstacles to Cost critic in MPPI (ros-navigation#4170) Signed-off-by: Steve Macenski <[email protected]> * completely shutdown inital_pose_sub_ (ros-navigation#4176) Signed-off-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> * fix typos in description messages (ros-navigation#4188) Signed-off-by: Antonio Park <[email protected]> * AMCL: Set an initial guess by service call (ros-navigation#4182) * Added initial guess service. Signed-off-by: Alexander Mock Signed-off-by: Alexander Mock <[email protected]> * - Removed added empty line - Renamed initialGuessCallback to initialPoseReceivedSrv - Added new line to SetInitialPose service definition - Removed mutex from initialPoseReceived - Cleanup service server Signed-off-by: Alexander Mock <[email protected]> * added whitespace Signed-off-by: Alexander Mock <[email protected]> * renamed initial pose service in callback bind Signed-off-by: Alexander Mock <[email protected]> --------- Signed-off-by: Alexander Mock <[email protected]> * Move lines for pre-computation to outside a loop (ros-navigation#4191) Signed-off-by: Kyungsik Park <[email protected]> * Fix typo (ros-navigation#4196) * Fix BT.CPP import Signed-off-by: Tony Najjar <[email protected]> * Update README.md --------- Signed-off-by: Tony Najjar <[email protected]> * Update footprint iif changed (ros-navigation#4193) Signed-off-by: Brice <[email protected]> * bump humble to 1.1.14 for sync * fix merge conflict * custom version of cost critic's cost method --------- Signed-off-by: GoesM <[email protected]> Signed-off-by: gg <[email protected]> Signed-off-by: cybaol <[email protected]> Signed-off-by: Brice <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Davide Faconti <[email protected]> Signed-off-by: Jose Faria <[email protected]> Signed-off-by: Ryan Friedman <[email protected]> Signed-off-by: Rhys Mainwaring <[email protected]> Signed-off-by: Brice Renaudeau <[email protected]> Signed-off-by: Antonio Park <[email protected]> Signed-off-by: Alexander Mock <[email protected]> Signed-off-by: Kyungsik Park <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Co-authored-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> Co-authored-by: Joshua Wallace <[email protected]> Co-authored-by: pepisg <[email protected]> Co-authored-by: Pedro Alejandro González <[email protected]> Co-authored-by: Kino <[email protected]> Co-authored-by: BriceRenaudeau <[email protected]> Co-authored-by: Davide Faconti <[email protected]> Co-authored-by: jncfa <[email protected]> Co-authored-by: Ryan <[email protected]> Co-authored-by: pedro-fuoco <[email protected]> Co-authored-by: Rhys Mainwaring <[email protected]> Co-authored-by: Antonio Park <[email protected]> Co-authored-by: Alexander Mock <[email protected]> Co-authored-by: Tony Najjar <[email protected]>
1 parent 83a7a4a commit f72d95b

File tree

66 files changed

+886
-138
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

66 files changed

+886
-138
lines changed

nav2_amcl/include/nav2_amcl/amcl_node.hpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535
#include "nav2_amcl/sensors/laser/laser.hpp"
3636
#include "nav2_msgs/msg/particle.hpp"
3737
#include "nav2_msgs/msg/particle_cloud.hpp"
38+
#include "nav2_msgs/srv/set_initial_pose.hpp"
3839
#include "nav_msgs/srv/set_map.hpp"
3940
#include "sensor_msgs/msg/laser_scan.hpp"
4041
#include "std_srvs/srv/empty.hpp"
@@ -210,6 +211,16 @@ class AmclNode : public nav2_util::LifecycleNode
210211
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
211212
std::shared_ptr<std_srvs::srv::Empty::Response> response);
212213

214+
// service server for providing an initial pose guess
215+
rclcpp::Service<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
216+
/*
217+
* @brief Service callback for an initial pose guess request
218+
*/
219+
void initialPoseReceivedSrv(
220+
const std::shared_ptr<rmw_request_id_t> request_header,
221+
const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> request,
222+
std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response> response);
223+
213224
// Let amcl update samples without requiring motion
214225
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr nomotion_update_srv_;
215226
/*

nav2_amcl/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_amcl</name>
5-
<version>1.1.13</version>
5+
<version>1.1.14</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_amcl/src/amcl_node.cpp

Lines changed: 21 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -325,13 +325,17 @@ AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
325325
// Get rid of the inputs first (services and message filter input), so we
326326
// don't continue to process incoming messages
327327
global_loc_srv_.reset();
328+
initial_guess_srv_.reset();
328329
nomotion_update_srv_.reset();
330+
executor_thread_.reset(); // to make sure initial_pose_sub_ completely exit
329331
initial_pose_sub_.reset();
330332
laser_scan_connection_.disconnect();
333+
tf_listener_.reset(); // listener may access lase_scan_filter_, so it should be reset earlier
331334
laser_scan_filter_.reset();
332335
laser_scan_sub_.reset();
333336

334337
// Map
338+
map_sub_.reset(); // map_sub_ may access map_, so it should be reset earlier
335339
if (map_ != NULL) {
336340
map_free(map_);
337341
map_ = nullptr;
@@ -341,7 +345,6 @@ AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
341345

342346
// Transforms
343347
tf_broadcaster_.reset();
344-
tf_listener_.reset();
345348
tf_buffer_.reset();
346349

347350
// PubSub
@@ -493,6 +496,15 @@ AmclNode::globalLocalizationCallback(
493496
pf_init_ = false;
494497
}
495498

499+
void
500+
AmclNode::initialPoseReceivedSrv(
501+
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
502+
const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> req,
503+
std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response>/*res*/)
504+
{
505+
initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
506+
}
507+
496508
// force nomotion updates (amcl updating without requiring motion)
497509
void
498510
AmclNode::nomotionUpdateCallback(
@@ -1093,20 +1105,20 @@ AmclNode::initParameters()
10931105
// Semantic checks
10941106
if (laser_likelihood_max_dist_ < 0) {
10951107
RCLCPP_WARN(
1096-
get_logger(), "You've set laser_likelihood_max_dist to be negtive,"
1108+
get_logger(), "You've set laser_likelihood_max_dist to be negative,"
10971109
" this isn't allowed so it will be set to default value 2.0.");
10981110
laser_likelihood_max_dist_ = 2.0;
10991111
}
11001112
if (max_particles_ < 0) {
11011113
RCLCPP_WARN(
1102-
get_logger(), "You've set max_particles to be negtive,"
1114+
get_logger(), "You've set max_particles to be negative,"
11031115
" this isn't allowed so it will be set to default value 2000.");
11041116
max_particles_ = 2000;
11051117
}
11061118

11071119
if (min_particles_ < 0) {
11081120
RCLCPP_WARN(
1109-
get_logger(), "You've set min_particles to be negtive,"
1121+
get_logger(), "You've set min_particles to be negative,"
11101122
" this isn't allowed so it will be set to default value 500.");
11111123
min_particles_ = 500;
11121124
}
@@ -1120,7 +1132,7 @@ AmclNode::initParameters()
11201132

11211133
if (resample_interval_ <= 0) {
11221134
RCLCPP_WARN(
1123-
get_logger(), "You've set resample_interval to be zero or negtive,"
1135+
get_logger(), "You've set resample_interval to be zero or negative,"
11241136
" this isn't allowed so it will be set to default value to 1.");
11251137
resample_interval_ = 1;
11261138
}
@@ -1533,6 +1545,10 @@ AmclNode::initServices()
15331545
"reinitialize_global_localization",
15341546
std::bind(&AmclNode::globalLocalizationCallback, this, _1, _2, _3));
15351547

1548+
initial_guess_srv_ = create_service<nav2_msgs::srv::SetInitialPose>(
1549+
"set_initial_pose",
1550+
std::bind(&AmclNode::initialPoseReceivedSrv, this, _1, _2, _3));
1551+
15361552
nomotion_update_srv_ = create_service<std_srvs::srv::Empty>(
15371553
"request_nomotion_update",
15381554
std::bind(&AmclNode::nomotionUpdateCallback, this, _1, _2, _3));

nav2_amcl/src/sensors/laser/likelihood_field_model.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,17 @@ LikelihoodFieldModel::sensorFunction(LaserData * data, pf_sample_set_t * set)
5353

5454
self = reinterpret_cast<LikelihoodFieldModel *>(data->laser);
5555

56+
// Pre-compute a couple of things
57+
double z_hit_denom = 2 * self->sigma_hit_ * self->sigma_hit_;
58+
double z_rand_mult = 1.0 / data->range_max;
59+
60+
step = (data->range_count - 1) / (self->max_beams_ - 1);
61+
62+
// Step size must be at least 1
63+
if (step < 1) {
64+
step = 1;
65+
}
66+
5667
total_weight = 0.0;
5768

5869
// Compute the sample weights
@@ -65,17 +76,6 @@ LikelihoodFieldModel::sensorFunction(LaserData * data, pf_sample_set_t * set)
6576

6677
p = 1.0;
6778

68-
// Pre-compute a couple of things
69-
double z_hit_denom = 2 * self->sigma_hit_ * self->sigma_hit_;
70-
double z_rand_mult = 1.0 / data->range_max;
71-
72-
step = (data->range_count - 1) / (self->max_beams_ - 1);
73-
74-
// Step size must be at least 1
75-
if (step < 1) {
76-
step = 1;
77-
}
78-
7979
for (i = 0; i < data->range_count; i += step) {
8080
obs_range = data->ranges[i][0];
8181
obs_bearing = data->ranges[i][1];

nav2_behavior_tree/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -204,6 +204,9 @@ list(APPEND plugin_libs nav2_smoother_selector_bt_node)
204204
add_library(nav2_goal_checker_selector_bt_node SHARED plugins/action/goal_checker_selector_node.cpp)
205205
list(APPEND plugin_libs nav2_goal_checker_selector_bt_node)
206206

207+
add_library(nav2_progress_checker_selector_bt_node SHARED plugins/action/progress_checker_selector_node.cpp)
208+
list(APPEND plugin_libs nav2_progress_checker_selector_bt_node)
209+
207210
add_library(nav2_goal_updated_controller_bt_node SHARED plugins/decorator/goal_updated_controller.cpp)
208211
list(APPEND plugin_libs nav2_goal_updated_controller_bt_node)
209212

Lines changed: 96 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,96 @@
1+
// Copyright (c) 2024 Open Navigation LLC
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__PROGRESS_CHECKER_SELECTOR_NODE_HPP_
16+
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__PROGRESS_CHECKER_SELECTOR_NODE_HPP_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include "std_msgs/msg/string.hpp"
22+
23+
#include "behaviortree_cpp_v3/action_node.h"
24+
25+
#include "rclcpp/rclcpp.hpp"
26+
27+
namespace nav2_behavior_tree
28+
{
29+
30+
/**
31+
* @brief The ProgressCheckerSelector behavior is used to switch the progress checker
32+
* of the controller server. It subscribes to a topic "progress_checker_selector"
33+
* to get the decision about what progress_checker must be used. It is usually used before of
34+
* the FollowPath. The selected_progress_checker output port is passed to progress_checker_id
35+
* input port of the FollowPath
36+
*/
37+
class ProgressCheckerSelector : public BT::SyncActionNode
38+
{
39+
public:
40+
/**
41+
* @brief A constructor for nav2_behavior_tree::ProgressCheckerSelector
42+
*
43+
* @param xml_tag_name Name for the XML tag for this node
44+
* @param conf BT node configuration
45+
*/
46+
ProgressCheckerSelector(
47+
const std::string & xml_tag_name,
48+
const BT::NodeConfiguration & conf);
49+
50+
/**
51+
* @brief Creates list of BT ports
52+
* @return BT::PortsList Containing basic ports along with node-specific ports
53+
*/
54+
static BT::PortsList providedPorts()
55+
{
56+
return {
57+
BT::InputPort<std::string>(
58+
"default_progress_checker",
59+
"the default progress_checker to use if there is not any external topic message received."),
60+
61+
BT::InputPort<std::string>(
62+
"topic_name",
63+
"progress_checker_selector",
64+
"the input topic name to select the progress_checker"),
65+
66+
BT::OutputPort<std::string>(
67+
"selected_progress_checker",
68+
"Selected progress_checker by subscription")
69+
};
70+
}
71+
72+
private:
73+
/**
74+
* @brief Function to perform some user-defined operation on tick
75+
*/
76+
BT::NodeStatus tick() override;
77+
78+
/**
79+
* @brief callback function for the progress_checker_selector topic
80+
*
81+
* @param msg the message with the id of the progress_checker_selector
82+
*/
83+
void callbackProgressCheckerSelect(const std_msgs::msg::String::SharedPtr msg);
84+
85+
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr progress_checker_selector_sub_;
86+
87+
std::string last_selected_progress_checker_;
88+
89+
rclcpp::Node::SharedPtr node_;
90+
91+
std::string topic_name_;
92+
};
93+
94+
} // namespace nav2_behavior_tree
95+
96+
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__PROGRESS_CHECKER_SELECTOR_NODE_HPP_

nav2_behavior_tree/nav2_tree_nodes.xml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -181,6 +181,12 @@
181181
<output_port name="selected_goal_checker">Name of the selected goal checker received from the topic subcription</output_port>
182182
</Action>
183183

184+
<Action ID="ProgressCheckerSelector">
185+
<input_port name="topic_name">Name of the topic to receive progress checker selection commands</input_port>
186+
<input_port name="default_progress_checker">Default progress checker of the controller selector</input_port>
187+
<output_port name="selected_progress_checker">Name of the selected progress checker received from the topic subcription</output_port>
188+
</Action>
189+
184190
<Action ID="Spin">
185191
<input_port name="spin_dist">Spin distance</input_port>
186192
<input_port name="time_allowance">Allowed time for spinning</input_port>

nav2_behavior_tree/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_behavior_tree</name>
5-
<version>1.1.13</version>
5+
<version>1.1.14</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Carlos Orduno</maintainer>
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
// Copyright (c) 2024 Open Navigation LLC
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <string>
16+
#include <memory>
17+
18+
#include "std_msgs/msg/string.hpp"
19+
20+
#include "nav2_behavior_tree/plugins/action/progress_checker_selector_node.hpp"
21+
22+
#include "rclcpp/rclcpp.hpp"
23+
24+
namespace nav2_behavior_tree
25+
{
26+
27+
using std::placeholders::_1;
28+
29+
ProgressCheckerSelector::ProgressCheckerSelector(
30+
const std::string & name,
31+
const BT::NodeConfiguration & conf)
32+
: BT::SyncActionNode(name, conf)
33+
{
34+
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
35+
36+
getInput("topic_name", topic_name_);
37+
38+
rclcpp::QoS qos(rclcpp::KeepLast(1));
39+
qos.transient_local().reliable();
40+
41+
progress_checker_selector_sub_ = node_->create_subscription<std_msgs::msg::String>(
42+
topic_name_, qos, std::bind(&ProgressCheckerSelector::callbackProgressCheckerSelect, this, _1));
43+
}
44+
45+
BT::NodeStatus ProgressCheckerSelector::tick()
46+
{
47+
rclcpp::spin_some(node_);
48+
49+
// This behavior always use the last selected progress checker received from the topic input.
50+
// When no input is specified it uses the default goaprogressl checker.
51+
// If the default progress checker is not specified then we work in
52+
// "required progress checker mode": In this mode, the behavior returns failure if the progress
53+
// checker selection is not received from the topic input.
54+
if (last_selected_progress_checker_.empty()) {
55+
std::string default_progress_checker;
56+
getInput("default_progress_checker", default_progress_checker);
57+
if (default_progress_checker.empty()) {
58+
return BT::NodeStatus::FAILURE;
59+
} else {
60+
last_selected_progress_checker_ = default_progress_checker;
61+
}
62+
}
63+
64+
setOutput("selected_progress_checker", last_selected_progress_checker_);
65+
66+
return BT::NodeStatus::SUCCESS;
67+
}
68+
69+
void
70+
ProgressCheckerSelector::callbackProgressCheckerSelect(const std_msgs::msg::String::SharedPtr msg)
71+
{
72+
last_selected_progress_checker_ = msg->data;
73+
}
74+
75+
} // namespace nav2_behavior_tree
76+
77+
#include "behaviortree_cpp_v3/bt_factory.h"
78+
BT_REGISTER_NODES(factory)
79+
{
80+
factory.registerNodeType<nav2_behavior_tree::ProgressCheckerSelector>("ProgressCheckerSelector");
81+
}

nav2_behavior_tree/test/plugins/action/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -107,3 +107,7 @@ ament_target_dependencies(test_smoother_selector_node ${dependencies})
107107
ament_add_gtest(test_goal_checker_selector_node test_goal_checker_selector_node.cpp)
108108
target_link_libraries(test_goal_checker_selector_node nav2_goal_checker_selector_bt_node)
109109
ament_target_dependencies(test_goal_checker_selector_node ${dependencies})
110+
111+
ament_add_gtest(test_progress_checker_selector_node test_progress_checker_selector_node.cpp)
112+
target_link_libraries(test_progress_checker_selector_node nav2_progress_checker_selector_bt_node)
113+
ament_target_dependencies(test_progress_checker_selector_node ${dependencies})

0 commit comments

Comments
 (0)