Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Classes | Public Member Functions | List of all members
dwb_critics::OscillationCritic Class Reference

Checks to see whether the sign of the commanded velocity flips frequently. More...

#include <nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp>

Inheritance diagram for dwb_critics::OscillationCritic:
Inheritance graph
[legend]
Collaboration diagram for dwb_critics::OscillationCritic:
Collaboration graph
[legend]

Public Member Functions

void onInit () override
 
bool prepare (const geometry_msgs::msg::Pose2D &pose, const nav_2d_msgs::msg::Twist2D &vel, const geometry_msgs::msg::Pose2D &goal, const nav_2d_msgs::msg::Path2D &global_plan) override
 Prior to evaluating any trajectories, look at contextual information constant across all trajectories. More...
 
double scoreTrajectory (const dwb_msgs::msg::Trajectory2D &traj) override
 Return a raw score for the given trajectory. More...
 
void reset () override
 Reset the state of the critic. More...
 
void debrief (const nav_2d_msgs::msg::Twist2D &cmd_vel) override
 debrief informs the critic what the chosen cmd_vel was (if it cares)
 
- Public Member Functions inherited from dwb_core::TrajectoryCritic
void initialize (const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &name, const std::string &ns, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
 Initialize the critic with appropriate pointers and parameters. More...
 
virtual void addCriticVisualization (std::vector< std::pair< std::string, std::vector< float >>> &)
 Add information to the given pointcloud for debugging costmap-grid based scores. More...
 
std::string getName ()
 
virtual double getScale () const
 
void setScale (const double scale)
 

Additional Inherited Members

- Public Types inherited from dwb_core::TrajectoryCritic
using Ptr = std::shared_ptr< dwb_core::TrajectoryCritic >
 
- Protected Attributes inherited from dwb_core::TrajectoryCritic
std::string name_
 
std::string dwb_plugin_name_
 
std::shared_ptr< nav2_costmap_2d::Costmap2DROScostmap_ros_
 
double scale_
 
rclcpp_lifecycle::LifecycleNode::WeakPtr node_
 

Detailed Description

Checks to see whether the sign of the commanded velocity flips frequently.

This critic figures out if the commanded trajectories are oscillating by seeing if one of the dimensions (x,y,theta) flips from positive to negative and then back (or vice versa) without moving sufficiently far or waiting sufficiently long.

Scenario 1: Robot moves one meter forward, and then two millimeters backward. Another forward motion would be considered oscillating, since the x dimension would then flip from positive to negative and then back to negative. Hence, when scoring different trajectories, positive velocity commands will get the oscillation_score (-5.0, or invalid) and only negative velocity commands will be considered valid.

Scenario 2: Robot moves one meter forward, and then one meter backward. The robot has thus moved one meter since flipping the sign of the x direction, which is greater than our oscillation_reset_dist, so its not considered oscillating, so all trajectories are considered valid.

Note: The critic will only check oscillations in the x dimension while it exceeds a particular value (x_only_threshold_). If it dips below that magnitude, it will also check for oscillations in the y and theta dimensions. If x_only_threshold_ is negative, then the critic will always check all dimensions.

Implementation Details: The critic saves the robot's current position when it prepares, and what the actual commanded velocity was during the debrief step. Upon debriefing, if the sign of any of dimensions has flipped since the last command, the position is saved as prev_stationary_pose_.

If the linear or angular distance from prev_stationary_pose_ to the current pose exceeds the limits, the oscillation flags are reset so the previous sign change is no longer remembered. This assumes that oscillation_reset_dist_ or oscillation_reset_angle_ are positive. Otherwise, it uses a time based delay reset function.

Definition at line 82 of file oscillation.hpp.

Member Function Documentation

◆ onInit()

void dwb_critics::OscillationCritic::onInit ( )
overridevirtual

Historical Parameter Loading If x_only_threshold is set, use that. If min_speed_xy is set in the namespace (as it is often used for trajectory generation), use that. If min_trans_vel is set in the namespace, as it used to be used for trajectory generation, complain then use that. Otherwise, set x_only_threshold_ to 0.05

Reimplemented from dwb_core::TrajectoryCritic.

Definition at line 92 of file oscillation.cpp.

References reset().

Here is the call graph for this function:

◆ prepare()

bool dwb_critics::OscillationCritic::prepare ( const geometry_msgs::msg::Pose2D &  ,
const nav_2d_msgs::msg::Twist2D &  ,
const geometry_msgs::msg::Pose2D &  ,
const nav_2d_msgs::msg::Path2D &   
)
overridevirtual

Prior to evaluating any trajectories, look at contextual information constant across all trajectories.

Subclasses may overwrite. Return false in case there is any error.

Parameters
poseCurrent pose (costmap frame)
velCurrent velocity
goalThe final goal (costmap frame)
global_planTransformed global plan in costmap frame, possibly cropped to nearby points

Reimplemented from dwb_core::TrajectoryCritic.

Definition at line 150 of file oscillation.cpp.

◆ reset()

void dwb_critics::OscillationCritic::reset ( )
overridevirtual

Reset the state of the critic.

Reset is called when the planner receives a new global plan. This can be used to discard information specific to one plan.

Reimplemented from dwb_core::TrajectoryCritic.

Definition at line 201 of file oscillation.cpp.

Referenced by debrief(), and onInit().

Here is the caller graph for this function:

◆ scoreTrajectory()

double dwb_critics::OscillationCritic::scoreTrajectory ( const dwb_msgs::msg::Trajectory2D &  traj)
overridevirtual

Return a raw score for the given trajectory.

scores < 0 are considered invalid/errors, such as collisions This is the raw score in that the scale should not be applied to it.

Implements dwb_core::TrajectoryCritic.

Definition at line 222 of file oscillation.cpp.


The documentation for this class was generated from the following files: