Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
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 Member Functions

Status onRun (const std::shared_ptr< const AssistedTeleopAction::Goal > command) override
 Initialization to run behavior. More...
 
void onActionCompletion () override
 func to run at the completion of the action
 
Status onCycleUpdate () override
 Loop function to run behavior. More...
 
- Public Member Functions inherited from nav2_behaviors::TimedBehavior< AssistedTeleopAction >
 TimedBehavior ()
 A TimedBehavior constructor.
 
virtual Status onRun (const std::shared_ptr< const typename ActionT::Goal > command)=0
 
virtual void onCleanup ()
 
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 > 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 deactive 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 teleopVelocityCallback (const geometry_msgs::msg::Twist::SharedPtr msg)
 Callback function for velocity subscriber. 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::Twist teleop_twist_
 
bool preempt_teleop_ {false}
 
rclcpp::Subscription< geometry_msgs::msg::Twist >::SharedPtr vel_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_
 
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr vel_pub_
 
std::shared_ptr< ActionServeraction_server_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckercollision_checker_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
double cycle_frequency_
 
double enabled_
 
std::string global_frame_
 
std::string robot_base_frame_
 
double transform_tolerance_
 
rclcpp::Duration elasped_time_
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_
 

Additional Inherited Members

- 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 >
 

Detailed Description

An action server behavior for assisted teleop.

Definition at line 35 of file assisted_teleop.hpp.

Member Function Documentation

◆ onCycleUpdate()

Status nav2_behaviors::AssistedTeleop::onCycleUpdate ( )
overridevirtual

Loop function to run behavior.

Returns
Status of behavior

Implements nav2_behaviors::TimedBehavior< AssistedTeleopAction >.

Definition at line 80 of file assisted_teleop.cpp.

◆ onRun()

Status nav2_behaviors::AssistedTeleop::onRun ( const std::shared_ptr< const AssistedTeleopAction::Goal >  command)
override

Initialization to run behavior.

Parameters
commandGoal to execute
Returns
Status of behavior

Definition at line 66 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 178 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 153 of file assisted_teleop.cpp.

◆ teleopVelocityCallback()

void nav2_behaviors::AssistedTeleop::teleopVelocityCallback ( const geometry_msgs::msg::Twist::SharedPtr  msg)
protected

Callback function for velocity subscriber.

Parameters
msgreceived Twist message

Definition at line 173 of file assisted_teleop.cpp.


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