A class to monitor if the vehicle docked in a given bay. More...
#include <scan_dock_scoring_plugin.hh>
Public Member Functions | |
bool | Allowed () const |
Whether it is allowed to dock in this bay or not. More... | |
void | AnnounceSymbol () |
Announce the symbol of the bay via ROS. More... | |
bool | AnytimeDocked () const |
Whether the robot has been successfully docked in this bay or not. More... | |
bool | AtEntrance () const |
Whether the robot is currently at the entrance of the bay. More... | |
DockChecker (const std::string &_name, const std::string &_internalActivationTopic, const std::string &_exteriorActivationTopic, const double _minDockTime, const bool _dockAllowed, const std::string &_worldName, const std::string &_rosNameSpace, const std::string &_announceSymbol, const std::string &_gzSymbolTopic) | |
Constructor. More... | |
void | Update () |
Update function that needs to be executed periodically. More... | |
Public Attributes | |
std::string | name |
The name of this checker. More... | |
Private Member Functions | |
void | OnExternalActivationEvent (ConstIntPtr &_msg) |
Callback triggered when the vehicle enters or exits the activation zone. More... | |
void | OnInternalActivationEvent (ConstIntPtr &_msg) |
Callback triggered when the vehicle enters or exits the activation zone. More... | |
Private Attributes | |
std_msgs::String | announceSymbol |
Color and shape of symbol to announce. E.g.: red_cross, blue_circle. More... | |
bool | anytimeDocked = false |
Whether the vehicle has successfully docked or not. More... | |
bool | atEntrance = false |
Whether the vehicle is at the entrance of the bay or not. More... | |
gazebo::transport::SubscriberPtr | containSub |
Subscriber to receive notifications from the contain plugin. More... | |
bool | dockAllowed |
Whether is allowed to dock in this bay or not. More... | |
gazebo::transport::PublisherPtr | dockPlacardPub |
Publish the placard symbols. More... | |
std::string | externalActivationTopic |
The gazebo topic used to receive notifications from the external activation zone. More... | |
std::string | gzSymbolTopic |
The gazebo topic used to publish symbols to the placards. More... | |
std::string | internalActivationTopic |
The gazebo topic used to receive notifications from the internal activation zone. More... | |
double | minDockTime |
Minimum amount of seconds to stay docked to be considered a fully successfull dock. More... | |
std::unique_ptr< ros::NodeHandle > | nh |
ROS Node handle. More... | |
gazebo::transport::NodePtr | node |
Create a node for communication. More... | |
std::string | ns |
ROS namespace. More... | |
ros::Publisher | symbolPub |
Publisher for the symbol. More... | |
std::string | symbolTopic = "/vrx/scan_dock/placard_symbol" |
ROS topic where the target symbol will be published. More... | |
gazebo::common::Timer | timer |
Timer used to calculate the elapsed time docked in the bay. More... | |
A class to monitor if the vehicle docked in a given bay.
Definition at line 94 of file scan_dock_scoring_plugin.hh.
DockChecker::DockChecker | ( | const std::string & | _name, |
const std::string & | _internalActivationTopic, | ||
const std::string & | _exteriorActivationTopic, | ||
const double | _minDockTime, | ||
const bool | _dockAllowed, | ||
const std::string & | _worldName, | ||
const std::string & | _rosNameSpace, | ||
const std::string & | _announceSymbol, | ||
const std::string & | _gzSymbolTopic | ||
) |
Constructor.
[in] | _name | The name of the checker (only used for debugging). |
[in] | _internalActivationTopic | The gazebo topic used to receive notifications about the internal activation zone. |
[in] | _externalActivationTopic | The gazebo topic used to receive notifications about the external activation zone. from the "contain" plugin. |
[in] | _minDockTime | Minimum amount of seconds to stay docked to be considered a fully successfull dock. |
[in] | _dockAllowed | Whether is allowed to dock in this bay or not. |
[in] | _worldName | Gazebo world name. |
[in] | _announceSymbol | Optional symbol to announce via ROS. |
Definition at line 125 of file scan_dock_scoring_plugin.cc.
bool DockChecker::Allowed | ( | ) | const |
Whether it is allowed to dock in this bay or not.
Definition at line 175 of file scan_dock_scoring_plugin.cc.
void DockChecker::AnnounceSymbol | ( | ) |
Announce the symbol of the bay via ROS.
Definition at line 181 of file scan_dock_scoring_plugin.cc.
bool DockChecker::AnytimeDocked | ( | ) | const |
Whether the robot has been successfully docked in this bay or not.
Definition at line 163 of file scan_dock_scoring_plugin.cc.
bool DockChecker::AtEntrance | ( | ) | const |
Whether the robot is currently at the entrance of the bay.
Definition at line 169 of file scan_dock_scoring_plugin.cc.
|
private |
Callback triggered when the vehicle enters or exits the activation zone.
[in] | _msg | The current state (0: exiting, 1: entering). |
Definition at line 310 of file scan_dock_scoring_plugin.cc.
|
private |
Callback triggered when the vehicle enters or exits the activation zone.
[in] | _msg | The current state (0: exiting, 1: entering). |
Definition at line 276 of file scan_dock_scoring_plugin.cc.
void DockChecker::Update | ( | ) |
Update function that needs to be executed periodically.
Definition at line 205 of file scan_dock_scoring_plugin.cc.
|
private |
Color and shape of symbol to announce. E.g.: red_cross, blue_circle.
Definition at line 195 of file scan_dock_scoring_plugin.hh.
|
private |
Whether the vehicle has successfully docked or not.
Definition at line 189 of file scan_dock_scoring_plugin.hh.
|
private |
Whether the vehicle is at the entrance of the bay or not.
Definition at line 192 of file scan_dock_scoring_plugin.hh.
|
private |
Subscriber to receive notifications from the contain plugin.
Definition at line 186 of file scan_dock_scoring_plugin.hh.
|
private |
Whether is allowed to dock in this bay or not.
Definition at line 172 of file scan_dock_scoring_plugin.hh.
|
private |
Publish the placard symbols.
Definition at line 210 of file scan_dock_scoring_plugin.hh.
|
private |
The gazebo topic used to receive notifications from the external activation zone.
Definition at line 162 of file scan_dock_scoring_plugin.hh.
|
private |
The gazebo topic used to publish symbols to the placards.
Definition at line 165 of file scan_dock_scoring_plugin.hh.
|
private |
The gazebo topic used to receive notifications from the internal activation zone.
Definition at line 158 of file scan_dock_scoring_plugin.hh.
|
private |
Minimum amount of seconds to stay docked to be considered a fully successfull dock.
Definition at line 169 of file scan_dock_scoring_plugin.hh.
std::string DockChecker::name |
The name of this checker.
Definition at line 119 of file scan_dock_scoring_plugin.hh.
|
private |
ROS Node handle.
Definition at line 201 of file scan_dock_scoring_plugin.hh.
|
private |
Create a node for communication.
Definition at line 183 of file scan_dock_scoring_plugin.hh.
|
private |
ROS namespace.
Definition at line 198 of file scan_dock_scoring_plugin.hh.
|
private |
Publisher for the symbol.
Definition at line 204 of file scan_dock_scoring_plugin.hh.
|
private |
ROS topic where the target symbol will be published.
Definition at line 207 of file scan_dock_scoring_plugin.hh.
|
private |
Timer used to calculate the elapsed time docked in the bay.
Definition at line 175 of file scan_dock_scoring_plugin.hh.