|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Public Member Functions | |
| MPPIController ()=default | |
| Constructor for mppi::MPPIController. | |
| 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 |
| Configure controller on bringup. More... | |
| void | cleanup () override |
| Cleanup resources. | |
| void | activate () override |
| Activate controller. | |
| void | deactivate () override |
| Deactivate controller. | |
| void | reset () |
| Reset the controller state between tasks. | |
| 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 |
| Main method to compute velocities using the optimizer. More... | |
| void | setPlan (const nav_msgs::msg::Path &path) override |
| Set new reference path to track. More... | |
| void | setSpeedLimit (const double &speed_limit, const bool &percentage) override |
| Set new speed limit from callback. More... | |
Public Member Functions inherited from nav2_core::Controller | |
| virtual | ~Controller () |
| Virtual destructor. | |
Protected Member Functions | |
| void | visualize (nav_msgs::msg::Path transformed_plan) |
| Visualize trajectories. More... | |
Protected Attributes | |
| 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_ |
| rclcpp::Time | last_time_called_ |
Additional Inherited Members | |
Public Types inherited from nav2_core::Controller | |
| using | Ptr = std::shared_ptr< nav2_core::Controller > |
Definition at line 40 of file controller.hpp.
|
overridevirtual |
Main method to compute velocities using the optimizer.
| robot_pose | Robot pose |
| robot_speed | Robot speed |
| goal_checker | Pointer to the goal checker for awareness if completed task |
Implements nav2_core::Controller.
Definition at line 80 of file controller.cpp.
References mppi::Optimizer::evalControl(), reset(), mppi::PathHandler::transformPath(), and visualize().
|
overridevirtual |
Configure controller on bringup.
| parent | WeakPtr to node |
| name | Name of plugin |
| tf | TF buffer to use |
| costmap_ros | Costmap2DROS object of environment |
Implements nav2_core::Controller.
Definition at line 25 of file controller.cpp.
References mppi::Optimizer::initialize(), mppi::PathHandler::initialize(), and mppi::TrajectoryVisualizer::on_configure().
|
overridevirtual |
Set new reference path to track.
| path | Path to track |
Implements nav2_core::Controller.
Definition at line 123 of file controller.cpp.
References mppi::PathHandler::setPath().
|
overridevirtual |
Set new speed limit from callback.
| speed_limit | Speed limit to use |
| percentage | Bool if the speed limit is absolute or relative |
Implements nav2_core::Controller.
Definition at line 128 of file controller.cpp.
References mppi::Optimizer::setSpeedLimit().
|
protected |
Visualize trajectories.
| transformed_plan | Transformed input plan |
Definition at line 116 of file controller.cpp.
References mppi::TrajectoryVisualizer::add(), mppi::Optimizer::getGeneratedTrajectories(), mppi::Optimizer::getOptimizedTrajectory(), and mppi::TrajectoryVisualizer::visualize().
Referenced by computeVelocityCommands().