Template Class TimedBehavior

Inheritance Relationships

Base Type

  • public nav2_core::Behavior

Derived Type

Class Documentation

template<typename ActionT>
class TimedBehavior : public nav2_core::Behavior

Subclassed by nav2_behaviors::DriveOnHeading< nav2_msgs::action::BackUp >

Public Types

using ActionServer = nav2_util::SimpleActionServer<ActionT>

Public Functions

inline TimedBehavior()

A TimedBehavior constructor.

virtual ~TimedBehavior() = default
virtual Status onRun(const std::shared_ptr<const typename ActionT::Goal> command) = 0
virtual Status onCycleUpdate() = 0
inline virtual void onConfigure()
inline virtual void onCleanup()
inline virtual void onActionCompletion()
inline 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
inline void cleanup() override
inline void activate() override
inline void deactivate() override

Protected Functions

inline void execute()
inline void stopRobot()

Protected Attributes

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 steady_clock_ = {RCL_STEADY_TIME}
rclcpp::Logger logger_ = {rclcpp::get_logger("nav2_behaviors")}