Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
assisted_teleop.hpp
1 // Copyright (c) 2022 Joshua Wallace
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_BEHAVIORS__PLUGINS__ASSISTED_TELEOP_HPP_
16 #define NAV2_BEHAVIORS__PLUGINS__ASSISTED_TELEOP_HPP_
17 
18 #include <chrono>
19 #include <memory>
20 #include <string>
21 
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"
27 
28 namespace nav2_behaviors
29 {
30 using AssistedTeleopAction = nav2_msgs::action::AssistedTeleop;
31 
36 class AssistedTeleop : public TimedBehavior<AssistedTeleopAction>
37 {
38  using CostmapInfoType = nav2_core::CostmapInfoType;
39 
40 public:
41  using AssistedTeleopActionGoal = AssistedTeleopAction::Goal;
42  using AssistedTeleopActionResult = AssistedTeleopAction::Result;
44 
50  ResultStatus onRun(const std::shared_ptr<const AssistedTeleopActionGoal> command) override;
51 
55  void onActionCompletion(std::shared_ptr<AssistedTeleopActionResult>/*result*/) override;
56 
61  ResultStatus onCycleUpdate() override;
62 
67  CostmapInfoType getResourceInfo() override {return CostmapInfoType::LOCAL;}
68 
69 protected:
73  void onConfigure() override;
74 
81  geometry_msgs::msg::Pose projectPose(
82  const geometry_msgs::msg::Pose & pose,
83  const geometry_msgs::msg::Twist & twist,
84  double projection_time);
85 
90  void preemptTeleopCallback(const std_msgs::msg::Empty::SharedPtr msg);
91 
92  AssistedTeleopAction::Feedback::SharedPtr feedback_;
93 
94  // parameters
95  double projection_time_;
96  double simulation_time_step_;
97 
98  geometry_msgs::msg::TwistStamped teleop_twist_;
99  bool preempt_teleop_{false};
100 
101  // subscribers
102  std::unique_ptr<nav2_util::TwistSubscriber> vel_sub_;
103  nav2::Subscription<std_msgs::msg::Empty>::SharedPtr preempt_teleop_sub_;
104 
105  rclcpp::Duration command_time_allowance_{0, 0};
106  rclcpp::Time end_time_;
107 };
108 } // namespace nav2_behaviors
109 
110 #endif // NAV2_BEHAVIORS__PLUGINS__ASSISTED_TELEOP_HPP_
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::Pose projectPose(const geometry_msgs::msg::Pose &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.