An action server behavior for assisted teleop.
More...
#include <nav2_behaviors/include/nav2_behaviors/plugins/assisted_teleop.hpp>
|
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...
|
|
| 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.
|
|
virtual | ~Behavior () |
| Virtual destructor.
|
|
|
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...
|
|
void | execute () |
|
void | stopRobot () |
|
|
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_ |
|
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
|
std::string | behavior_name_ |
|
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr | vel_pub_ |
|
std::shared_ptr< ActionServer > | action_server_ |
|
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | collision_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_ |
|
An action server behavior for assisted teleop.
Definition at line 35 of file assisted_teleop.hpp.
◆ onCycleUpdate()
Status nav2_behaviors::AssistedTeleop::onCycleUpdate |
( |
| ) |
|
|
overridevirtual |
◆ onRun()
Status nav2_behaviors::AssistedTeleop::onRun |
( |
const std::shared_ptr< const AssistedTeleopAction::Goal > |
command | ) |
|
|
override |
Initialization to run behavior.
- Parameters
-
- 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 |
◆ 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
-
pose | initial pose to project |
twist | velocity to project pose by |
projection_time | time 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
-
msg | received Twist message |
Definition at line 173 of file assisted_teleop.cpp.
The documentation for this class was generated from the following files: