Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
ScoringPlugin Class Reference

A plugin that provides common functionality to any scoring plugin. This plugin defines four different task states: More...

#include <scoring_plugin.hh>

Inheritance diagram for ScoringPlugin:
Inheritance graph
[legend]

Public Member Functions

 ScoringPlugin ()=default
 Class constructor. More...
 

Protected Member Functions

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...
 
void Load (gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
 
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...
 
std::string TaskName () const
 Get the task name. More...
 
std::string TaskState () const
 Get the task state. More...
 

Protected Attributes

double score = 0.0
 The score. More...
 
std::string taskName = "undefined"
 The name of the task. More...
 
std::string topic = "/vmrc/task/info"
 Topic where the task stats are published. More...
 
gazebo::event::ConnectionPtr updateConnection
 Pointer to the update event connection. 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...
 

Private Member Functions

virtual void OnFinished ()
 Callback executed when the task state transition into "finished". More...
 
virtual void OnReady ()
 Callback executed when the task state transition into "ready". More...
 
virtual void OnRunning ()
 Callback executed when the task state transition into "running". More...
 
bool ParseJoints ()
 Parse the joints section of the SDF block. More...
 
bool ParseSDFParameters ()
 Parse all SDF parameters. More...
 
void PublishStats ()
 Publish the task stats over a ROS topic. More...
 
void ReleaseVehicle ()
 Tries to release the vehicle in case is locked. More...
 
void Update ()
 Callback executed at every world update. More...
 
void UpdateTaskMessage ()
 Update the task stats message. More...
 
void UpdateTaskState ()
 Update the state of the current task. More...
 
void UpdateTime ()
 Update all time-related variables. More...
 

Private Attributes

gazebo::common::Time currentTime
 Current time (simulation). More...
 
gazebo::common::Time elapsedTime
 
gazebo::common::Time finishTime
 Absolute time specifying the start of the finish state. More...
 
double initialStateDuration = 30.0
 Duration (seconds) of the initial state. More...
 
gazebo::common::Time lastStatsSent = gazebo::common::Time::Zero
 Time at which the last message was sent. More...
 
std::vector< std::string > lockJointNames
 The name of the joints to be dettached during ReleaseVehicle(). More...
 
double readyStateDuration = 60.0
 Duration (seconds) of the ready state. More...
 
gazebo::common::Time readyTime
 Absolute time specifying the start of the ready state. More...
 
gazebo::common::Time remainingTime
 Remaining time since the start of the task (running state). More...
 
std::unique_ptr< ros::NodeHandlerosNode
 ROS node handle. More...
 
double runningStateDuration = 300.0
 Duration (seconds) of the running state (max task time). More...
 
gazebo::common::Time runningTime
 Absolute time specifying the start of the running state. More...
 
sdf::ElementPtr sdf
 Pointer to the SDF plugin element. More...
 
vmrc_gazebo::Task taskMsg
 The next task message to be published. More...
 
ros::Publisher taskPub
 Publisher for the task state. More...
 
std::string taskState = "initial"
 The task state. More...
 
bool timedOut = false
 Whether the current task has timed out or not. More...
 

Detailed Description

A plugin that provides common functionality to any scoring plugin. This plugin defines four different task states:

The plugin also exposes a pair of methods [Set]Score() for setting and getting a score.

Derived plugins can also override the OnReady(), OnRunning(), and OnFinished() to be notified when the task transitions into the "ready". "running" or "finished" states respectively.

The plugin publishes task information on a ROS topic at 1Hz.

This plugin uses the following SDF parameters:

<vehicle>: Required parameter (string type) with the name of the main vehicle to be under control during the task.

<task_name>: Required parameter specifying the task name (string type).

<topic>: Optional parameter (string type) containing the ROS topic name to publish the task stats. The default topic name is /vmrc/task/info .

<initial_state_duration>: Optional parameter (double type) specifying the amount of seconds that the plugin will be in the "initial" state.

<ready_state_duration>: Optional parameter (double type) specifying the amount of seconds that the plugin will be in the "ready" state.

<running_state_duration>: Optional parameter (double type) specifying the amount of maximum seconds that the plugin will be in the "running" state. Note that this parameter specifies the maximum task time.

<release_joints>: Optional element specifying the collection of joints that should be dettached when transitioning to the "ready" state.

This block should contain at least one of these blocks: <joint>: This block should contain a <name> element with the name of the joint to release.

Here's an example: <plugin name="scoring_plugin" filename="libscoring_plugin.so"> <vehicle>wamv</vehicle> <task_name>navigation_course</task_name> <initial_state_duration>10</initial_state_duration> <ready_state_duration>10</ready_state_duration> <running_state_duration>30</running_state_duration> <release_joints> <joint> <name>wamv_external_pivot_joint</name> </joint> <joint> <name>wamv_external_riser</name> </joint> </release_joints> </plugin>

Definition at line 99 of file scoring_plugin.hh.

Constructor & Destructor Documentation

ScoringPlugin::ScoringPlugin ( )
default

Class constructor.

Member Function Documentation

gazebo::common::Time ScoringPlugin::ElapsedTime ( ) const
protected

Elapsed time in the running state.

Returns
The elapsed time in the running state.

Definition at line 84 of file scoring_plugin.cc.

void ScoringPlugin::Finish ( )
protected

Finish the current task. This will set the "finished" flag in the task message to true.

Definition at line 96 of file scoring_plugin.cc.

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

Definition at line 25 of file scoring_plugin.cc.

void ScoringPlugin::OnFinished ( )
privatevirtual

Callback executed when the task state transition into "finished".

Reimplemented in NavigationScoringPlugin.

Definition at line 212 of file scoring_plugin.cc.

void ScoringPlugin::OnReady ( )
privatevirtual

Callback executed when the task state transition into "ready".

Reimplemented in NavigationScoringPlugin.

Definition at line 202 of file scoring_plugin.cc.

void ScoringPlugin::OnRunning ( )
privatevirtual

Callback executed when the task state transition into "running".

Reimplemented in NavigationScoringPlugin.

Definition at line 207 of file scoring_plugin.cc.

bool ScoringPlugin::ParseJoints ( )
private

Parse the joints section of the SDF block.

Returns
True when all parameters were successfully parsed or false otherwise.

Definition at line 283 of file scoring_plugin.cc.

bool ScoringPlugin::ParseSDFParameters ( )
private

Parse all SDF parameters.

Returns
True when all parameters were successfully parsed or false otherwise.

Definition at line 217 of file scoring_plugin.cc.

void ScoringPlugin::PublishStats ( )
private

Publish the task stats over a ROS topic.

Definition at line 169 of file scoring_plugin.cc.

void ScoringPlugin::ReleaseVehicle ( )
private

Tries to release the vehicle in case is locked.

Definition at line 182 of file scoring_plugin.cc.

gazebo::common::Time ScoringPlugin::RemainingTime ( ) const
protected

Remaining time in the running state.

Returns
The remaining time in the running state.

Definition at line 90 of file scoring_plugin.cc.

double ScoringPlugin::Score ( ) const
protected

Get the current score.

Returns
The current score.

Definition at line 60 of file scoring_plugin.cc.

void ScoringPlugin::SetScore ( double  _newScore)
protected

Set the score.

Parameters
[in]_newScoreThe new score.

Definition at line 66 of file scoring_plugin.cc.

std::string ScoringPlugin::TaskName ( ) const
protected

Get the task name.

Returns
Task name.

Definition at line 72 of file scoring_plugin.cc.

std::string ScoringPlugin::TaskState ( ) const
protected

Get the task state.

Returns
Task state.

Definition at line 78 of file scoring_plugin.cc.

void ScoringPlugin::Update ( )
private

Callback executed at every world update.

Definition at line 106 of file scoring_plugin.cc.

void ScoringPlugin::UpdateTaskMessage ( )
private

Update the task stats message.

Definition at line 159 of file scoring_plugin.cc.

void ScoringPlugin::UpdateTaskState ( )
private

Update the state of the current task.

Definition at line 131 of file scoring_plugin.cc.

void ScoringPlugin::UpdateTime ( )
private

Update all time-related variables.

Definition at line 118 of file scoring_plugin.cc.

Member Data Documentation

gazebo::common::Time ScoringPlugin::currentTime
private

Current time (simulation).

Definition at line 216 of file scoring_plugin.hh.

gazebo::common::Time ScoringPlugin::elapsedTime
private

Definition at line 219 of file scoring_plugin.hh.

gazebo::common::Time ScoringPlugin::finishTime
private

Absolute time specifying the start of the finish state.

Definition at line 213 of file scoring_plugin.hh.

double ScoringPlugin::initialStateDuration = 30.0
private

Duration (seconds) of the initial state.

Definition at line 198 of file scoring_plugin.hh.

gazebo::common::Time ScoringPlugin::lastStatsSent = gazebo::common::Time::Zero
private

Time at which the last message was sent.

Definition at line 228 of file scoring_plugin.hh.

std::vector<std::string> ScoringPlugin::lockJointNames
private

The name of the joints to be dettached during ReleaseVehicle().

Definition at line 237 of file scoring_plugin.hh.

double ScoringPlugin::readyStateDuration = 60.0
private

Duration (seconds) of the ready state.

Definition at line 201 of file scoring_plugin.hh.

gazebo::common::Time ScoringPlugin::readyTime
private

Absolute time specifying the start of the ready state.

Definition at line 207 of file scoring_plugin.hh.

gazebo::common::Time ScoringPlugin::remainingTime
private

Remaining time since the start of the task (running state).

Definition at line 222 of file scoring_plugin.hh.

std::unique_ptr<ros::NodeHandle> ScoringPlugin::rosNode
private

ROS node handle.

Definition at line 240 of file scoring_plugin.hh.

double ScoringPlugin::runningStateDuration = 300.0
private

Duration (seconds) of the running state (max task time).

Definition at line 204 of file scoring_plugin.hh.

gazebo::common::Time ScoringPlugin::runningTime
private

Absolute time specifying the start of the running state.

Definition at line 210 of file scoring_plugin.hh.

double ScoringPlugin::score = 0.0
protected

The score.

Definition at line 186 of file scoring_plugin.hh.

sdf::ElementPtr ScoringPlugin::sdf
private

Pointer to the SDF plugin element.

Definition at line 195 of file scoring_plugin.hh.

vmrc_gazebo::Task ScoringPlugin::taskMsg
private

The next task message to be published.

Definition at line 234 of file scoring_plugin.hh.

std::string ScoringPlugin::taskName = "undefined"
protected

The name of the task.

Definition at line 177 of file scoring_plugin.hh.

ros::Publisher ScoringPlugin::taskPub
private

Publisher for the task state.

Definition at line 243 of file scoring_plugin.hh.

std::string ScoringPlugin::taskState = "initial"
private

The task state.

Definition at line 231 of file scoring_plugin.hh.

bool ScoringPlugin::timedOut = false
private

Whether the current task has timed out or not.

Definition at line 225 of file scoring_plugin.hh.

std::string ScoringPlugin::topic = "/vmrc/task/info"
protected

Topic where the task stats are published.

Definition at line 183 of file scoring_plugin.hh.

gazebo::event::ConnectionPtr ScoringPlugin::updateConnection
protected

Pointer to the update event connection.

Definition at line 180 of file scoring_plugin.hh.

gazebo::physics::ModelPtr ScoringPlugin::vehicleModel
protected

Pointer to the vehicle to score.

Definition at line 192 of file scoring_plugin.hh.

std::string ScoringPlugin::vehicleName
protected

The name of the vehicle to score.

Definition at line 189 of file scoring_plugin.hh.

gazebo::physics::WorldPtr ScoringPlugin::world
protected

A world pointer.

Definition at line 174 of file scoring_plugin.hh.


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


vmrc_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Sun Feb 17 2019 03:14:16