Program Listing for File controller.hpp
↰ Return to documentation for file (include/nav2_mppi_controller/controller.hpp
)
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
//
// 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.
#ifndef NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
#define NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
#include <string>
#include <memory>
#include "nav2_mppi_controller/tools/path_handler.hpp"
#include "nav2_mppi_controller/optimizer.hpp"
#include "nav2_mppi_controller/tools/trajectory_visualizer.hpp"
#include "nav2_mppi_controller/models/constraints.hpp"
#include "nav2_mppi_controller/tools/utils.hpp"
#include "nav2_core/controller.hpp"
#include "nav2_core/goal_checker.hpp"
#include "rclcpp/rclcpp.hpp"
namespace nav2_mppi_controller
{
using namespace mppi; // NOLINT
class MPPIController : public nav2_core::Controller
{
public:
MPPIController() = default;
void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
void cleanup() override;
void activate() override;
void deactivate() override;
void reset();
geometry_msgs::msg::TwistStamped computeVelocityCommands(
const geometry_msgs::msg::PoseStamped & robot_pose,
const geometry_msgs::msg::Twist & robot_speed,
nav2_core::GoalChecker * goal_checker) override;
void setPlan(const nav_msgs::msg::Path & path) override;
void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
protected:
void visualize(nav_msgs::msg::Path transformed_plan);
std::string name_;
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
rclcpp::Clock::SharedPtr clock_;
rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
std::unique_ptr<ParametersHandler> parameters_handler_;
Optimizer optimizer_;
PathHandler path_handler_;
TrajectoryVisualizer trajectory_visualizer_;
bool visualize_;
double reset_period_;
// Last time computeVelocityCommands was called
rclcpp::Time last_time_called_;
};
} // namespace nav2_mppi_controller
#endif // NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_