Nav2 Navigation Stack - humble  humble
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 
26 namespace nav2_behaviors
27 {
28 using SpinAction = nav2_msgs::action::Spin;
29 
34 class Spin : public TimedBehavior<SpinAction>
35 {
36 public:
40  Spin();
41  ~Spin();
42 
48  Status onRun(const std::shared_ptr<const SpinAction::Goal> command) override;
49 
53  void onConfigure() override;
54 
59  Status onCycleUpdate() override;
60 
61 protected:
69  bool isCollisionFree(
70  const double & distance,
71  geometry_msgs::msg::Twist * cmd_vel,
72  geometry_msgs::msg::Pose2D & pose2d);
73 
74  SpinAction::Feedback::SharedPtr feedback_;
75 
76  double min_rotational_vel_;
77  double max_rotational_vel_;
78  double rotational_acc_lim_;
79  double cmd_yaw_;
80  double prev_yaw_;
81  double relative_yaw_;
82  double simulate_ahead_time_;
83  rclcpp::Duration command_time_allowance_{0, 0};
84  rclcpp::Time end_time_;
85 };
86 
87 } // namespace nav2_behaviors
88 
89 #endif // NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_
An action server behavior for spinning in.
Definition: spin.hpp:35
Spin()
A constructor for nav2_behaviors::Spin.
Definition: spin.cpp:31
bool isCollisionFree(const double &distance, geometry_msgs::msg::Twist *cmd_vel, geometry_msgs::msg::Pose2D &pose2d)
Check if pose is collision free.
Definition: spin.cpp:160
Status onCycleUpdate() override
Loop function to run behavior.
Definition: spin.cpp:99
void onConfigure() override
Configuration of behavior action.
Definition: spin.cpp:46
Status onRun(const std::shared_ptr< const SpinAction::Goal > command) override
Initialization to run behavior.
Definition: spin.cpp:74