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"
26 namespace nav2_behaviors
28 using SpinAction = nav2_msgs::action::Spin;
48 Status
onRun(
const std::shared_ptr<const SpinAction::Goal> command)
override;
70 const double & distance,
71 geometry_msgs::msg::Twist * cmd_vel,
72 geometry_msgs::msg::Pose2D & pose2d);
74 SpinAction::Feedback::SharedPtr feedback_;
76 double min_rotational_vel_;
77 double max_rotational_vel_;
78 double rotational_acc_lim_;
82 double simulate_ahead_time_;
83 rclcpp::Duration command_time_allowance_{0, 0};
84 rclcpp::Time end_time_;
An action server behavior for spinning in.
Spin()
A constructor for nav2_behaviors::Spin.
bool isCollisionFree(const double &distance, geometry_msgs::msg::Twist *cmd_vel, geometry_msgs::msg::Pose2D &pose2d)
Check if pose is collision free.
Status onCycleUpdate() override
Loop function to run behavior.
void onConfigure() override
Configuration of behavior action.
Status onRun(const std::shared_ptr< const SpinAction::Goal > command) override
Initialization to run behavior.