Class PoseProgressChecker

Inheritance Relationships

Base Type

Class Documentation

class PoseProgressChecker : public nav2_controller::SimpleProgressChecker

This plugin is used to check the position and the angle of the robot to make sure that it is actually progressing or rotating towards a goal.

Public Functions

void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override
bool check(geometry_msgs::msg::PoseStamped &current_pose) override

Protected Functions

bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D &pose)

Calculates robots movement from baseline pose.

Parameters:

pose – Current pose of the robot

Returns:

true, if movement is greater than radius_, or false

rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

Callback executed when a paramter change is detected.

Parameters:

parameters – list of changed parameters

Protected Attributes

double required_movement_angle_
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
std::string plugin_name_

Protected Static Functions

static double poseAngleDistance(const geometry_msgs::msg::Pose2D&, const geometry_msgs::msg::Pose2D&)