Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
An action server behavior for assisted teleop. More...
#include <nav2_behaviors/include/nav2_behaviors/plugins/assisted_teleop.hpp>
Public Types | |
using | AssistedTeleopActionGoal = AssistedTeleopAction::Goal |
using | AssistedTeleopActionResult = AssistedTeleopAction::Result |
![]() | |
using | ActionServer = nav2::SimpleActionServer< AssistedTeleopAction > |
![]() | |
using | Ptr = std::shared_ptr< Behavior > |
Public Member Functions | |
ResultStatus | onRun (const std::shared_ptr< const AssistedTeleopActionGoal > command) override |
Initialization to run behavior. More... | |
void | onActionCompletion (std::shared_ptr< AssistedTeleopActionResult >) override |
func to run at the completion of the action | |
ResultStatus | onCycleUpdate () override |
Loop function to run behavior. More... | |
CostmapInfoType | getResourceInfo () override |
Method to determine the required costmap info. More... | |
![]() | |
TimedBehavior () | |
A TimedBehavior constructor. | |
virtual ResultStatus | onRun (const std::shared_ptr< const typename ActionT::Goal > command)=0 |
virtual void | onCleanup () |
virtual void | onActionCompletion (std::shared_ptr< typename ActionT::Result >) |
void | configure (const nav2::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > local_collision_checker, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > global_collision_checker) override |
void | cleanup () override |
Method to cleanup resources used on shutdown. | |
void | activate () override |
Method to active Behavior and any threads involved in execution. | |
void | deactivate () override |
Method to deactivate Behavior and any threads involved in execution. | |
![]() | |
virtual | ~Behavior () |
Virtual destructor. | |
Protected Member Functions | |
void | onConfigure () override |
Configuration of behavior action. | |
geometry_msgs::msg::Pose | projectPose (const geometry_msgs::msg::Pose &pose, const geometry_msgs::msg::Twist &twist, double projection_time) |
project a position More... | |
void | preemptTeleopCallback (const std_msgs::msg::Empty::SharedPtr msg) |
Callback function to preempt assisted teleop. More... | |
![]() | |
void | execute () |
void | stopRobot () |
Protected Attributes | |
AssistedTeleopAction::Feedback::SharedPtr | feedback_ |
double | projection_time_ |
double | simulation_time_step_ |
geometry_msgs::msg::TwistStamped | teleop_twist_ |
bool | preempt_teleop_ {false} |
std::unique_ptr< nav2_util::TwistSubscriber > | vel_sub_ |
nav2::Subscription< std_msgs::msg::Empty >::SharedPtr | preempt_teleop_sub_ |
rclcpp::Duration | command_time_allowance_ {0, 0} |
rclcpp::Time | end_time_ |
![]() | |
nav2::LifecycleNode::WeakPtr | node_ |
std::string | behavior_name_ |
std::unique_ptr< nav2_util::TwistPublisher > | vel_pub_ |
ActionServer::SharedPtr | action_server_ |
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | local_collision_checker_ |
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | global_collision_checker_ |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
double | cycle_frequency_ |
double | enabled_ |
std::string | local_frame_ |
std::string | global_frame_ |
std::string | robot_base_frame_ |
double | transform_tolerance_ |
rclcpp::Duration | elapsed_time_ |
rclcpp::Clock::SharedPtr | clock_ |
rclcpp::Logger | logger_ |
An action server behavior for assisted teleop.
Definition at line 36 of file assisted_teleop.hpp.
|
inlineoverridevirtual |
Method to determine the required costmap info.
Implements nav2_core::Behavior.
Definition at line 67 of file assisted_teleop.hpp.
|
overridevirtual |
Loop function to run behavior.
Implements nav2_behaviors::TimedBehavior< AssistedTeleopAction >.
Definition at line 84 of file assisted_teleop.cpp.
|
override |
Initialization to run behavior.
command | Goal to execute |
Definition at line 70 of file assisted_teleop.cpp.
|
protected |
Callback function to preempt assisted teleop.
msg | empty message |
Definition at line 175 of file assisted_teleop.cpp.
|
protected |
project a position
pose | initial pose to project |
twist | velocity to project pose by |
projection_time | time to project by |
Definition at line 152 of file assisted_teleop.cpp.