15 #ifndef NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_
16 #define NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_
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"
27 namespace nav2_behaviors
29 using SpinAction = nav2_msgs::action::Spin;
37 using CostmapInfoType = nav2_core::CostmapInfoType;
40 using SpinActionGoal = SpinAction::Goal;
41 using SpinActionResult = SpinAction::Result;
82 const double & distance,
83 const geometry_msgs::msg::Twist & cmd_vel,
84 geometry_msgs::msg::Pose2D & pose2d);
86 SpinAction::Feedback::SharedPtr feedback_;
88 double min_rotational_vel_;
89 double max_rotational_vel_;
90 double rotational_acc_lim_;
92 bool cmd_disable_collision_checks_;
95 double simulate_ahead_time_;
96 rclcpp::Duration command_time_allowance_{0, 0};
97 rclcpp::Time end_time_;
An action server behavior for spinning in.
CostmapInfoType getResourceInfo() override
Method to determine the required costmap info.
ResultStatus onRun(const std::shared_ptr< const SpinActionGoal > command) override
Initialization to run behavior.
ResultStatus onCycleUpdate() override
Loop function to run behavior.
Spin()
A constructor for nav2_behaviors::Spin.
bool isCollisionFree(const double &distance, const geometry_msgs::msg::Twist &cmd_vel, geometry_msgs::msg::Pose2D &pose2d)
Check if pose is collision free.
void onConfigure() override
Configuration of behavior action.