An action server behavior for spinning in.
More...
#include <nav2_behaviors/include/nav2_behaviors/plugins/spin.hpp>
|
|
using | SpinActionGoal = SpinAction::Goal |
| |
|
using | SpinActionResult = SpinAction::Result |
| |
|
using | ActionServer = nav2_util::SimpleActionServer< SpinAction > |
| |
|
using | Ptr = std::shared_ptr< Behavior > |
| |
|
|
| Spin () |
| | A constructor for nav2_behaviors::Spin.
|
| |
| ResultStatus | onRun (const std::shared_ptr< const SpinActionGoal > command) override |
| | Initialization to run behavior. More...
|
| |
|
void | onConfigure () override |
| | Configuration of behavior action.
|
| |
| ResultStatus | onCycleUpdate () override |
| | Loop function to run behavior. More...
|
| |
| CostmapInfoType | getResourceInfo () override |
| | Method to determine the required costmap info. More...
|
| |
|
| TimedBehavior () |
| | A TimedBehavior constructor.
|
| |
|
virtual ResultStatus | onRun (const std::shared_ptr< const typename ActionT::Goal > command)=0 |
| |
|
virtual void | onCleanup () |
| |
|
virtual void | onActionCompletion (std::shared_ptr< typename ActionT::Result >) |
| |
| 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.
|
| |
|
virtual | ~Behavior () |
| | Virtual destructor.
|
| |
|
| 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 | execute () |
| |
|
void | stopRobot () |
| |
|
|
SpinAction::Feedback::SharedPtr | feedback_ |
| |
|
double | min_rotational_vel_ |
| |
|
double | max_rotational_vel_ |
| |
|
double | rotational_acc_lim_ |
| |
|
double | cmd_yaw_ |
| |
|
bool | cmd_disable_collision_checks_ |
| |
|
double | prev_yaw_ |
| |
|
double | relative_yaw_ |
| |
|
double | simulate_ahead_time_ |
| |
|
rclcpp::Duration | command_time_allowance_ {0, 0} |
| |
|
rclcpp::Time | end_time_ |
| |
|
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
| |
|
std::string | behavior_name_ |
| |
|
std::unique_ptr< nav2_util::TwistPublisher > | vel_pub_ |
| |
|
std::shared_ptr< ActionServer > | action_server_ |
| |
|
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | local_collision_checker_ |
| |
|
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | global_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_ |
| |
An action server behavior for spinning in.
Definition at line 35 of file spin.hpp.
◆ getResourceInfo()
| CostmapInfoType nav2_behaviors::Spin::getResourceInfo |
( |
| ) |
|
|
inlineoverridevirtual |
Method to determine the required costmap info.
- Returns
- costmap resources needed
Implements nav2_core::Behavior.
Definition at line 71 of file spin.hpp.
◆ isCollisionFree()
| bool nav2_behaviors::Spin::isCollisionFree |
( |
const double & |
distance, |
|
|
const geometry_msgs::msg::Twist & |
cmd_vel, |
|
|
geometry_msgs::msg::Pose2D & |
pose2d |
|
) |
| |
|
protected |
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
Definition at line 165 of file spin.cpp.
Referenced by onCycleUpdate().
◆ onCycleUpdate()
◆ onRun()
| ResultStatus nav2_behaviors::Spin::onRun |
( |
const std::shared_ptr< const SpinActionGoal > |
command | ) |
|
|
override |
Initialization to run behavior.
- Parameters
-
- Returns
- Status of behavior
Definition at line 74 of file spin.cpp.
The documentation for this class was generated from the following files:
- nav2_behaviors/include/nav2_behaviors/plugins/spin.hpp
- nav2_behaviors/plugins/spin.cpp