Class AssistedTeleop

Inheritance Relationships

Base Type

Class Documentation

class AssistedTeleop : public nav2_behaviors::TimedBehavior<AssistedTeleopAction>

An action server behavior for assisted teleop.

Public Functions

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

Initialization to run behavior.

Parameters:

command – Goal to execute

Returns:

Status of behavior

virtual void onActionCompletion() override

func to run at the completion of the action

virtual Status onCycleUpdate() override

Loop function to run behavior.

Returns:

Status of behavior

Protected Functions

virtual 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

Parameters:
  • pose – initial pose to project

  • twist – velocity to project pose by

  • projection_time – time to project by

void teleopVelocityCallback(const geometry_msgs::msg::Twist::SharedPtr msg)

Callback function for velocity subscriber.

Parameters:

msg – received Twist message

void preemptTeleopCallback(const std_msgs::msg::Empty::SharedPtr msg)

Callback function to preempt assisted teleop.

Parameters:

msg – empty message

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_