Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | List of all members
nav2_behaviors::BackUp Class Reference
Inheritance diagram for nav2_behaviors::BackUp:
Inheritance graph
[legend]
Collaboration diagram for nav2_behaviors::BackUp:
Collaboration graph
[legend]

Public Member Functions

Status onRun (const std::shared_ptr< const BackUpAction::Goal > command) override
 
- Public Member Functions inherited from nav2_behaviors::DriveOnHeading< nav2_msgs::action::BackUp >
 DriveOnHeading ()
 A constructor for nav2_behaviors::DriveOnHeading.
 
Status onRun (const std::shared_ptr< const typename ActionT::Goal > command) override
 Initialization to run behavior. More...
 
Status onCycleUpdate () override
 Loop function to run behavior. More...
 
void onCleanup () override
 
void onActionCompletion () override
 
- Public Member Functions inherited from nav2_behaviors::TimedBehavior< ActionT >
 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 > 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 deactive Behavior and any threads involved in execution.
 
- Public Member Functions inherited from nav2_core::Behavior
virtual ~Behavior ()
 Virtual destructor.
 

Additional Inherited Members

- Public Types inherited from nav2_behaviors::TimedBehavior< ActionT >
using ActionServer = nav2_util::SimpleActionServer< ActionT >
 
- Public Types inherited from nav2_core::Behavior
using Ptr = std::shared_ptr< Behavior >
 
- Protected Member Functions inherited from nav2_behaviors::DriveOnHeading< nav2_msgs::action::BackUp >
bool isCollisionFree (const double &distance, 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< ActionT >
void execute ()
 
void stopRobot ()
 
- Protected Attributes inherited from nav2_behaviors::DriveOnHeading< nav2_msgs::action::BackUp >
ActionT::Feedback::SharedPtr feedback_
 
geometry_msgs::msg::PoseStamped initial_pose_
 
double command_x_
 
double command_speed_
 
rclcpp::Duration command_time_allowance_
 
rclcpp::Time end_time_
 
double simulate_ahead_time_
 
double acceleration_limit_
 
double deceleration_limit_
 
double minimum_speed_
 
double last_vel_
 
- Protected Attributes inherited from nav2_behaviors::TimedBehavior< ActionT >
rclcpp_lifecycle::LifecycleNode::WeakPtr node_
 
std::string behavior_name_
 
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr vel_pub_
 
std::shared_ptr< ActionServeraction_server_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckercollision_checker_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
double cycle_frequency_
 
double enabled_
 
std::string global_frame_
 
std::string robot_base_frame_
 
double transform_tolerance_
 
rclcpp::Duration elasped_time_ {0, 0}
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_ {rclcpp::get_logger("nav2_behaviors")}
 

Detailed Description

Definition at line 28 of file back_up.hpp.


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