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"
26 #include "nav2_util/twist_subscriber.hpp"
28 namespace nav2_behaviors
30 using AssistedTeleopAction = nav2_msgs::action::AssistedTeleop;
38 using CostmapInfoType = nav2_core::CostmapInfoType;
41 using AssistedTeleopActionGoal = AssistedTeleopAction::Goal;
42 using AssistedTeleopActionResult = AssistedTeleopAction::Result;
50 ResultStatus onRun(
const std::shared_ptr<const AssistedTeleopActionGoal> command)
override;
82 const geometry_msgs::msg::Pose2D & pose,
83 const geometry_msgs::msg::Twist & twist,
84 double projection_time);
92 AssistedTeleopAction::Feedback::SharedPtr feedback_;
95 double projection_time_;
96 double simulation_time_step_;
98 geometry_msgs::msg::TwistStamped teleop_twist_;
99 bool preempt_teleop_{
false};
102 std::unique_ptr<nav2_util::TwistSubscriber> vel_sub_;
103 rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr preempt_teleop_sub_;
105 rclcpp::Duration command_time_allowance_{0, 0};
106 rclcpp::Time end_time_;
An action server behavior for assisted teleop.
void onActionCompletion(std::shared_ptr< AssistedTeleopActionResult >) override
func to run at the completion of the action
ResultStatus onCycleUpdate() override
Loop function to run behavior.
CostmapInfoType getResourceInfo() override
Method to determine the required costmap info.
geometry_msgs::msg::Pose2D projectPose(const geometry_msgs::msg::Pose2D &pose, const geometry_msgs::msg::Twist &twist, double projection_time)
project a position
void preemptTeleopCallback(const std_msgs::msg::Empty::SharedPtr msg)
Callback function to preempt assisted teleop.
void onConfigure() override
Configuration of behavior action.
ResultStatus onRun(const std::shared_ptr< const AssistedTeleopActionGoal > command) override
Initialization to run behavior.