Skip to content
Snippets Groups Projects
Commit 65eb602e authored by Yathartha Tuladhar's avatar Yathartha Tuladhar Committed by Matt Hansen
Browse files

Renaming, cleanup, and reintroduced TF buffer

parent 176dc7db
No related branches found
No related tags found
No related merge requests found
......@@ -114,7 +114,7 @@ def generate_launch_description():
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
{'node_names': ['nav2_controller',
{'node_names': ['controller_server',
'navfn_planner',
'bt_navigator']}]),
......
......@@ -51,7 +51,7 @@ bt_navigator:
use_sim_time: True
bt_xml_filename: "bt_navigator.xml"
nav2_controller:
controller_server:
ros__parameters:
use_sim_time: True
debug_trajectory_details: True
......
......@@ -19,7 +19,7 @@ include_directories(
include
)
set(executable_name nav2_controller)
set(executable_name controller_server)
add_executable(${executable_name}
src/main.cpp
......
......@@ -28,10 +28,10 @@ namespace nav2_controller
{
Nav2Controller::Nav2Controller()
: LifecycleNode("nav2_controller", "", true),
: LifecycleNode("controller_server", "", true),
lp_loader_("nav2_core", "nav2_core::LocalPlanner")
{
RCLCPP_INFO(get_logger(), "Creating local planner");
RCLCPP_INFO(get_logger(), "Creating controller");
declare_parameter("controller_frequency", 20.0);
declare_parameter("local_controller_plugin", "dwb_core::DWBLocalPlanner");
......@@ -64,7 +64,7 @@ Nav2Controller::on_configure(const rclcpp_lifecycle::State & state)
{
std::string local_planner_name;
RCLCPP_INFO(get_logger(), "Configuring local planner interface");
RCLCPP_INFO(get_logger(), "Configuring local controller interface");
costmap_ros_->on_configure(state);
......@@ -76,8 +76,8 @@ Nav2Controller::on_configure(const rclcpp_lifecycle::State & state)
std::string local_controller_plugin;
get_parameter("local_controller_plugin", local_controller_plugin);
local_planner_ = lp_loader_.createUniqueInstance(local_controller_plugin);
RCLCPP_INFO(get_logger(), "Created local_planner");
local_planner_->configure(node, costmap_ros_);
RCLCPP_INFO(get_logger(), "Created local controller");
local_planner_->configure(node, costmap_ros_->getTfBuffer(), costmap_ros_);
} catch (const pluginlib::PluginlibException & ex) {
RCLCPP_FATAL(get_logger(), "Failed to create local planner. Exception: %s", ex.what());
}
......
/*
* Software License Agreement (BSD License)
* Software License Agreement (BSD License)
*
* Copyright (c) 2017, Locus Robotics
......
......@@ -73,6 +73,7 @@ public:
*/
virtual void configure(
const rclcpp_lifecycle::LifecycleNode::SharedPtr &,
const std::shared_ptr<tf2_ros::Buffer> &,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> &) = 0;
/**
......
......@@ -68,6 +68,7 @@ public:
void configure(
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros) override;
virtual ~DWBLocalPlanner() {}
......
......@@ -66,11 +66,12 @@ DWBLocalPlanner::DWBLocalPlanner()
void DWBLocalPlanner::configure(
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros)
{
node_ = node;
costmap_ros_ = costmap_ros;
tf_ = costmap_ros_->getTfBuffer();
tf_ = tf;
declare_parameter_if_not_declared(node_, "critics");
declare_parameter_if_not_declared(node_, "prune_plan", rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, "prune_distance", rclcpp::ParameterValue(1.0));
......
......@@ -77,7 +77,7 @@ def generate_launch_description():
launch_ros.actions.Node(
package='nav2_controller',
node_executable='nav2_controller',
node_executable='controller_server',
output='screen',
parameters=[params_file]),
......@@ -109,7 +109,7 @@ def generate_launch_description():
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'node_names': ['map_server', 'amcl',
'nav2_controller', 'planner_server', 'bt_navigator']},
'controller_server', 'planner_server', 'bt_navigator']},
{'autostart': True}]),
])
......
......@@ -83,7 +83,7 @@ def generate_launch_description():
cmd=[
os.path.join(
get_package_prefix('nav2_controller'),
'lib/nav2_controller/nav2_controller'),
'lib/nav2_controller/controller_server'),
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment