Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added use of declare_parameter_if_not_declared. #1765

Merged
merged 4 commits into from
May 27, 2020
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
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "nav2_util/robot_utils.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "tf2_ros/buffer.h"
#include "nav2_util/node_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down Expand Up @@ -64,6 +65,10 @@ class GoalReachedCondition : public BT::ConditionNode
void initialize()
{
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");

nav2_util::declare_parameter_if_not_declared(
node_, "goal_reached_tol",
rclcpp::ParameterValue(0.25));
node_->get_parameter_or<double>("goal_reached_tol", goal_reached_tol_, 0.25);
tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,9 @@ class OdomSubscriber
nav2_util::LifecycleNode::SharedPtr nh,
std::string default_topic = "odom")
{
nav2_util::declare_parameter_if_not_declared(
nh, "odom_topic", rclcpp::ParameterValue(default_topic));

std::string odom_topic;
nh->get_parameter_or("odom_topic", odom_topic, default_topic);
odom_sub_ =
Expand Down