navigation_scoring_plugin.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef VMRC_GAZEBO_NAVIGATION_SCORING_PLUGIN_HH_
19 #define VMRC_GAZEBO_NAVIGATION_SCORING_PLUGIN_HH_
20 
21 #include <string>
22 #include <vector>
23 #include <gazebo/common/Events.hh>
24 #include <gazebo/math/Pose.hh>
25 #include <gazebo/physics/Model.hh>
26 #include <gazebo/physics/World.hh>
27 #include <sdf/sdf.hh>
29 
85 {
87  private: enum class GateState
88  {
91 
94 
97 
99  CROSSED,
100 
102  INVALID,
103  };
104 
106  private: class Gate
107  {
111  public: Gate(const gazebo::physics::ModelPtr _leftMarkerModel,
112  const gazebo::physics::ModelPtr _rightMarkerModel);
113 
117  public: GateState IsPoseInGate(const gazebo::math::Pose &_robotWorldPose)
118  const;
119 
121  public: void Update();
122 
124  public: gazebo::physics::ModelPtr leftMarkerModel;
125 
127  public: gazebo::physics::ModelPtr rightMarkerModel;
128 
132  public: gazebo::math::Pose pose;
133 
135  public: double width;
136 
139  };
140 
141  // Constructor.
142  public: NavigationScoringPlugin();
143 
144  // Documentation inherited.
145  public: void Load(gazebo::physics::WorldPtr _world,
146  sdf::ElementPtr _sdf);
147 
151  private: bool ParseGates(sdf::ElementPtr _sdf);
152 
157  private: bool AddGate(const std::string &_leftMarkerName,
158  const std::string &_rightMarkerName);
159 
161  private: void Update();
162 
163  // Documentation inherited.
164  private: void OnReady() override;
165 
166  // Documentation inherited.
167  private: void OnRunning() override;
168 
169  // Documentation inherited.
170  private: void OnFinished() override;
171 
173  private: std::vector<Gate> gates;
174 
176  private: gazebo::event::ConnectionPtr updateConnection;
177 };
178 
179 #endif
std::vector< Gate > gates
All the gates.
Gate invalid. E.g.: if crossed in the wrong direction.
double width
The width of the gate in meters.
void OnReady() override
Callback executed when the task state transition into "ready".
gazebo::physics::ModelPtr rightMarkerModel
The right marker model.
bool ParseGates(sdf::ElementPtr _sdf)
Parse the gates from SDF.
void Load(gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
A plugin that provides common functionality to any scoring plugin. This plugin defines four different...
void OnFinished() override
Callback executed when the task state transition into "finished".
bool AddGate(const std::string &_leftMarkerName, const std::string &_rightMarkerName)
Register a new gate.
gazebo::math::Pose pose
The center of the gate in the world frame. Note that the roll and pitch are ignored. Only yaw is relevant and it points into the direction in which the gate should be crossed.
void OnRunning() override
Callback executed when the task state transition into "running".
void Update()
Callback executed at every world update.
A gate that is part of the navigation challenge.
gazebo::physics::ModelPtr leftMarkerModel
The left marker model.
gazebo::event::ConnectionPtr updateConnection
Pointer to the update event connection.
A plugin for computing the score of the navigation task. This plugin derives from the generic Scoring...


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