Skip to content

Commit f405c85

Browse files
SteveMacenskidoisygErikOrjehagEkanshhTony Najjar
authored
Galactic sync 6 (#2940)
* fix invert logic (#2772) * Bugfix tf lookup of goal pose in nav2_controller (#2780) Signed-off-by: Erik Örjehag <[email protected]> * Feature to call controller action server to follow path (#2789) * Added call to controller action server with a path to follow ++ Added a new function in robot_navigator,py ++ Added a launch script to test function ++ Updated setup.py to include demo_follow_path.py * Code refactoring * Code refactoring * Code refactoring for consistency * Updated README.md * Resolved executable conflict in setup.py for example_follow_path.py * Code refactoring with ament_flake8 * Add recoveries to simple commander (#2792) * fix Typo * add recoveries * add docs * added demo using backup and spin * rename isNavigationComplete to isTaskComplete * rename cancelNav to cancelTask * add prints * fix premature exit * rename NavResult to TaskResult * fix readme order * fix import order * renaming * renaming * added planner_id (#2806) * Fixing the issue #2781: raytraceLine with same start and end point (#2784) * Fixing the issue #2781: raytraceLine with same start and end point no longer causes segmentation fault * Some whitespace modifications to make the code pass release_test * Add testcase for raytraceLine the same point Co-authored-by: Alexey Merzlyakov <[email protected]> * Add optional node names to wait (#2811) * add option to specify navigator and localizer to wait for * add docs for waituntilNav2Active * wait for pose only for amcl * revert order * remove resizing on update message callback (#2818) * restrict test_msgs to test_dependency (#2827) Signed-off-by: Alberto Soragna <[email protected]> * remove unused odometry smoother in bt navigator (#2829) * remove unused odometry smoother in bt navigator Signed-off-by: Alberto Soragna <[email protected]> * reorganize bt navigator to shared odom_smoother object with servers Signed-off-by: Alberto Soragna <[email protected]> * Add all action options (#2834) * added options * update docs * Adding theta* to the main packages list * Fix: bt_navigator crashes on lc transitions (#2848) * fix empty address access on halt all actions * fix unsafe declaration of parameters * restore odom smoother * fix styling issues * add missing semicolumn * fix-collision checker must capture lethal before unknow (#2854) * Removing old unused function and comment (#2863) * Better Costmap Error Message (#2884) * Better Costmap Error Message * PR Feedback * add getRobotRadius() in costmap_2d_ros (#2896) * Add clock time to costmaps (#2899) * update goal checker plugin to plugins (#2909) * Allow usage of std::string in searchAndGetParam() (#2918) * Allow usage of std::string in searchAndGetParam() Removed also old TODO related to legacy ROS API * Fix * Clean up action clients in nav2_simple_commander (#2924) * Clean up action clients in nav2_simple_commander * Add camelCase version * Add docs * Added mutex to prevent SEGFAULT on map change in AMCL (#2933) * Added mutex to prevent SEGFAULT on map change * Removing redundant mutex Co-authored-by: Antonio Marangi <[email protected]> Co-authored-by: G.Doisy <[email protected]> Co-authored-by: Erik Örjehag <[email protected]> Co-authored-by: Ekansh Sharma <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Joshua Wallace <[email protected]> Co-authored-by: janx8r <[email protected]> Co-authored-by: Alexey Merzlyakov <[email protected]> Co-authored-by: Andrii Maistruk <[email protected]> Co-authored-by: Alberto Soragna <[email protected]> Co-authored-by: Erwin Lejeune <[email protected]> Co-authored-by: Hossein Sheikhi Darani <[email protected]> Co-authored-by: David V. Lu!! <[email protected]> Co-authored-by: Carlos Andrés Álvarez Restrepo <[email protected]> Co-authored-by: Patrick Roncagliolo <[email protected]> Co-authored-by: M. Mostafa Farzan <[email protected]> Co-authored-by: mrmara <[email protected]> Co-authored-by: Antonio Marangi <[email protected]>
1 parent 04031ba commit f405c85

File tree

49 files changed

+702
-175
lines changed

Some content is hidden

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

49 files changed

+702
-175
lines changed

nav2_amcl/include/nav2_amcl/amcl_node.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ class AmclNode : public nav2_util::LifecycleNode
130130
bool first_map_only_{true};
131131
std::atomic<bool> first_map_received_{false};
132132
amcl_hyp_t * initial_pose_hyp_;
133-
std::recursive_mutex configuration_mutex_;
133+
std::recursive_mutex mutex_;
134134
rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::ConstSharedPtr map_sub_;
135135
#if NEW_UNIFORM_SAMPLING
136136
static std::vector<std::pair<int, int>> free_space_indices;
@@ -238,7 +238,6 @@ class AmclNode : public nav2_util::LifecycleNode
238238
*/
239239
static pf_vector_t uniformPoseGenerator(void * arg);
240240
pf_t * pf_{nullptr};
241-
std::mutex pf_mutex_;
242241
bool pf_init_;
243242
pf_vector_t pf_odom_pose_;
244243
int resample_count_{0};

nav2_amcl/src/amcl_node.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -504,7 +504,7 @@ AmclNode::globalLocalizationCallback(
504504
const std::shared_ptr<std_srvs::srv::Empty::Request>/*req*/,
505505
std::shared_ptr<std_srvs::srv::Empty::Response>/*res*/)
506506
{
507-
std::lock_guard<std::mutex> lock(pf_mutex_);
507+
std::lock_guard<std::recursive_mutex> cfl(mutex_);
508508

509509
RCLCPP_INFO(get_logger(), "Initializing with uniform distribution");
510510

@@ -530,7 +530,7 @@ AmclNode::nomotionUpdateCallback(
530530
void
531531
AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
532532
{
533-
std::lock_guard<std::mutex> lock(pf_mutex_);
533+
std::lock_guard<std::recursive_mutex> cfl(mutex_);
534534

535535
RCLCPP_INFO(get_logger(), "initialPoseReceived");
536536

@@ -565,6 +565,7 @@ AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::Sha
565565
void
566566
AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
567567
{
568+
std::lock_guard<std::recursive_mutex> cfl(mutex_);
568569
// In case the client sent us a pose estimate in the past, integrate the
569570
// intervening odometric change.
570571
geometry_msgs::msg::TransformStamped tx_odom;
@@ -629,7 +630,7 @@ AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
629630
void
630631
AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
631632
{
632-
std::lock_guard<std::mutex> lock(pf_mutex_);
633+
std::lock_guard<std::recursive_mutex> cfl(mutex_);
633634

634635
// Since the sensor data is continually being published by the simulator or robot,
635636
// we don't want our callbacks to fire until we're in the active state
@@ -1166,7 +1167,7 @@ AmclNode::mapReceived(const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
11661167
void
11671168
AmclNode::handleMapMessage(const nav_msgs::msg::OccupancyGrid & msg)
11681169
{
1169-
std::lock_guard<std::recursive_mutex> cfl(configuration_mutex_);
1170+
std::lock_guard<std::recursive_mutex> cfl(mutex_);
11701171

11711172
RCLCPP_INFO(
11721173
get_logger(), "Received a %d X %d map @ %.3f m/pix",

nav2_behavior_tree/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@
5151
<test_depend>ament_lint_common</test_depend>
5252
<test_depend>ament_lint_auto</test_depend>
5353
<test_depend>ament_cmake_gtest</test_depend>
54+
<test_depend>test_msgs</test_depend>
5455

5556
<export>
5657
<build_type>ament_cmake</build_type>

nav2_behavior_tree/src/behavior_tree_engine.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -108,6 +108,10 @@ BehaviorTreeEngine::resetGrootMonitor()
108108
void
109109
BehaviorTreeEngine::haltAllActions(BT::TreeNode * root_node)
110110
{
111+
if (!root_node) {
112+
return;
113+
}
114+
111115
// this halt signal should propagate through the entire tree.
112116
root_node->halt();
113117

nav2_behavior_tree/test/plugins/action/CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
1+
find_package(test_msgs REQUIRED)
2+
13
ament_add_gtest(test_bt_action_node test_bt_action_node.cpp)
2-
ament_target_dependencies(test_bt_action_node ${dependencies})
4+
ament_target_dependencies(test_bt_action_node ${dependencies} test_msgs)
35

46
ament_add_gtest(test_action_spin_action test_spin_action.cpp)
57
target_link_libraries(test_action_spin_action nav2_spin_action_bt_node)

nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ controller_server:
108108
min_y_velocity_threshold: 0.5
109109
min_theta_velocity_threshold: 0.001
110110
progress_checker_plugin: "progress_checker"
111-
goal_checker_plugin: "goal_checker"
111+
goal_checker_plugins: "goal_checker"
112112
controller_plugins: ["FollowPath"]
113113

114114
# Progress checker parameters

nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ controller_server:
108108
min_y_velocity_threshold: 0.5
109109
min_theta_velocity_threshold: 0.001
110110
progress_checker_plugin: "progress_checker"
111-
goal_checker_plugin: "goal_checker"
111+
goal_checker_plugins: "goal_checker"
112112
controller_plugins: ["FollowPath"]
113113

114114
# Progress checker parameters

nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ class BtNavigator : public nav2_util::LifecycleNode
8989
nav2_bt_navigator::NavigatorMuxer plugin_muxer_;
9090

9191
// Odometry smoother object
92-
std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
92+
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
9393

9494
// Metrics for feedback
9595
std::string robot_frame_;

nav2_bt_navigator/include/nav2_bt_navigator/navigator.hpp

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -135,13 +135,15 @@ class Navigator
135135
* @param feedback_utils Some utilities useful for navigators to have
136136
* @param plugin_muxer The muxing object to ensure only one navigator
137137
* can be active at a time
138+
* @param odom_smoother Object to get current smoothed robot's speed
138139
* @return bool If successful
139140
*/
140141
bool on_configure(
141142
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
142143
const std::vector<std::string> & plugin_lib_names,
143144
const FeedbackUtils & feedback_utils,
144-
nav2_bt_navigator::NavigatorMuxer * plugin_muxer)
145+
nav2_bt_navigator::NavigatorMuxer * plugin_muxer,
146+
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
145147
{
146148
auto node = parent_node.lock();
147149
logger_ = node->get_logger();
@@ -173,7 +175,7 @@ class Navigator
173175
blackboard->set<bool>("initial_pose_received", false); // NOLINT
174176
blackboard->set<int>("number_recoveries", 0); // NOLINT
175177

176-
return configure(parent_node) && ok;
178+
return configure(parent_node, odom_smoother) && ok;
177179
}
178180

179181
/**
@@ -284,7 +286,12 @@ class Navigator
284286
/**
285287
* @param Method to configure resources.
286288
*/
287-
virtual bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr /*node*/) {return true;}
289+
virtual bool configure(
290+
rclcpp_lifecycle::LifecycleNode::WeakPtr /*node*/
291+
std::shared_ptr<nav2_util::OdomSmoother> /*odom_smoother*/)
292+
{
293+
return true;
294+
}
288295

289296
/**
290297
* @brief Method to cleanup resources.

nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -51,9 +51,11 @@ class NavigateThroughPosesNavigator
5151
/**
5252
* @brief A configure state transition to configure navigator's state
5353
* @param node Weakptr to the lifecycle node
54+
* @param odom_smoother Object to get current smoothed robot's speed
5455
*/
5556
bool configure(
56-
rclcpp_lifecycle::LifecycleNode::WeakPtr node) override;
57+
rclcpp_lifecycle::LifecycleNode::WeakPtr node,
58+
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) override;
5759

5860
/**
5961
* @brief Get action name for this navigator
@@ -106,7 +108,7 @@ class NavigateThroughPosesNavigator
106108
std::string path_blackboard_id_;
107109

108110
// Odometry smoother object
109-
std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
111+
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
110112
};
111113

112114
} // namespace nav2_bt_navigator

0 commit comments

Comments
 (0)