Class SimpleProgressChecker

Inheritance Relationships

Base Type

  • public nav2_core::ProgressChecker

Derived Type

Class Documentation

class SimpleProgressChecker : public nav2_core::ProgressChecker

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

Subclassed by nav2_controller::PoseProgressChecker

Public Functions

virtual void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name) override
virtual bool check(geometry_msgs::msg::PoseStamped &current_pose) override
virtual void reset() 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

void resetBaselinePose(const geometry_msgs::msg::Pose2D &pose)

Resets baseline pose with the current pose of the robot.

Parameters:

pose – Current pose of the robot

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

rclcpp::Clock::SharedPtr clock_
double radius_
rclcpp::Duration time_allowance_ = {0, 0}
geometry_msgs::msg::Pose2D baseline_pose_
rclcpp::Time baseline_time_
bool baseline_pose_set_ = {false}
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
std::string plugin_name_

Protected Static Functions

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