SMACC2
|
#include <pure_spinning_local_planner.hpp>
Public Member Functions | |
PureSpinningLocalPlanner () | |
virtual | ~PureSpinningLocalPlanner () |
void | configure (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override |
void | activate () override |
void | deactivate () override |
void | cleanup () override |
void | setPlan (const nav_msgs::msg::Path &path) override |
nav2_core setPlan - Sets the global plan | |
virtual geometry_msgs::msg::TwistStamped | computeVelocityCommands (const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker) override |
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity | |
bool | isGoalReached () |
virtual void | setSpeedLimit (const double &speed_limit, const bool &percentage) override |
Private Member Functions | |
void | updateParameters () |
void | publishGoalMarker (double x, double y, double phi) |
Private Attributes | |
nav2_util::LifecycleNode::SharedPtr | nh_ |
std::string | name_ |
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmapRos_ |
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > | goalMarkerPublisher_ |
std::vector< geometry_msgs::msg::PoseStamped > | plan_ |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
double | k_betta_ |
bool | goalReached_ |
int | currentPoseIndex_ |
rad | yaw_goal_tolerance_ |
rad | intermediate_goal_yaw_tolerance_ |
rad_s | max_angular_z_speed_ |
double | transform_tolerance_ |
bool | use_shortest_angular_distance_ |
Definition at line 41 of file pure_spinning_local_planner.hpp.
cl_nav2z::pure_spinning_local_planner::PureSpinningLocalPlanner::PureSpinningLocalPlanner | ( | ) |
Definition at line 35 of file pure_spinning_local_planner.cpp.
|
virtual |
Definition at line 37 of file pure_spinning_local_planner.cpp.
|
override |
Definition at line 39 of file pure_spinning_local_planner.cpp.
References nh_, and updateParameters().
|
override |
Definition at line 47 of file pure_spinning_local_planner.cpp.
References currentPoseIndex_, plan_, and yaw_goal_tolerance_.
|
overridevirtual |
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity
It is presumed that the global plan is already set.
This is mostly a wrapper for the protected computeVelocityCommands function which has additional debugging info.
pose | Current robot pose |
velocity | Current robot velocity |
Definition at line 88 of file pure_spinning_local_planner.cpp.
References currentPoseIndex_, goalReached_, intermediate_goal_yaw_tolerance_, k_betta_, max_angular_z_speed_, nh_, plan_, updateParameters(), use_shortest_angular_distance_, and yaw_goal_tolerance_.
|
override |
Definition at line 54 of file pure_spinning_local_planner.cpp.
References costmapRos_, declareOrSet(), intermediate_goal_yaw_tolerance_, k_betta_, max_angular_z_speed_, name_, nh_, tf_, transform_tolerance_, use_shortest_angular_distance_, and yaw_goal_tolerance_.
|
override |
Definition at line 45 of file pure_spinning_local_planner.cpp.
bool cl_nav2z::pure_spinning_local_planner::PureSpinningLocalPlanner::isGoalReached | ( | ) |
|
private |
|
override |
nav2_core setPlan - Sets the global plan
path | The global plan |
Definition at line 192 of file pure_spinning_local_planner.cpp.
References costmapRos_, currentPoseIndex_, goalReached_, nh_, plan_, tf_, and transform_tolerance_.
|
overridevirtual |
Definition at line 181 of file pure_spinning_local_planner.cpp.
References nh_.
|
private |
Definition at line 79 of file pure_spinning_local_planner.cpp.
References intermediate_goal_yaw_tolerance_, k_betta_, max_angular_z_speed_, name_, nh_, transform_tolerance_, cl_nav2z::pure_spinning_local_planner::tryGetOrSet(), and use_shortest_angular_distance_.
Referenced by activate(), and computeVelocityCommands().
|
private |
Definition at line 90 of file pure_spinning_local_planner.hpp.
Referenced by configure(), and setPlan().
|
private |
Definition at line 101 of file pure_spinning_local_planner.hpp.
Referenced by cleanup(), computeVelocityCommands(), and setPlan().
|
private |
Definition at line 93 of file pure_spinning_local_planner.hpp.
|
private |
Definition at line 100 of file pure_spinning_local_planner.hpp.
Referenced by computeVelocityCommands(), isGoalReached(), and setPlan().
|
private |
Definition at line 103 of file pure_spinning_local_planner.hpp.
Referenced by computeVelocityCommands(), configure(), and updateParameters().
|
private |
Definition at line 99 of file pure_spinning_local_planner.hpp.
Referenced by computeVelocityCommands(), configure(), and updateParameters().
|
private |
Definition at line 104 of file pure_spinning_local_planner.hpp.
Referenced by computeVelocityCommands(), configure(), and updateParameters().
|
private |
Definition at line 87 of file pure_spinning_local_planner.hpp.
Referenced by configure(), and updateParameters().
|
private |
Definition at line 86 of file pure_spinning_local_planner.hpp.
Referenced by activate(), computeVelocityCommands(), configure(), setPlan(), setSpeedLimit(), and updateParameters().
|
private |
Definition at line 95 of file pure_spinning_local_planner.hpp.
Referenced by cleanup(), computeVelocityCommands(), and setPlan().
|
private |
Definition at line 97 of file pure_spinning_local_planner.hpp.
Referenced by configure(), and setPlan().
|
private |
Definition at line 105 of file pure_spinning_local_planner.hpp.
Referenced by configure(), setPlan(), and updateParameters().
|
private |
Definition at line 106 of file pure_spinning_local_planner.hpp.
Referenced by computeVelocityCommands(), configure(), and updateParameters().
|
private |
Definition at line 102 of file pure_spinning_local_planner.hpp.
Referenced by cleanup(), computeVelocityCommands(), and configure().