Newer
Older
// Copyright (c) 2019 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <chrono>
#include <vector>
#include <string>
#include "nav2_core/exceptions.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_controller/progress_checker.hpp"
#include "nav2_controller/nav2_controller.hpp"
using namespace std::chrono_literals;
namespace nav2_controller
: LifecycleNode("controller_server", "", true),
lp_loader_("nav2_core", "nav2_core::LocalPlanner")

Steven Macenski
committed
RCLCPP_INFO(get_logger(), "Creating controller server");
declare_parameter("controller_frequency", 20.0);
std::vector<std::string> default_property, default_type;

Steven Macenski
committed
default_type.push_back("dwb_core::DWBLocalPlanner");
default_property.push_back("FollowPath");
controller_properties_ = declare_parameter("controller_plugin_properties",
default_property);

Steven Macenski
committed
controller_types_ = declare_parameter("controller_plugin_types", default_type);
// The costmap node is used in the implementation of the local planner
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
"local_costmap", std::string{get_namespace()}, "local_costmap");
// Launch a thread to run the costmap node
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
RCLCPP_INFO(get_logger(), "Destroying");
}
ControllerServer::on_configure(const rclcpp_lifecycle::State & state)

Steven Macenski
committed
RCLCPP_INFO(get_logger(), "Configuring controller interface");
costmap_ros_->on_configure(state);
auto node = shared_from_this();

Carlos A. Orduno
committed
progress_checker_ = std::make_unique<ProgressChecker>(rclcpp_node_);
if (controller_types_.size() != controller_properties_.size()) {

Steven Macenski
committed
RCLCPP_FATAL(get_logger(), "Size of controller names (%i) and "
"controller types (%i) are not the same!",
static_cast<int>(controller_types_.size()),
static_cast<int>(controller_properties_.size()));

Steven Macenski
committed
exit(-1);
}
for (uint i = 0; i != controller_types_.size(); i++) {

Steven Macenski
committed
try {
nav2_core::LocalPlanner::Ptr controller =
lp_loader_.createUniqueInstance(controller_types_[i]);
RCLCPP_INFO(get_logger(), "Created controller : %s of type %s",
controller_properties_[i].c_str(), controller_types_[i].c_str());
controller->configure(node, controller_properties_[i],

Steven Macenski
committed
costmap_ros_->getTfBuffer(), costmap_ros_);
controllers_.insert({controller_properties_[i], controller});

Steven Macenski
committed
} catch (const pluginlib::PluginlibException & ex) {
RCLCPP_FATAL(get_logger(), "Failed to create controller. Exception: %s", ex.what());
}
}
for (uint i = 0; i != controller_properties_.size(); i++) {
controller_properties_concat_ += controller_properties_[i] + std::string(" ");
get_parameter("controller_frequency", controller_frequency_);
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);
// Create the action server that we implement with our followPath method
action_server_ = std::make_unique<ActionServer>(rclcpp_node_, "FollowPath",

Steven Macenski
committed
std::bind(&ControllerServer::computeControl, this));
return nav2_util::CallbackReturn::SUCCESS;
ControllerServer::on_activate(const rclcpp_lifecycle::State & state)
{
RCLCPP_INFO(get_logger(), "Activating");
costmap_ros_->on_activate(state);

Steven Macenski
committed
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->activate();
}
return nav2_util::CallbackReturn::SUCCESS;
ControllerServer::on_deactivate(const rclcpp_lifecycle::State & state)
{
RCLCPP_INFO(get_logger(), "Deactivating");

Steven Macenski
committed
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->deactivate();
}
costmap_ros_->on_deactivate(state);
return nav2_util::CallbackReturn::SUCCESS;
ControllerServer::on_cleanup(const rclcpp_lifecycle::State & state)
{
RCLCPP_INFO(get_logger(), "Cleaning up");
// Cleanup the helper classes

Steven Macenski
committed
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->cleanup();
}
costmap_ros_->on_cleanup(state);
// Release any allocated resources

Steven Macenski
committed
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second.reset();
}
odom_sub_.reset();
return nav2_util::CallbackReturn::SUCCESS;
ControllerServer::on_error(const rclcpp_lifecycle::State &)

Michael Jeronimo
committed
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
ControllerServer::on_shutdown(const rclcpp_lifecycle::State &)
RCLCPP_INFO(get_logger(), "Shutting down");
return nav2_util::CallbackReturn::SUCCESS;

Steven Macenski
committed
void ControllerServer::computeControl()

Steven Macenski
committed
RCLCPP_INFO(get_logger(), "Received a goal, begin computing control effort.");
std::string c_name = action_server_->get_current_goal()->controller_property;

Steven Macenski
committed
if (controllers_.find(c_name) == controllers_.end()) {
if (controllers_.size() == 1 && c_name.empty()) {

Steven Macenski
committed
RCLCPP_WARN(get_logger(), "No controller was specified in action call."
" Server will use only plugin loaded %s. "
"This warning will appear once.", controller_properties_concat_.c_str());

Steven Macenski
committed
single_controller_warning_given_ = true;
}
current_controller_ = controllers_.begin()->first;
} else {
RCLCPP_ERROR(get_logger(), "FollowPath called with controller name %s, "

Steven Macenski
committed
"which does not exist. Available controllers are %s.",
c_name.c_str(), controller_properties_concat_.c_str());
action_server_->terminate_goals();
return;

Steven Macenski
committed
}
} else {
current_controller_ = c_name;
}
setPlannerPath(action_server_->get_current_goal()->path);
progress_checker_->reset();
rclcpp::Rate loop_rate(controller_frequency_);
if (action_server_ == nullptr) {
RCLCPP_DEBUG(get_logger(), "Action server unavailable. Stopping.");
return;
}
if (!action_server_->is_server_active()) {
RCLCPP_DEBUG(get_logger(), "Action server is inactive. Stopping.");
return;
}

Carlos A. Orduno
committed
if (action_server_->is_cancel_requested()) {
RCLCPP_INFO(get_logger(), "Goal was canceled. Stopping the robot.");
action_server_->terminate_goals();

Carlos A. Orduno
committed
return;
}
updateGlobalPath();
computeAndPublishVelocity();
if (isGoalReached()) {
RCLCPP_INFO(get_logger(), "Reached the goal!");
break;
if (!loop_rate.sleep()) {
RCLCPP_WARN(get_logger(), "Control loop missed its desired rate of %.4fHz",
controller_frequency_);
}
} catch (nav2_core::PlannerException & e) {
RCLCPP_ERROR(this->get_logger(), e.what());
publishZeroVelocity();
action_server_->terminate_goals();
RCLCPP_DEBUG(get_logger(), "DWB succeeded, setting result");

Carlos A. Orduno
committed
publishZeroVelocity();

Carlos A. Orduno
committed

Steven Macenski
committed
// TODO(orduno) #861 Handle a pending preemption and set controller name

Carlos A. Orduno
committed
action_server_->succeeded_current();
}
void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)

Carlos A. Orduno
committed
{

Steven Macenski
committed
RCLCPP_DEBUG(get_logger(),
"Providing path to the controller %s", current_controller_);
controllers_[current_controller_]->setPlan(path);

Carlos A. Orduno
committed
auto end_pose = *(path.poses.end() - 1);
RCLCPP_DEBUG(get_logger(), "Path end point is (%.2f, %.2f)",
end_pose.pose.position.x, end_pose.pose.position.y);

Carlos A. Orduno
committed
}
void ControllerServer::computeAndPublishVelocity()

Carlos A. Orduno
committed
{
geometry_msgs::msg::PoseStamped pose;

Carlos A. Orduno
committed
if (!getRobotPose(pose)) {
throw nav2_core::PlannerException("Failed to obtain robot pose");

Carlos A. Orduno
committed
}
progress_checker_->check(pose);

Carlos A. Orduno
committed

Steven Macenski
committed
auto cmd_vel_2d =
controllers_[current_controller_]->computeVelocityCommands(pose,
nav_2d_utils::twist2Dto3D(odom_sub_->getTwist()));

Carlos A. Orduno
committed
RCLCPP_DEBUG(get_logger(), "Publishing velocity at time %.2f", now().seconds());
publishVelocity(cmd_vel_2d);
}

Carlos A. Orduno
committed
{
if (action_server_->is_preempt_requested()) {

Carlos A. Orduno
committed
RCLCPP_INFO(get_logger(), "Preempting the goal. Passing the new path to the planner.");
setPlannerPath(action_server_->accept_pending_goal()->path);
}
void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped & velocity)
auto cmd_vel = velocity.twist;
geometry_msgs::msg::TwistStamped velocity;
velocity.twist.angular.x = 0;
velocity.twist.angular.y = 0;
velocity.twist.angular.z = 0;
velocity.twist.linear.x = 0;
velocity.twist.linear.y = 0;
velocity.twist.linear.z = 0;
publishVelocity(velocity);
}
geometry_msgs::msg::PoseStamped pose;
if (!getRobotPose(pose)) {

Carlos A. Orduno
committed
return false;
}
geometry_msgs::msg::Twist velocity = nav_2d_utils::twist2Dto3D(odom_sub_->getTwist());

Steven Macenski
committed
return controllers_[current_controller_]->isGoalReached(pose, velocity);
bool ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped & pose)
{
geometry_msgs::msg::PoseStamped current_pose;
if (!costmap_ros_->getRobotPose(current_pose)) {
RCLCPP_ERROR(this->get_logger(), "Could not get robot pose");
return false;
}
pose = current_pose;
} // namespace nav2_controller