Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_behaviors::DriveOnHeading< ActionT > Class Template Reference

An action server Behavior for spinning in. More...

#include <nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp>

Inheritance diagram for nav2_behaviors::DriveOnHeading< ActionT >:
Inheritance graph
[legend]
Collaboration diagram for nav2_behaviors::DriveOnHeading< ActionT >:
Collaboration graph
[legend]

Public Member Functions

 DriveOnHeading ()
 A constructor for nav2_behaviors::DriveOnHeading.
 
ResultStatus onRun (const std::shared_ptr< const typename ActionT::Goal > command) override
 Initialization to run behavior. More...
 
ResultStatus onCycleUpdate () override
 Loop function to run behavior. More...
 
CostmapInfoType getResourceInfo () override
 Method to determine the required costmap info. More...
 
void onCleanup () override
 
void onActionCompletion (std::shared_ptr< typename ActionT::Result >) override
 
- Public Member Functions inherited from nav2_behaviors::TimedBehavior< nav2_msgs::action::DriveOnHeading >
 TimedBehavior ()
 A TimedBehavior constructor.
 
void configure (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > local_collision_checker, std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > global_collision_checker) override
 
void cleanup () override
 Method to cleanup resources used on shutdown.
 
void activate () override
 Method to active Behavior and any threads involved in execution.
 
void deactivate () override
 Method to deactivate Behavior and any threads involved in execution.
 
- Public Member Functions inherited from nav2_core::Behavior
virtual ~Behavior ()
 Virtual destructor.
 

Protected Member Functions

bool isCollisionFree (const double &distance, const geometry_msgs::msg::Twist &cmd_vel, geometry_msgs::msg::Pose2D &pose2d)
 Check if pose is collision free. More...
 
void onConfigure () override
 Configuration of behavior action.
 
- Protected Member Functions inherited from nav2_behaviors::TimedBehavior< nav2_msgs::action::DriveOnHeading >
void execute ()
 
void stopRobot ()
 

Protected Attributes

ActionT::Feedback::SharedPtr feedback_
 
geometry_msgs::msg::PoseStamped initial_pose_
 
double command_x_
 
double command_speed_
 
bool command_disable_collision_checks_
 
rclcpp::Duration command_time_allowance_ {0, 0}
 
rclcpp::Time end_time_
 
double simulate_ahead_time_
 
double acceleration_limit_
 
double deceleration_limit_
 
double minimum_speed_
 
double last_vel_ = std::numeric_limits<double>::max()
 
- Protected Attributes inherited from nav2_behaviors::TimedBehavior< nav2_msgs::action::DriveOnHeading >
rclcpp_lifecycle::LifecycleNode::WeakPtr node_
 
std::string behavior_name_
 
std::unique_ptr< nav2_util::TwistPublishervel_pub_
 
std::shared_ptr< ActionServeraction_server_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckerlocal_collision_checker_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckerglobal_collision_checker_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
double cycle_frequency_
 
double enabled_
 
std::string local_frame_
 
std::string global_frame_
 
std::string robot_base_frame_
 
double transform_tolerance_
 
rclcpp::Duration elapsed_time_
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_
 

Additional Inherited Members

- Public Types inherited from nav2_behaviors::TimedBehavior< nav2_msgs::action::DriveOnHeading >
using ActionServer = nav2_util::SimpleActionServer< nav2_msgs::action::DriveOnHeading >
 
- Public Types inherited from nav2_core::Behavior
using Ptr = std::shared_ptr< Behavior >
 

Detailed Description

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

An action server Behavior for spinning in.

Definition at line 39 of file drive_on_heading.hpp.

Member Function Documentation

◆ getResourceInfo()

template<typename ActionT = nav2_msgs::action::DriveOnHeading>
CostmapInfoType nav2_behaviors::DriveOnHeading< ActionT >::getResourceInfo ( )
inlineoverridevirtual

Method to determine the required costmap info.

Returns
costmap resources needed

Implements nav2_core::Behavior.

Definition at line 188 of file drive_on_heading.hpp.

◆ isCollisionFree()

template<typename ActionT = nav2_msgs::action::DriveOnHeading>
bool nav2_behaviors::DriveOnHeading< ActionT >::isCollisionFree ( const double &  distance,
const geometry_msgs::msg::Twist &  cmd_vel,
geometry_msgs::msg::Pose2D &  pose2d 
)
inlineprotected

Check if pose is collision free.

Parameters
distanceDistance to check forward
cmd_velcurrent commanded velocity
pose2dCurrent pose
Returns
is collision free or not

Definition at line 206 of file drive_on_heading.hpp.

Referenced by nav2_behaviors::DriveOnHeading< ActionT >::onCycleUpdate().

Here is the caller graph for this function:

◆ onCycleUpdate()

template<typename ActionT = nav2_msgs::action::DriveOnHeading>
ResultStatus nav2_behaviors::DriveOnHeading< ActionT >::onCycleUpdate ( )
inlineoverridevirtual

Loop function to run behavior.

Returns
Status of behavior

Implements nav2_behaviors::TimedBehavior< nav2_msgs::action::DriveOnHeading >.

Definition at line 103 of file drive_on_heading.hpp.

References nav2_behaviors::DriveOnHeading< ActionT >::isCollisionFree().

Here is the call graph for this function:

◆ onRun()

template<typename ActionT = nav2_msgs::action::DriveOnHeading>
ResultStatus nav2_behaviors::DriveOnHeading< ActionT >::onRun ( const std::shared_ptr< const typename ActionT::Goal >  command)
inlineoverridevirtual

Initialization to run behavior.

Parameters
commandGoal to execute
Returns
Status of behavior

Implements nav2_behaviors::TimedBehavior< nav2_msgs::action::DriveOnHeading >.

Definition at line 64 of file drive_on_heading.hpp.


The documentation for this class was generated from the following file: