Template Class DriveOnHeading

Inheritance Relationships

Base Type

Class Documentation

template<typename ActionT = nav2_msgs::action::DriveOnHeading>
class DriveOnHeading : public nav2_behaviors::TimedBehavior<nav2_msgs::action::DriveOnHeading>

An action server Behavior for spinning in.

Public Functions

inline DriveOnHeading()

A constructor for nav2_behaviors::DriveOnHeading.

~DriveOnHeading() = default
inline virtual ResultStatus onRun(const std::shared_ptr<const typename ActionT::Goal> command) override

Initialization to run behavior.

Parameters:

command – Goal to execute

Returns:

Status of behavior

inline virtual ResultStatus onCycleUpdate() override

Loop function to run behavior.

Returns:

Status of behavior

inline virtual CostmapInfoType getResourceInfo() override

Method to determine the required costmap info.

Returns:

costmap resources needed

Protected Functions

inline bool isCollisionFree(const double &distance, const 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

inline virtual void onConfigure() override

Configuration of behavior action.

Protected Attributes

ActionT::Feedback::SharedPtr feedback_
geometry_msgs::msg::PoseStamped initial_pose_
double command_x_
double command_speed_
rclcpp::Duration command_time_allowance_ = {0, 0}
rclcpp::Time end_time_
double simulate_ahead_time_