|
|
| TimedBehavior () |
| | A TimedBehavior constructor.
|
| |
|
virtual Status | onRun (const std::shared_ptr< const typename ActionT::Goal > command)=0 |
| |
|
virtual Status | onCycleUpdate ()=0 |
| |
|
virtual void | onConfigure () |
| |
|
virtual void | onCleanup () |
| |
|
virtual void | onActionCompletion () |
| |
| 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.
|
| |
|
virtual | ~Behavior () |
| | Virtual destructor.
|
| |
|
|
void | execute () |
| |
|
void | stopRobot () |
| |
|
|
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
| |
|
std::string | behavior_name_ |
| |
|
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr | vel_pub_ |
| |
|
std::shared_ptr< ActionServer > | action_server_ |
| |
|
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | collision_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")} |
| |
template<typename ActionT>
class nav2_behaviors::TimedBehavior< ActionT >
Definition at line 55 of file timed_behavior.hpp.
◆ configure()
template<typename ActionT >
- Parameters
-
| parent | pointer to user's node |
| name | The name of this planner |
| tf | A pointer to a TF buffer |
| costmap_ros | A pointer to the costmap |
Implements nav2_core::Behavior.
Definition at line 104 of file timed_behavior.hpp.
The documentation for this class was generated from the following file: