15 #ifndef NAV2_BEHAVIORS__PLUGINS__ASSISTED_TELEOP_HPP_
16 #define NAV2_BEHAVIORS__PLUGINS__ASSISTED_TELEOP_HPP_
22 #include "geometry_msgs/msg/twist.hpp"
23 #include "std_msgs/msg/empty.hpp"
24 #include "nav2_behaviors/timed_behavior.hpp"
25 #include "nav2_msgs/action/assisted_teleop.hpp"
27 namespace nav2_behaviors
29 using AssistedTeleopAction = nav2_msgs::action::AssistedTeleop;
45 Status
onRun(
const std::shared_ptr<const AssistedTeleopAction::Goal> command)
override;
71 const geometry_msgs::msg::Pose2D & pose,
72 const geometry_msgs::msg::Twist & twist,
73 double projection_time);
87 AssistedTeleopAction::Feedback::SharedPtr feedback_;
90 double projection_time_;
91 double simulation_time_step_;
93 geometry_msgs::msg::Twist teleop_twist_;
94 bool preempt_teleop_{
false};
97 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr vel_sub_;
98 rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr preempt_teleop_sub_;
100 rclcpp::Duration command_time_allowance_{0, 0};
101 rclcpp::Time end_time_;
An action server behavior for assisted teleop.
geometry_msgs::msg::Pose2D projectPose(const geometry_msgs::msg::Pose2D &pose, const geometry_msgs::msg::Twist &twist, double projection_time)
project a position
Status onRun(const std::shared_ptr< const AssistedTeleopAction::Goal > command) override
Initialization to run behavior.
void onActionCompletion() override
func to run at the completion of the action
Status onCycleUpdate() override
Loop function to run behavior.
void preemptTeleopCallback(const std_msgs::msg::Empty::SharedPtr msg)
Callback function to preempt assisted teleop.
void onConfigure() override
Configuration of behavior action.
void teleopVelocityCallback(const geometry_msgs::msg::Twist::SharedPtr msg)
Callback function for velocity subscriber.