Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
spin.hpp
1 // Copyright (c) 2018 Intel Corporation
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__SPIN_HPP_
16 #define NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_
17 
18 #include <chrono>
19 #include <string>
20 #include <memory>
21 
22 #include "nav2_behaviors/timed_behavior.hpp"
23 #include "nav2_msgs/action/spin.hpp"
24 #include "geometry_msgs/msg/quaternion.hpp"
25 #include "geometry_msgs/msg/twist_stamped.hpp"
26 
27 namespace nav2_behaviors
28 {
29 using SpinAction = nav2_msgs::action::Spin;
30 
35 class Spin : public TimedBehavior<SpinAction>
36 {
37  using CostmapInfoType = nav2_core::CostmapInfoType;
38 
39 public:
40  using SpinActionGoal = SpinAction::Goal;
41  using SpinActionResult = SpinAction::Result;
42 
46  Spin();
47  ~Spin();
48 
54  ResultStatus onRun(const std::shared_ptr<const SpinActionGoal> command) override;
55 
59  void onConfigure() override;
60 
65  ResultStatus onCycleUpdate() override;
66 
71  CostmapInfoType getResourceInfo() override {return CostmapInfoType::LOCAL;}
72 
73 protected:
81  bool isCollisionFree(
82  const double & distance,
83  const geometry_msgs::msg::Twist & cmd_vel,
84  geometry_msgs::msg::Pose & pose);
85 
86  SpinAction::Feedback::SharedPtr feedback_;
87 
88  double min_rotational_vel_;
89  double max_rotational_vel_;
90  double rotational_acc_lim_;
91  double cmd_yaw_;
92  bool cmd_disable_collision_checks_;
93  double prev_yaw_;
94  double relative_yaw_;
95  double simulate_ahead_time_;
96  rclcpp::Duration command_time_allowance_{0, 0};
97  rclcpp::Time end_time_;
98 };
99 
100 } // namespace nav2_behaviors
101 
102 #endif // NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_
An action server behavior for spinning in.
Definition: spin.hpp:36
CostmapInfoType getResourceInfo() override
Method to determine the required costmap info.
Definition: spin.hpp:71
ResultStatus onRun(const std::shared_ptr< const SpinActionGoal > command) override
Initialization to run behavior.
Definition: spin.cpp:73
ResultStatus onCycleUpdate() override
Loop function to run behavior.
Definition: spin.cpp:100
Spin()
A constructor for nav2_behaviors::Spin.
Definition: spin.cpp:30
void onConfigure() override
Configuration of behavior action.
Definition: spin.cpp:45
bool isCollisionFree(const double &distance, const geometry_msgs::msg::Twist &cmd_vel, geometry_msgs::msg::Pose &pose)
Check if pose is collision free.
Definition: spin.cpp:161