Class Spin

Inheritance Relationships

Base Type

Class Documentation

class Spin : public nav2_behaviors::TimedBehavior<SpinAction>

An action server behavior for spinning in.

Public Functions

Spin()

A constructor for nav2_behaviors::Spin.

~Spin()
Status onRun(const std::shared_ptr<const SpinAction::Goal> command) override

Initialization to run behavior.

Parameters:

command – Goal to execute

Returns:

Status of behavior

virtual void onConfigure() override

Configuration of behavior action.

virtual Status onCycleUpdate() override

Loop function to run behavior.

Returns:

Status of behavior

Protected Functions

bool isCollisionFree(const double &distance, geometry_msgs::msg::Twist *cmd_vel, geometry_msgs::msg::Pose2D &pose2d)

Check if pose is collision free.

Parameters:
  • distance – Distance to check forward

  • cmd_vel – current commanded velocity

  • pose2d – Current pose

Returns:

is collision free or not

Protected Attributes

SpinAction::Feedback::SharedPtr feedback_
double min_rotational_vel_
double max_rotational_vel_
double rotational_acc_lim_
double cmd_yaw_
double prev_yaw_
double relative_yaw_
double simulate_ahead_time_
rclcpp::Duration command_time_allowance_ = {0, 0}
rclcpp::Time end_time_