Nav2 Navigation Stack - humble  humble
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 
27 namespace nav2_behaviors
28 {
29 using AssistedTeleopAction = nav2_msgs::action::AssistedTeleop;
30 
35 class AssistedTeleop : public TimedBehavior<AssistedTeleopAction>
36 {
37 public:
39 
45  Status onRun(const std::shared_ptr<const AssistedTeleopAction::Goal> command) override;
46 
50  void onActionCompletion() override;
51 
56  Status onCycleUpdate() override;
57 
58 protected:
62  void onConfigure() override;
63 
70  geometry_msgs::msg::Pose2D projectPose(
71  const geometry_msgs::msg::Pose2D & pose,
72  const geometry_msgs::msg::Twist & twist,
73  double projection_time);
74 
79  void teleopVelocityCallback(const geometry_msgs::msg::Twist::SharedPtr msg);
80 
85  void preemptTeleopCallback(const std_msgs::msg::Empty::SharedPtr msg);
86 
87  AssistedTeleopAction::Feedback::SharedPtr feedback_;
88 
89  // parameters
90  double projection_time_;
91  double simulation_time_step_;
92 
93  geometry_msgs::msg::Twist teleop_twist_;
94  bool preempt_teleop_{false};
95 
96  // subscribers
97  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr vel_sub_;
98  rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr preempt_teleop_sub_;
99 
100  rclcpp::Duration command_time_allowance_{0, 0};
101  rclcpp::Time end_time_;
102 };
103 } // namespace nav2_behaviors
104 
105 #endif // NAV2_BEHAVIORS__PLUGINS__ASSISTED_TELEOP_HPP_
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.