Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
NavigationScoringPlugin Class Reference

A plugin for computing the score of the navigation task. This plugin derives from the generic ScoringPlugin class. Check out that plugin for other required SDF elements. This plugin requires the following SDF parameters: More...

#include <navigation_scoring_plugin.hh>

Inheritance diagram for NavigationScoringPlugin:
Inheritance graph
[legend]

Classes

class  Gate
 A gate that is part of the navigation challenge. More...
 

Public Member Functions

void Load (gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
 
 NavigationScoringPlugin ()
 
- Public Member Functions inherited from ScoringPlugin
void Exit ()
 Shutdown Gazebo and ROS. More...
 
 ScoringPlugin ()
 Class constructor. More...
 

Private Types

enum  GateState {
  GateState::VEHICLE_OUTSIDE, GateState::VEHICLE_BEFORE, GateState::VEHICLE_AFTER, GateState::CROSSED,
  GateState::INVALID
}
 All gate states. More...
 

Private Member Functions

bool AddGate (const std::string &_leftMarkerName, const std::string &_rightMarkerName)
 Register a new gate. More...
 
void Fail ()
 Set the score to 0 and change to state to "finish". More...
 
void OnCollision () override
 Callback executed when a collision is detected for the WAMV. More...
 
bool ParseGates (sdf::ElementPtr _sdf)
 Parse the gates from SDF. More...
 
void Update ()
 Callback executed at every world update. More...
 

Private Attributes

gazebo::physics::ModelPtr course
 
std::vector< Gategates
 All the gates. More...
 
unsigned int numCollisions = 0
 The number of WAM-V collisions. More...
 
int numGates
 Number of gates. More...
 
double obstaclePenalty = 10.0
 Number of points deducted per collision. More...
 
gazebo::event::ConnectionPtr updateConnection
 Pointer to the update event connection. More...
 

Additional Inherited Members

- Protected Member Functions inherited from ScoringPlugin
gazebo::common::Time ElapsedTime () const
 Elapsed time in the running state. More...
 
void Finish ()
 Finish the current task. This will set the "finished" flag in the task message to true. More...
 
double GetRunningStateDuration ()
 Get running duration. More...
 
double GetTimeoutScore ()
 Get the timeoutScore. More...
 
void Load (gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
 
virtual void ReleaseVehicle ()
 Tries to release the vehicle in case is locked. More...
 
gazebo::common::Time RemainingTime () const
 Remaining time in the running state. More...
 
double Score () const
 Get the current score. More...
 
void SetScore (double _newScore)
 Set the score. More...
 
void SetTimeoutScore (double _timeoutScore)
 Set the score in case of timeout. More...
 
std::string TaskName () const
 Get the task name. More...
 
std::string TaskState () const
 Get the task state. More...
 
- Protected Attributes inherited from ScoringPlugin
gazebo::common::Time lastCollisionTime
 Last collision time. More...
 
double runningStateDuration = 300.0
 Duration (seconds) of the running state (max task time). More...
 
vrx_gazebo::Task taskMsg
 The next task message to be published. More...
 
std::string taskName = "undefined"
 The name of the task. More...
 
ros::Publisher taskPub
 Publisher for the task state. More...
 
gazebo::physics::ModelPtr vehicleModel
 Pointer to the vehicle to score. More...
 
std::string vehicleName
 The name of the vehicle to score. More...
 
gazebo::physics::WorldPtr world
 A world pointer. More...
 

Detailed Description

A plugin for computing the score of the navigation task. This plugin derives from the generic ScoringPlugin class. Check out that plugin for other required SDF elements. This plugin requires the following SDF parameters:

<obstacle_penalty>: Specifies how many points are deducted per collision. <gates>: Specifies the collection of gates delimiting the course.

Each gate accepts the following elements:

<gate>: A gate is delimited by two markers (left and right). The vessel should pass through the gate with the markers on the defined right and left sides. E.g.:

<left_marker>: The name of the marker that should stay on the left side of the vessel. <right_marker> The name of the marker that should stay on the right side of the vessel.

Here's an example: <plugin name="navigation_scoring_plugin" filename="libnavigation_scoring_plugin.so"> <vehicle>wamv</vehicle> <task_name>navigation_scoring_plugin</task_name> <course_name>vrx_navigation_course</course_name> <obstacle_penalty>10</obstable_penalty> <gates> <gate> <left_marker>red_bound_0</left_marker> <right_marker>green_bound_0</right_marker> </gate> <gate> <left_marker>red_bound_1</left_marker> <right_marker>green_bound_1</right_marker> </gate> <gate> <left_marker>red_bound_2</left_marker> <right_marker>green_bound_2</right_marker> </gate> <gate> <left_marker>red_bound_3</left_marker> <right_marker>green_bound_3</right_marker> </gate> <gate> <left_marker>red_bound_4</left_marker> <right_marker>green_bound_4</right_marker> </gate> <gate> <left_marker>red_bound_5</left_marker> <right_marker>green_bound_5</right_marker> </gate> <gate> <left_marker>red_bound_6</left_marker> <right_marker>green_bound_6</right_marker> </gate> </gates> </plugin>

Definition at line 87 of file navigation_scoring_plugin.hh.

Member Enumeration Documentation

All gate states.

Enumerator
VEHICLE_OUTSIDE 

Not "in" the gate.

VEHICLE_BEFORE 

Before the gate.

VEHICLE_AFTER 

After the gate.

CROSSED 

Gate crossed!

INVALID 

Gate invalid. E.g.: if crossed in the wrong direction.

Definition at line 90 of file navigation_scoring_plugin.hh.

Constructor & Destructor Documentation

NavigationScoringPlugin::NavigationScoringPlugin ( )

Definition at line 91 of file navigation_scoring_plugin.cc.

Member Function Documentation

bool NavigationScoringPlugin::AddGate ( const std::string &  _leftMarkerName,
const std::string &  _rightMarkerName 
)
private

Register a new gate.

Parameters
[in]_leftMarkerNameThe name of the left marker.
[in]_rightMarkerNameThe name of the right marker.
Returns
True when the gate has been registered or false otherwise.

Definition at line 203 of file navigation_scoring_plugin.cc.

void NavigationScoringPlugin::Fail ( )
private

Set the score to 0 and change to state to "finish".

Definition at line 316 of file navigation_scoring_plugin.cc.

void NavigationScoringPlugin::Load ( gazebo::physics::WorldPtr  _world,
sdf::ElementPtr  _sdf 
)

Definition at line 97 of file navigation_scoring_plugin.cc.

void NavigationScoringPlugin::OnCollision ( )
overrideprivatevirtual

Callback executed when a collision is detected for the WAMV.

Reimplemented from ScoringPlugin.

Definition at line 323 of file navigation_scoring_plugin.cc.

bool NavigationScoringPlugin::ParseGates ( sdf::ElementPtr  _sdf)
private

Parse the gates from SDF.

Parameters
[in]_sdfThe current SDF element.
Returns
True when the gates were successfully parsed or false othwerwise.

Definition at line 156 of file navigation_scoring_plugin.cc.

void NavigationScoringPlugin::Update ( )
private

Callback executed at every world update.

Definition at line 235 of file navigation_scoring_plugin.cc.

Member Data Documentation

gazebo::physics::ModelPtr NavigationScoringPlugin::course
private

Definition at line 173 of file navigation_scoring_plugin.hh.

std::vector<Gate> NavigationScoringPlugin::gates
private

All the gates.

Definition at line 176 of file navigation_scoring_plugin.hh.

unsigned int NavigationScoringPlugin::numCollisions = 0
private

The number of WAM-V collisions.

Definition at line 185 of file navigation_scoring_plugin.hh.

int NavigationScoringPlugin::numGates
private

Number of gates.

Definition at line 179 of file navigation_scoring_plugin.hh.

double NavigationScoringPlugin::obstaclePenalty = 10.0
private

Number of points deducted per collision.

Definition at line 188 of file navigation_scoring_plugin.hh.

gazebo::event::ConnectionPtr NavigationScoringPlugin::updateConnection
private

Pointer to the update event connection.

Definition at line 182 of file navigation_scoring_plugin.hh.


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


vrx_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:56