Public Member Functions | Protected Member Functions | Protected Attributes
mir_dwb_critics::PathProgressCritic Class Reference

Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal. More...

#include <path_progress.h>

Inheritance diagram for mir_dwb_critics::PathProgressCritic:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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

unsigned int getGoalIndex (const std::vector< geometry_msgs::Pose2D > &plan, unsigned int start_index, unsigned int last_valid_index) const
bool getGoalPose (const geometry_msgs::Pose2D &robot_pose, const nav_2d_msgs::Path2D &global_plan, unsigned int &x, unsigned int &y, double &desired_angle)

Protected Attributes

double angle_threshold_
double desired_angle_
double heading_scale_
std::vector
< geometry_msgs::Pose2D > 
reached_intermediate_goals_
double xy_local_goal_tolerance_

Detailed Description

Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal.

This trajectory critic helps ensure progress along the global path. It calculates an intermediate goal that is as far as possible along the global path as long as the path continues to move in one direction (+/- angle_threshold).

Definition at line 50 of file path_progress.h.


Member Function Documentation

unsigned int mir_dwb_critics::PathProgressCritic::getGoalIndex ( const std::vector< geometry_msgs::Pose2D > &  plan,
unsigned int  start_index,
unsigned int  last_valid_index 
) const [protected]

Definition at line 190 of file path_progress.cpp.

bool mir_dwb_critics::PathProgressCritic::getGoalPose ( const geometry_msgs::Pose2D &  robot_pose,
const nav_2d_msgs::Path2D &  global_plan,
unsigned int &  x,
unsigned int &  y,
double &  desired_angle 
) [protected]

Definition at line 82 of file path_progress.cpp.

void mir_dwb_critics::PathProgressCritic::onInit ( ) [override, virtual]

Reimplemented from dwb_critics::MapGridCritic.

Definition at line 60 of file path_progress.cpp.

bool mir_dwb_critics::PathProgressCritic::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 41 of file path_progress.cpp.

void mir_dwb_critics::PathProgressCritic::reset ( ) [override, virtual]

Reimplemented from dwb_critics::MapGridCritic.

Definition at line 70 of file path_progress.cpp.

double mir_dwb_critics::PathProgressCritic::scoreTrajectory ( const dwb_msgs::Trajectory2D &  traj) [override, virtual]

Reimplemented from dwb_critics::MapGridCritic.

Definition at line 74 of file path_progress.cpp.


Member Data Documentation

Definition at line 73 of file path_progress.h.

Definition at line 77 of file path_progress.h.

Definition at line 74 of file path_progress.h.

std::vector<geometry_msgs::Pose2D> mir_dwb_critics::PathProgressCritic::reached_intermediate_goals_ [protected]

Definition at line 76 of file path_progress.h.

Definition at line 72 of file path_progress.h.


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


mir_dwb_critics
Author(s): Martin Günther
autogenerated on Wed May 8 2019 02:53:29