wayfinding_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 VRX_GAZEBO_WAYFINDING_SCORING_PLUGIN_HH_
19 #define VRX_GAZEBO_WAYFINDING_SCORING_PLUGIN_HH_
20 
21 #include <ros/ros.h>
22 #include <memory>
23 #include <string>
24 #include <vector>
25 #include <gazebo/common/Events.hh>
26 #include <gazebo/common/Timer.hh>
27 #include <gazebo/physics/World.hh>
28 #include <sdf/sdf.hh>
31 
59 {
61  public: WayfindingScoringPlugin();
62 
63  // Documentation inherited.
64  public: void Load(gazebo::physics::WorldPtr _world,
65  sdf::ElementPtr _sdf);
66 
68  private: void Update();
69 
70  // Documentation inherited.
71  private: void OnReady() override;
72 
73  // Documentation inherited.
74  private: void OnRunning() override;
75 
77  private: void PublishWaypoints();
78 
80  private: gazebo::event::ConnectionPtr updateConnection;
81 
83  private: sdf::ElementPtr sdf;
84 
86  private: std::string waypointsTopic = "/vrx/wayfinding/waypoints";
87 
90  private: std::string minErrorsTopic = "/vrx/wayfinding/min_errors";
91 
93  private: std::string meanErrorTopic = "/vrx/wayfinding/mean_error";
94 
96  private: std::unique_ptr<ros::NodeHandle> rosNode;
97 
100 
103 
106 
109  private: std::vector<ignition::math::Vector3d> localWaypoints;
110 
114  private: std::vector<ignition::math::Vector3d> sphericalWaypoints;
115 
118  private: std::vector<double> minErrors;
119 
121  private: double meanError;
122 
124  private: gazebo::common::Timer timer;
125 
128 };
129 
130 #endif
gazebo::event::ConnectionPtr updateConnection
Pointer to the update event connection.
double meanError
Current average minimum error for all waypoints.
void PublishWaypoints()
Publish the waypoints through which the vehicle must navigate.
std::vector< double > minErrors
Vector containing current minimum 2D pose error achieved for each waypoint so far.
void OnReady() override
Callback executed when the task state transition into "ready".
ros::Publisher meanErrorPub
Publisher for the current rms error.
std::unique_ptr< ros::NodeHandle > rosNode
ROS node handle.
std::string minErrorsTopic
Topic where the current minimum pose error distance for each waypoint is published.
void Load(gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
ros::Publisher waypointsPub
Publisher for the goal.
std::string waypointsTopic
Topic where the list of waypoints is published.
void Update()
Callback executed at every world update.
ros::Publisher minErrorsPub
Publisher for the combined 2D pose error.
std::vector< ignition::math::Vector3d > localWaypoints
Vector containing waypoints as 3D vectors of doubles representing X Y yaw, where X and Y are local (G...
A plugin that provides common functionality to any scoring plugin. This plugin defines four different...
std::vector< ignition::math::Vector3d > sphericalWaypoints
Vector containing waypoints as 3D vectors of doubles representing Lattitude Longitude yaw...
This class is used to display waypoint markers. Cylindrical Gazebo markers are drawn with text on top...
sdf::ElementPtr sdf
Pointer to the sdf plugin element.
WaypointMarkers waypointMarkers
Waypoint visualization markers.
std::string meanErrorTopic
Topic where the current average minimum error is published.
gazebo::common::Timer timer
Timer used to calculate the elapsed time docked in the bay.
A plugin for computing the score of the wayfinding navigation task. This plugin derives from the gene...
void OnRunning() override
Callback executed when the task state transition into "running".


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