Classes | Public Member Functions | Protected Member Functions | Protected Attributes
dwb_critics::OscillationCritic Class Reference

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

#include <oscillation.h>

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

List of all members.

Classes

class  CommandTrend
 Helper class for performing the same logic on the x,y and theta dimensions. More...

Public Member Functions

void debrief (const nav_2d_msgs::Twist2D &cmd_vel) override
void onInit () override
bool prepare (const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override
void reset () override
double scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override

Protected Member Functions

bool resetAvailable ()
 Return true if the robot has travelled far enough or waited long enough.
bool setOscillationFlags (const nav_2d_msgs::Twist2D &cmd_vel)
 Given a command that has been selected, track each component's sign for oscillations.

Protected Attributes

double oscillation_reset_angle_
double oscillation_reset_dist_
double oscillation_reset_dist_sq_
double oscillation_reset_time_
geometry_msgs::Pose2D pose_
ros::Time prev_reset_time_
geometry_msgs::Pose2D prev_stationary_pose_
CommandTrend theta_trend_
double x_only_threshold_
CommandTrend x_trend_
CommandTrend y_trend_

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 79 of file oscillation.h.


Member Function Documentation

void dwb_critics::OscillationCritic::debrief ( const nav_2d_msgs::Twist2D &  cmd_vel) [override, virtual]

Reimplemented from dwb_local_planner::TrajectoryCritic.

Definition at line 140 of file oscillation.cpp.

void dwb_critics::OscillationCritic::onInit ( ) [override, virtual]

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_local_planner::TrajectoryCritic.

Definition at line 94 of file oscillation.cpp.

bool dwb_critics::OscillationCritic::prepare ( const geometry_msgs::Pose2D &  pose,
const nav_2d_msgs::Twist2D &  vel,
const geometry_msgs::Pose2D &  goal,
const nav_2d_msgs::Path2D &  global_plan 
) [override, virtual]

Reimplemented from dwb_local_planner::TrajectoryCritic.

Definition at line 131 of file oscillation.cpp.

void dwb_critics::OscillationCritic::reset ( ) [override, virtual]

Reimplemented from dwb_local_planner::TrajectoryCritic.

Definition at line 190 of file oscillation.cpp.

Return true if the robot has travelled far enough or waited long enough.

Definition at line 159 of file oscillation.cpp.

double dwb_critics::OscillationCritic::scoreTrajectory ( const dwb_msgs::Trajectory2D &  traj) [override, virtual]

Implements dwb_local_planner::TrajectoryCritic.

Definition at line 212 of file oscillation.cpp.

bool dwb_critics::OscillationCritic::setOscillationFlags ( const nav_2d_msgs::Twist2D &  cmd_vel) [protected]

Given a command that has been selected, track each component's sign for oscillations.

Parameters:
cmd_velThe command velocity selected by the algorithm
Returns:
True if the sign on any of the components flipped

Definition at line 197 of file oscillation.cpp.


Member Data Documentation

Definition at line 141 of file oscillation.h.

Definition at line 141 of file oscillation.h.

Definition at line 145 of file oscillation.h.

Definition at line 142 of file oscillation.h.

geometry_msgs::Pose2D dwb_critics::OscillationCritic::pose_ [protected]

Definition at line 148 of file oscillation.h.

Definition at line 150 of file oscillation.h.

geometry_msgs::Pose2D dwb_critics::OscillationCritic::prev_stationary_pose_ [protected]

Definition at line 148 of file oscillation.h.

Definition at line 140 of file oscillation.h.

Definition at line 141 of file oscillation.h.

Definition at line 140 of file oscillation.h.

Definition at line 140 of file oscillation.h.


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


dwb_critics
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:09:47