A plugin for computing the score of the station keeping task. This plugin derives from the generic ScoringPlugin class. Refer to that plugin for an explanation of the four states defined (Initial, Ready, Running and Finished) as well as other required SDF elements. More...
#include <stationkeeping_scoring_plugin.hh>
Public Member Functions | |
void | Load (gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf) |
StationkeepingScoringPlugin () | |
Constructor. More... | |
Public Member Functions inherited from ScoringPlugin | |
void | Exit () |
Shutdown Gazebo and ROS. More... | |
ScoringPlugin () | |
Class constructor. More... | |
Private Member Functions | |
void | OnReady () override |
Callback executed when the task state transition into "ready". More... | |
void | OnRunning () override |
Callback executed when the task state transition into "running". More... | |
void | PublishGoal () |
Publish the goal pose. More... | |
void | Update () |
Callback executed at every world update. More... | |
Private Attributes | |
double | goalLat |
Goal pose in spherical (WGS84) coordinates. More... | |
double | goalLon |
Goal pose in spherical (WGS84) coordinates. More... | |
ros::Publisher | goalPub |
Publisher for the goal. More... | |
std::string | goalTopic = "/vrx/station_keeping/goal" |
Topic where the task stats are published. More... | |
double | goalX |
Goal pose in local (Gazebo) coordinates. More... | |
double | goalY |
Goal pose in local (Gazebo) coordinates. More... | |
double | goalYaw |
Goal pose in local (Gazebo) coordinates. More... | |
double | meanError |
Cumulative 2D RMS error in meters. More... | |
ros::Publisher | meanErrorPub |
Publisher for the current mean error. More... | |
std::string | meanErrorTopic = "/vrx/station_keeping/rms_error" |
Topic where mean pose error is published. More... | |
double | poseError |
Combined 2D pose error (distance and yaw). More... | |
ros::Publisher | poseErrorPub |
Publisher for the combined 2D pose error. More... | |
std::string | poseErrorTopic = "/vrx/station_keeping/pose_error" |
Topic where 2D pose error is published. More... | |
std::unique_ptr< ros::NodeHandle > | rosNode |
ROS node handle. More... | |
unsigned int | sampleCount = 0 |
Number of instant pose error scores calculated so far . More... | |
gazebo::common::Timer | timer |
Timer used to calculate the elapsed time docked in the bay. More... | |
double | totalPoseError = 0 |
Sum of all pose error scores calculated so far. More... | |
gazebo::event::ConnectionPtr | updateConnection |
Pointer to the update event connection. More... | |
WaypointMarkers | waypointMarkers |
Waypoint visualization markers. 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... | |
A plugin for computing the score of the station keeping task. This plugin derives from the generic ScoringPlugin class. Refer to that plugin for an explanation of the four states defined (Initial, Ready, Running and Finished) as well as other required SDF elements.
This plugin publishes a goal pose to a topic when it enters the Ready state.
In the running state it calculates a 2D pose error distance between the vehicle and the goal as well as a running RMS error of all 2D pose errors calculated so far. The current 2D pose error is published to a topic for pose error, and the RMS error is published to a task score topic. RMS error is also set as the score using the SetScore() method inherited from the parent. This causes it to also appear in the task information topic.
This plugin requires the following SDF parameters:
<goal_pose>: Optional parameter (vector type) specifying the latitude, longitude and yaw of the task goal. If not provided, all values default to 0. <markers>: Optional parameter to enable visualization markers. Check the WaypointMarkers class for SDF documentation.
Definition at line 54 of file stationkeeping_scoring_plugin.hh.
StationkeepingScoringPlugin::StationkeepingScoringPlugin | ( | ) |
Constructor.
Definition at line 29 of file stationkeeping_scoring_plugin.cc.
void StationkeepingScoringPlugin::Load | ( | gazebo::physics::WorldPtr | _world, |
sdf::ElementPtr | _sdf | ||
) |
Definition at line 39 of file stationkeeping_scoring_plugin.cc.
|
overrideprivatevirtual |
Callback executed when the task state transition into "ready".
Reimplemented from ScoringPlugin.
Definition at line 194 of file stationkeeping_scoring_plugin.cc.
|
overrideprivatevirtual |
Callback executed when the task state transition into "running".
Reimplemented from ScoringPlugin.
Definition at line 202 of file stationkeeping_scoring_plugin.cc.
|
private |
Publish the goal pose.
Definition at line 171 of file stationkeeping_scoring_plugin.cc.
|
private |
Callback executed at every world update.
Definition at line 116 of file stationkeeping_scoring_plugin.cc.
|
private |
Goal pose in spherical (WGS84) coordinates.
Definition at line 109 of file stationkeeping_scoring_plugin.hh.
|
private |
Goal pose in spherical (WGS84) coordinates.
Definition at line 112 of file stationkeeping_scoring_plugin.hh.
|
private |
Publisher for the goal.
Definition at line 91 of file stationkeeping_scoring_plugin.hh.
|
private |
Topic where the task stats are published.
Definition at line 79 of file stationkeeping_scoring_plugin.hh.
|
private |
Goal pose in local (Gazebo) coordinates.
Definition at line 100 of file stationkeeping_scoring_plugin.hh.
|
private |
Goal pose in local (Gazebo) coordinates.
Definition at line 103 of file stationkeeping_scoring_plugin.hh.
|
private |
Goal pose in local (Gazebo) coordinates.
Definition at line 106 of file stationkeeping_scoring_plugin.hh.
|
private |
Cumulative 2D RMS error in meters.
Definition at line 124 of file stationkeeping_scoring_plugin.hh.
|
private |
Publisher for the current mean error.
Definition at line 97 of file stationkeeping_scoring_plugin.hh.
|
private |
Topic where mean pose error is published.
Definition at line 85 of file stationkeeping_scoring_plugin.hh.
|
private |
Combined 2D pose error (distance and yaw).
Definition at line 115 of file stationkeeping_scoring_plugin.hh.
|
private |
Publisher for the combined 2D pose error.
Definition at line 94 of file stationkeeping_scoring_plugin.hh.
|
private |
Topic where 2D pose error is published.
Definition at line 82 of file stationkeeping_scoring_plugin.hh.
|
private |
ROS node handle.
Definition at line 88 of file stationkeeping_scoring_plugin.hh.
|
private |
Number of instant pose error scores calculated so far .
Definition at line 118 of file stationkeeping_scoring_plugin.hh.
|
private |
Timer used to calculate the elapsed time docked in the bay.
Definition at line 127 of file stationkeeping_scoring_plugin.hh.
|
private |
Sum of all pose error scores calculated so far.
Definition at line 121 of file stationkeeping_scoring_plugin.hh.
|
private |
Pointer to the update event connection.
Definition at line 76 of file stationkeeping_scoring_plugin.hh.
|
private |
Waypoint visualization markers.
Definition at line 130 of file stationkeeping_scoring_plugin.hh.