Skip to content

Commit 1a96da4

Browse files
tgreierCarl Delsey
andauthored
Declare odometry subscriber topic and goal_reached_tol. (#1770)
* Declare progress checker parameters (#1526) * Declare progress checker parameters * Use declare_if_not_declared function This should allow the node to be brought down and back up using the lifecycle manager. * Declared parameters before get. * Fixed column width. * Removed changes not related to parameter declare. Co-authored-by: Carl Delsey <carl.r.delsey@intel.com>
1 parent 9615c2e commit 1a96da4

File tree

3 files changed

+10
-0
lines changed

3 files changed

+10
-0
lines changed

nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "nav2_util/robot_utils.hpp"
2424
#include "geometry_msgs/msg/pose_stamped.hpp"
2525
#include "tf2_ros/buffer.h"
26+
#include "nav2_util/node_utils.hpp"
2627

2728
namespace nav2_behavior_tree
2829
{
@@ -59,6 +60,8 @@ class GoalReachedCondition : public BT::ConditionNode
5960
void initialize()
6061
{
6162
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
63+
nav2_util::declare_parameter_if_not_declared(node_, "goal_reached_tol",
64+
rclcpp::ParameterValue(0.25));
6265
node_->get_parameter_or<double>("goal_reached_tol", goal_reached_tol_, 0.25);
6366
tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
6467

nav2_controller/src/progress_checker.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "nav_2d_utils/conversions.hpp"
1919
#include "geometry_msgs/msg/pose_stamped.hpp"
2020
#include "geometry_msgs/msg/pose2_d.hpp"
21+
#include "nav2_util/node_utils.hpp"
2122

2223
namespace nav2_controller
2324
{
@@ -26,6 +27,10 @@ static double pose_distance(const geometry_msgs::msg::Pose2D &, const geometry_m
2627
ProgressChecker::ProgressChecker(const rclcpp::Node::SharedPtr & node)
2728
: nh_(node)
2829
{
30+
nav2_util::declare_parameter_if_not_declared(
31+
nh_, "required_movement_radius", rclcpp::ParameterValue(0.5));
32+
nav2_util::declare_parameter_if_not_declared(
33+
nh_, "movement_time_allowance", rclcpp::ParameterValue(10.0));
2934
// Scale is set to 0 by default, so if it was not set otherwise, set to 0
3035
nh_->get_parameter_or("required_movement_radius", radius_, 0.5);
3136
double time_allowance_param;

nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,8 @@ class OdomSubscriber
6666
std::string default_topic = "odom")
6767
{
6868
std::string odom_topic;
69+
nav2_util::declare_parameter_if_not_declared(nh, "odom_topic",
70+
rclcpp::ParameterValue(default_topic));
6971
nh->get_parameter_or("odom_topic", odom_topic, default_topic);
7072
odom_sub_ =
7173
nh->create_subscription<nav_msgs::msg::Odometry>(odom_topic,

0 commit comments

Comments
 (0)