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
31 changes: 8 additions & 23 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,19 +38,6 @@ BtNavigator::BtNavigator(rclcpp::NodeOptions options)
class_loader_("nav2_core", "nav2_core::NavigatorBase")
{
RCLCPP_INFO(get_logger(), "Creating");

declare_parameter_if_not_declared(
this, "plugin_lib_names", rclcpp::ParameterValue(std::vector<std::string>{}));
declare_parameter_if_not_declared(
this, "transform_tolerance", rclcpp::ParameterValue(0.1));
declare_parameter_if_not_declared(
this, "global_frame", rclcpp::ParameterValue(std::string("map")));
declare_parameter_if_not_declared(
this, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
declare_parameter_if_not_declared(
this, "odom_topic", rclcpp::ParameterValue(std::string("odom")));
declare_parameter_if_not_declared(
this, "filter_duration", rclcpp::ParameterValue(0.3));
}

BtNavigator::~BtNavigator()
Expand All @@ -69,17 +56,18 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
tf_->setUsingDedicatedThread(true);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, false);

global_frame_ = get_parameter("global_frame").as_string();
robot_frame_ = get_parameter("robot_base_frame").as_string();
transform_tolerance_ = get_parameter("transform_tolerance").as_double();
odom_topic_ = get_parameter("odom_topic").as_string();
filter_duration_ = get_parameter("filter_duration").as_double();
global_frame_ = this->declare_or_get_parameter("global_frame", std::string("map"));
robot_frame_ = this->declare_or_get_parameter("robot_base_frame", std::string("base_link"));
transform_tolerance_ = this->declare_or_get_parameter("transform_tolerance", 0.1);
odom_topic_ = this->declare_or_get_parameter("odom_topic", std::string("odom"));
filter_duration_ = this->declare_or_get_parameter("filter_duration", 0.3);

// Libraries to pull plugins (BT Nodes) from
std::vector<std::string> plugin_lib_names;
plugin_lib_names = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS, ';');

auto user_defined_plugins = get_parameter("plugin_lib_names").as_string_array();
auto user_defined_plugins =
this->declare_or_get_parameter("plugin_lib_names", std::vector<std::string>{});
// append user_defined_plugins to plugin_lib_names
plugin_lib_names.insert(
plugin_lib_names.end(), user_defined_plugins.begin(),
Expand All @@ -106,10 +94,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
};

std::vector<std::string> navigator_ids;
declare_parameter_if_not_declared(
node, "navigators",
rclcpp::ParameterValue(default_navigator_ids));
get_parameter("navigators", navigator_ids);
navigator_ids = this->declare_or_get_parameter("navigators", default_navigator_ids);
if (navigator_ids == default_navigator_ids) {
for (size_t i = 0; i < default_navigator_ids.size(); ++i) {
declare_parameter_if_not_declared(
Comment thread
elsayedelsheikh marked this conversation as resolved.
Expand Down
55 changes: 18 additions & 37 deletions nav2_bt_navigator/src/navigators/navigate_through_poses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,39 +30,25 @@ NavigateThroughPosesNavigator::configure(
start_time_ = rclcpp::Time(0);
auto node = parent_node.lock();

if (!node->has_parameter("goals_blackboard_id")) {
node->declare_parameter("goals_blackboard_id", std::string("goals"));
}

goals_blackboard_id_ = node->get_parameter("goals_blackboard_id").as_string();

if (!node->has_parameter("path_blackboard_id")) {
node->declare_parameter("path_blackboard_id", std::string("path"));
}

path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();

if (!node->has_parameter("waypoint_statuses_blackboard_id")) {
node->declare_parameter("waypoint_statuses_blackboard_id", std::string("waypoint_statuses"));
}

goals_blackboard_id_ =
node->declare_or_get_parameter("goals_blackboard_id", std::string("goals"));
path_blackboard_id_ =
node->declare_or_get_parameter("path_blackboard_id", std::string("path"));
waypoint_statuses_blackboard_id_ =
node->get_parameter("waypoint_statuses_blackboard_id").as_string();
node->declare_or_get_parameter("waypoint_statuses_blackboard_id",
std::string("waypoint_statuses"));

// Odometry smoother object for getting current speed
odom_smoother_ = odom_smoother;

if (!node->has_parameter(getName() + ".enable_groot_monitoring")) {
node->declare_parameter(getName() + ".enable_groot_monitoring", false);
}

if (!node->has_parameter(getName() + ".groot_server_port")) {
node->declare_parameter(getName() + ".groot_server_port", 1669);
}
bool enable_groot_monitoring =
node->declare_or_get_parameter(getName() + ".enable_groot_monitoring", false);
int groot_server_port =
node->declare_or_get_parameter(getName() + ".groot_server_port", 1669);

bt_action_server_->setGrootMonitoring(
node->get_parameter(getName() + ".enable_groot_monitoring").as_bool(),
node->get_parameter(getName() + ".groot_server_port").as_int());
enable_groot_monitoring,
groot_server_port);

return true;
}
Expand All @@ -71,19 +57,14 @@ std::string
NavigateThroughPosesNavigator::getDefaultBTFilepath(
nav2::LifecycleNode::WeakPtr parent_node)
{
std::string default_bt_xml_filename;
auto node = parent_node.lock();
std::string pkg_share_dir =
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");

if (!node->has_parameter("default_nav_through_poses_bt_xml")) {
std::string pkg_share_dir =
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
node->declare_parameter<std::string>(
"default_nav_through_poses_bt_xml",
pkg_share_dir +
"/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
}

node->get_parameter("default_nav_through_poses_bt_xml", default_bt_xml_filename);
auto default_bt_xml_filename = node->declare_or_get_parameter(
"default_nav_through_poses_bt_xml",
pkg_share_dir +
"/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");

return default_bt_xml_filename;
}
Expand Down
47 changes: 16 additions & 31 deletions nav2_bt_navigator/src/navigators/navigate_to_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,10 @@ NavigateToPoseNavigator::configure(
start_time_ = rclcpp::Time(0);
auto node = parent_node.lock();

if (!node->has_parameter("goal_blackboard_id")) {
node->declare_parameter("goal_blackboard_id", std::string("goal"));
}

goal_blackboard_id_ = node->get_parameter("goal_blackboard_id").as_string();

if (!node->has_parameter("path_blackboard_id")) {
node->declare_parameter("path_blackboard_id", std::string("path"));
}

path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();
goal_blackboard_id_ =
node->declare_or_get_parameter("goal_blackboard_id", std::string("goal"));
path_blackboard_id_ =
node->declare_or_get_parameter("path_blackboard_id", std::string("path"));

// Odometry smoother object for getting current speed
odom_smoother_ = odom_smoother;
Expand All @@ -50,17 +43,14 @@ NavigateToPoseNavigator::configure(
"goal_pose",
std::bind(&NavigateToPoseNavigator::onGoalPoseReceived, this, std::placeholders::_1));

if (!node->has_parameter(getName() + ".enable_groot_monitoring")) {
node->declare_parameter(getName() + ".enable_groot_monitoring", false);
}

if (!node->has_parameter(getName() + ".groot_server_port")) {
node->declare_parameter(getName() + ".groot_server_port", 1667);
}
bool enable_groot_monitoring =
node->declare_or_get_parameter(getName() + ".enable_groot_monitoring", false);
int groot_server_port =
node->declare_or_get_parameter(getName() + ".groot_server_port", 1669);

bt_action_server_->setGrootMonitoring(
node->get_parameter(getName() + ".enable_groot_monitoring").as_bool(),
node->get_parameter(getName() + ".groot_server_port").as_int());
enable_groot_monitoring,
groot_server_port);

return true;
}
Expand All @@ -69,19 +59,14 @@ std::string
NavigateToPoseNavigator::getDefaultBTFilepath(
nav2::LifecycleNode::WeakPtr parent_node)
{
std::string default_bt_xml_filename;
auto node = parent_node.lock();
std::string pkg_share_dir =
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");

if (!node->has_parameter("default_nav_to_pose_bt_xml")) {
std::string pkg_share_dir =
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
node->declare_parameter<std::string>(
"default_nav_to_pose_bt_xml",
pkg_share_dir +
"/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");
}

node->get_parameter("default_nav_to_pose_bt_xml", default_bt_xml_filename);
auto default_bt_xml_filename = node->declare_or_get_parameter(
"default_nav_to_pose_bt_xml",
pkg_share_dir +
"/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");

return default_bt_xml_filename;
}
Expand Down
Loading