Dummy state for mapping at a reached goal during exploration. Only initiates transition to CalculateGoalState. More...
#include <RealsenseMappingState.h>

Public Member Functions | |
| void | onActive () |
| void | onEntry () |
| void | onExit () |
| void | onExplorationStart (bool &success, std::string &message) |
| void | onExplorationStop (bool &success, std::string &message) |
| void | onInterrupt (int interrupt) |
| Called when an operation mode interrupt was received. More... | |
| void | onSetup () |
| void | onWaypointFollowingStart (bool &success, std::string &message) |
| void | onWaypointFollowingStop (bool &success, std::string &message) |
| RealsenseMappingState () | |
| ~RealsenseMappingState () | |
Public Member Functions inherited from rsm::BaseState | |
| BaseState () | |
| std::string | getName () |
| StateInterface * | getStateInterface () |
| void | setStateInterface (StateInterface *stateinterface) |
| virtual | ~BaseState () |
Private Member Functions | |
| void | jointStateCallback (sensor_msgs::JointState::ConstPtr joint_state) |
Additional Inherited Members | |
Protected Attributes inherited from rsm::BaseState | |
| bool | _interrupt_occured |
| std::string | _name |
| StateInterface * | _stateinterface |
Dummy state for mapping at a reached goal during exploration. Only initiates transition to CalculateGoalState.
Definition at line 32 of file RealsenseMappingState.h.
| rsm::RealsenseMappingState::RealsenseMappingState | ( | ) |
Constructor
Definition at line 5 of file RealsenseMappingState.cpp.
| rsm::RealsenseMappingState::~RealsenseMappingState | ( | ) |
Destructor
Definition at line 8 of file RealsenseMappingState.cpp.
|
private |
Callback for joint states to check if camera reached the desired position
| joint_state | joint state message |
Definition at line 150 of file RealsenseMappingState.cpp.
|
virtual |
Process method (step-wise, never block this method)
Implements rsm::BaseState.
Definition at line 32 of file RealsenseMappingState.cpp.
|
virtual |
Called once when activated
Reimplemented from rsm::BaseState.
Definition at line 28 of file RealsenseMappingState.cpp.
|
virtual |
Called once when left
Reimplemented from rsm::BaseState.
Definition at line 88 of file RealsenseMappingState.cpp.
|
virtual |
Called when exploration was started manually
Reimplemented from rsm::BaseState.
Definition at line 105 of file RealsenseMappingState.cpp.
|
virtual |
Called when exploration was stopped manually
Reimplemented from rsm::BaseState.
Definition at line 111 of file RealsenseMappingState.cpp.
|
virtual |
Called when an operation mode interrupt was received.
| interrupt | Kind of interrupt (0=EmergencyStop, 1=TeleoperationInterupt) |
Reimplemented from rsm::BaseState.
Definition at line 130 of file RealsenseMappingState.cpp.
|
virtual |
Called once when registered at StateInterface
Reimplemented from rsm::BaseState.
Definition at line 11 of file RealsenseMappingState.cpp.
|
virtual |
Called when waypoint following was started/paused manually
Reimplemented from rsm::BaseState.
Definition at line 118 of file RealsenseMappingState.cpp.
|
virtual |
Called when waypoint following was stopped manually
Reimplemented from rsm::BaseState.
Definition at line 124 of file RealsenseMappingState.cpp.
|
private |
Definition at line 95 of file RealsenseMappingState.h.
|
private |
Move command sent to realsense controller
Definition at line 111 of file RealsenseMappingState.h.
|
private |
Was the mapping at the exploration goal successful or not
Definition at line 115 of file RealsenseMappingState.h.
|
private |
Definition at line 98 of file RealsenseMappingState.h.
|
private |
Definition at line 94 of file RealsenseMappingState.h.
|
private |
If the current state reached it's goal already
Definition at line 107 of file RealsenseMappingState.h.
|
private |
Definition at line 96 of file RealsenseMappingState.h.
|
private |
Definition at line 97 of file RealsenseMappingState.h.
|
private |
Current state of swiveling the Realsense camera from left to right and back (0: to left, 1: left to right: 2: back to center)
Definition at line 103 of file RealsenseMappingState.h.