Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_behaviors::AssistedTeleop Class Reference

An action server behavior for assisted teleop. More...

#include <nav2_behaviors/include/nav2_behaviors/plugins/assisted_teleop.hpp>

Inheritance diagram for nav2_behaviors::AssistedTeleop:
Inheritance graph
[legend]
Collaboration diagram for nav2_behaviors::AssistedTeleop:
Collaboration graph
[legend]

Public Types

using AssistedTeleopActionGoal = AssistedTeleopAction::Goal
 
using AssistedTeleopActionResult = AssistedTeleopAction::Result
 
- Public Types inherited from nav2_behaviors::TimedBehavior< AssistedTeleopAction >
using ActionServer = nav2_util::SimpleActionServer< AssistedTeleopAction >
 
- Public Types inherited from nav2_core::Behavior
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...
 
- Public Member Functions inherited from nav2_behaviors::TimedBehavior< AssistedTeleopAction >
 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 rclcpp_lifecycle::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.
 
- Public Member Functions inherited from nav2_core::Behavior
virtual ~Behavior ()
 Virtual destructor.
 

Protected Member Functions

void onConfigure () override
 Configuration of behavior action.
 
geometry_msgs::msg::Pose2D projectPose (const geometry_msgs::msg::Pose2D &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...
 
- Protected Member Functions inherited from nav2_behaviors::TimedBehavior< AssistedTeleopAction >
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::TwistSubscribervel_sub_
 
rclcpp::Subscription< std_msgs::msg::Empty >::SharedPtr preempt_teleop_sub_
 
rclcpp::Duration command_time_allowance_ {0, 0}
 
rclcpp::Time end_time_
 
- Protected Attributes inherited from nav2_behaviors::TimedBehavior< AssistedTeleopAction >
rclcpp_lifecycle::LifecycleNode::WeakPtr node_
 
std::string behavior_name_
 
std::unique_ptr< nav2_util::TwistPublishervel_pub_
 
std::shared_ptr< ActionServeraction_server_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckerlocal_collision_checker_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckerglobal_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_
 

Detailed Description

An action server behavior for assisted teleop.

Definition at line 36 of file assisted_teleop.hpp.

Member Function Documentation

◆ getResourceInfo()

CostmapInfoType nav2_behaviors::AssistedTeleop::getResourceInfo ( )
inlineoverridevirtual

Method to determine the required costmap info.

Returns
costmap resources needed

Implements nav2_core::Behavior.

Definition at line 67 of file assisted_teleop.hpp.

◆ onCycleUpdate()

ResultStatus nav2_behaviors::AssistedTeleop::onCycleUpdate ( )
overridevirtual

Loop function to run behavior.

Returns
Status of behavior

Implements nav2_behaviors::TimedBehavior< AssistedTeleopAction >.

Definition at line 83 of file assisted_teleop.cpp.

◆ onRun()

ResultStatus nav2_behaviors::AssistedTeleop::onRun ( const std::shared_ptr< const AssistedTeleopActionGoal >  command)
override

Initialization to run behavior.

Parameters
commandGoal to execute
Returns
Status of behavior

Definition at line 69 of file assisted_teleop.cpp.

◆ preemptTeleopCallback()

void nav2_behaviors::AssistedTeleop::preemptTeleopCallback ( const std_msgs::msg::Empty::SharedPtr  msg)
protected

Callback function to preempt assisted teleop.

Parameters
msgempty message

Definition at line 174 of file assisted_teleop.cpp.

◆ projectPose()

geometry_msgs::msg::Pose2D nav2_behaviors::AssistedTeleop::projectPose ( const geometry_msgs::msg::Pose2D &  pose,
const geometry_msgs::msg::Twist &  twist,
double  projection_time 
)
protected

project a position

Parameters
poseinitial pose to project
twistvelocity to project pose by
projection_timetime to project by

Definition at line 154 of file assisted_teleop.cpp.


The documentation for this class was generated from the following files: