Class HomingLocalPlanner
Defined in File homing_local_planner.hpp
Inheritance Relationships
Base Type
public nav2_core::Controller
Class Documentation
-
class HomingLocalPlanner : public nav2_core::Controller
Public Functions
-
HomingLocalPlanner() = default
-
~HomingLocalPlanner() override = default
-
void cleanup() override
-
void activate() override
-
void deactivate() override
-
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
-
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
Protected Functions
-
template<typename P1, typename P2>
inline double distancePoints2d(const P1 &point1, const P2 &point2)
-
void simplifyGlobalPlan(std::vector<geometry_msgs::msg::PoseStamped> &plan, double simplify_separation)
-
void smoothPlan2d(std::vector<geometry_msgs::msg::PoseStamped> &global_plan_vec)
-
void updateViaPointsContainer(const std::vector<geometry_msgs::msg::PoseStamped> &transformed_plan, double min_separation_via, double min_separation_goal)
-
double clip(double value, double lower, double upper)
-
void cart2Pol(double x, double y, double °, double &dist)
-
double angDiff(double alpha, double beta)
-
void poseError(double dx, double dy, double dyaw, double &rho, double &alpha, double &phi)
-
void homingControl(double rho, double alpha, double phi, double &v, double &omega)
-
Eigen::Vector3d R2ypr(const Eigen::Matrix3d &R)
-
double checkCollision(const std::vector<geometry_msgs::msg::PoseStamped> &transformed_plan, double check_dist)
-
HomingLocalPlanner() = default