Class that establishes communication between the different states and the RSM's periphery including the GUI for the states and classes defined in rsm_additions package. It offers services and publishes topics based on the variables that need to be saved during state transitions. More...
#include <AdditionsServiceProvider.h>
Public Member Functions | |
AdditionsServiceProvider () | |
void | publishTopics () |
~AdditionsServiceProvider () | |
Private Member Functions | |
void | cmdVelCallback (const geometry_msgs::Twist::ConstPtr &msg) |
void | explorationGoalCallback (const rsm_msgs::GoalStatus::ConstPtr &goal_status) |
void | explorationModeCallback (const std_msgs::Bool::ConstPtr &exploration_mode) |
void | frontierCallback (const visualization_msgs::MarkerArray::ConstPtr &frontiers) |
bool | navGoalIncludedInFrontiers () |
void | navigationGoalCallback (const move_base_msgs::MoveBaseGoalConstPtr &frontier_goal) |
void | publishExplorationGoals () |
void | publishFailedGoals () |
void | publishGoalObsolete () |
bool | resetKinectPosition (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
void | reverseModeCmdVelCallback (const geometry_msgs::Twist::ConstPtr &cmd_vel) |
bool | setNavigationToReverse (std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) |
Class that establishes communication between the different states and the RSM's periphery including the GUI for the states and classes defined in rsm_additions package. It offers services and publishes topics based on the variables that need to be saved during state transitions.
Definition at line 31 of file AdditionsServiceProvider.h.
rsm::AdditionsServiceProvider::AdditionsServiceProvider | ( | ) |
Definition at line 5 of file AdditionsServiceProvider.cpp.
rsm::AdditionsServiceProvider::~AdditionsServiceProvider | ( | ) |
Definition at line 69 of file AdditionsServiceProvider.cpp.
|
private |
Callback for receiving autonomy cmd vel messages and save the ones not equals zero in the cirular buffer
msg | Cmd vel autonomy message |
|
private |
Callback for exploration goal status
goal_status | Current goal status and pose |
Definition at line 125 of file AdditionsServiceProvider.cpp.
|
private |
Callback for exploration mode
exploration_mode | Exploration mode (0=complete goal, 1=interrupt goal when exploration goals vanished) |
Definition at line 157 of file AdditionsServiceProvider.cpp.
|
private |
Callback for frontier visualization generated by Explore Lite. Extracts the centers of these frontiers and saves them in a list
frontiers | Marker list containing frontiers as points and nearest frontier points for each frontier as sphere |
Definition at line 134 of file AdditionsServiceProvider.cpp.
|
private |
Checks if the current navigation goal is still present as an exploration goal
Definition at line 169 of file AdditionsServiceProvider.cpp.
|
private |
Callback for requests to the SimpleActionServer that just responds with "Goal reached"
frontier_goal |
Definition at line 102 of file AdditionsServiceProvider.cpp.
|
private |
Publish list of extracted frontier centers for further calculation
Definition at line 107 of file AdditionsServiceProvider.cpp.
|
private |
Publish list of previously failed goals
Definition at line 113 of file AdditionsServiceProvider.cpp.
|
private |
Publish if current exploration goal is obsolete if exploration mode is set to interrupt
Definition at line 119 of file AdditionsServiceProvider.cpp.
void rsm::AdditionsServiceProvider::publishTopics | ( | ) |
Definition at line 73 of file AdditionsServiceProvider.cpp.
|
private |
Definition at line 193 of file AdditionsServiceProvider.cpp.
|
private |
Receives cmd vel and negate linear movement so robot goes backwards
cmd_vel | cmd vel generated for backward movement |
Definition at line 90 of file AdditionsServiceProvider.cpp.
|
private |
Definition at line 83 of file AdditionsServiceProvider.cpp.
|
private |
Topic name for the autonomy cmd vel topic to be recorded
Definition at line 64 of file AdditionsServiceProvider.h.
|
private |
Is the Calculate Goal plugin used
Definition at line 84 of file AdditionsServiceProvider.h.
|
private |
Definition at line 51 of file AdditionsServiceProvider.h.
|
private |
Tolerance for comparing if the current goal is still in the list of exploration goals
Definition at line 76 of file AdditionsServiceProvider.h.
|
private |
List of all extracted frontier centers
Definition at line 68 of file AdditionsServiceProvider.h.
|
private |
Definition at line 48 of file AdditionsServiceProvider.h.
|
private |
Mode of exploration (0=complete goal, 1=interrupt goal when exploration goals vanished)
Definition at line 80 of file AdditionsServiceProvider.h.
|
private |
Definition at line 52 of file AdditionsServiceProvider.h.
|
private |
List of previously failed goals
Definition at line 72 of file AdditionsServiceProvider.h.
|
private |
Definition at line 45 of file AdditionsServiceProvider.h.
|
private |
Definition at line 49 of file AdditionsServiceProvider.h.
|
private |
Is navigation goal still an exploration goal
Definition at line 88 of file AdditionsServiceProvider.h.
|
private |
Definition at line 50 of file AdditionsServiceProvider.h.
|
private |
Definition at line 55 of file AdditionsServiceProvider.h.
|
private |
Definition at line 39 of file AdditionsServiceProvider.h.
|
private |
Definition at line 54 of file AdditionsServiceProvider.h.
|
private |
Definition at line 43 of file AdditionsServiceProvider.h.
|
private |
Definition at line 42 of file AdditionsServiceProvider.h.
|
private |
Definition at line 41 of file AdditionsServiceProvider.h.
|
private |
SimpleActionServer for making Explore Lite run and lead it to believe it talks to Move Base
Definition at line 60 of file AdditionsServiceProvider.h.
|
private |
Definition at line 47 of file AdditionsServiceProvider.h.