Public Member Functions | Private Member Functions | Private Attributes | List of all members
rsm::RealsenseMappingState Class Reference

Dummy state for mapping at a reached goal during exploration. Only initiates transition to CalculateGoalState. More...

#include <RealsenseMappingState.h>

Inheritance diagram for rsm::RealsenseMappingState:
Inheritance graph
[legend]

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 ()
 
StateInterfacegetStateInterface ()
 
void setStateInterface (StateInterface *stateinterface)
 
virtual ~BaseState ()
 

Private Member Functions

void jointStateCallback (sensor_msgs::JointState::ConstPtr joint_state)
 

Private Attributes

ros::Subscriber _joint_states_subscriber
 
bool _message_send
 
int _navigation_completed_status
 
ros::ServiceClient _navigation_goal_completed_service
 
ros::NodeHandle _nh
 
bool _position_reached
 
ros::Publisher _realsense_joint_controller
 
ros::ServiceClient _reset_realsense_position_client
 
int _swivel_state
 

Additional Inherited Members

- Protected Attributes inherited from rsm::BaseState
bool _interrupt_occured
 
std::string _name
 
StateInterface_stateinterface
 

Detailed Description

Dummy state for mapping at a reached goal during exploration. Only initiates transition to CalculateGoalState.

Definition at line 32 of file RealsenseMappingState.h.

Constructor & Destructor Documentation

◆ RealsenseMappingState()

rsm::RealsenseMappingState::RealsenseMappingState ( )

Constructor

Definition at line 5 of file RealsenseMappingState.cpp.

◆ ~RealsenseMappingState()

rsm::RealsenseMappingState::~RealsenseMappingState ( )

Destructor

Definition at line 8 of file RealsenseMappingState.cpp.

Member Function Documentation

◆ jointStateCallback()

void rsm::RealsenseMappingState::jointStateCallback ( sensor_msgs::JointState::ConstPtr  joint_state)
private

Callback for joint states to check if camera reached the desired position

Parameters
joint_statejoint state message

Definition at line 150 of file RealsenseMappingState.cpp.

◆ onActive()

void rsm::RealsenseMappingState::onActive ( )
virtual

Process method (step-wise, never block this method)

Implements rsm::BaseState.

Definition at line 32 of file RealsenseMappingState.cpp.

◆ onEntry()

void rsm::RealsenseMappingState::onEntry ( )
virtual

Called once when activated

Reimplemented from rsm::BaseState.

Definition at line 28 of file RealsenseMappingState.cpp.

◆ onExit()

void rsm::RealsenseMappingState::onExit ( )
virtual

Called once when left

Reimplemented from rsm::BaseState.

Definition at line 88 of file RealsenseMappingState.cpp.

◆ onExplorationStart()

void rsm::RealsenseMappingState::onExplorationStart ( bool &  success,
std::string &  message 
)
virtual

Called when exploration was started manually

Reimplemented from rsm::BaseState.

Definition at line 105 of file RealsenseMappingState.cpp.

◆ onExplorationStop()

void rsm::RealsenseMappingState::onExplorationStop ( bool &  success,
std::string &  message 
)
virtual

Called when exploration was stopped manually

Reimplemented from rsm::BaseState.

Definition at line 111 of file RealsenseMappingState.cpp.

◆ onInterrupt()

void rsm::RealsenseMappingState::onInterrupt ( int  interrupt)
virtual

Called when an operation mode interrupt was received.

Parameters
interruptKind of interrupt (0=EmergencyStop, 1=TeleoperationInterupt)

Reimplemented from rsm::BaseState.

Definition at line 130 of file RealsenseMappingState.cpp.

◆ onSetup()

void rsm::RealsenseMappingState::onSetup ( )
virtual

Called once when registered at StateInterface

Reimplemented from rsm::BaseState.

Definition at line 11 of file RealsenseMappingState.cpp.

◆ onWaypointFollowingStart()

void rsm::RealsenseMappingState::onWaypointFollowingStart ( bool &  success,
std::string &  message 
)
virtual

Called when waypoint following was started/paused manually

Reimplemented from rsm::BaseState.

Definition at line 118 of file RealsenseMappingState.cpp.

◆ onWaypointFollowingStop()

void rsm::RealsenseMappingState::onWaypointFollowingStop ( bool &  success,
std::string &  message 
)
virtual

Called when waypoint following was stopped manually

Reimplemented from rsm::BaseState.

Definition at line 124 of file RealsenseMappingState.cpp.

Member Data Documentation

◆ _joint_states_subscriber

ros::Subscriber rsm::RealsenseMappingState::_joint_states_subscriber
private

Definition at line 95 of file RealsenseMappingState.h.

◆ _message_send

bool rsm::RealsenseMappingState::_message_send
private

Move command sent to realsense controller

Definition at line 111 of file RealsenseMappingState.h.

◆ _navigation_completed_status

int rsm::RealsenseMappingState::_navigation_completed_status
private

Was the mapping at the exploration goal successful or not

Definition at line 115 of file RealsenseMappingState.h.

◆ _navigation_goal_completed_service

ros::ServiceClient rsm::RealsenseMappingState::_navigation_goal_completed_service
private

Definition at line 98 of file RealsenseMappingState.h.

◆ _nh

ros::NodeHandle rsm::RealsenseMappingState::_nh
private

Definition at line 94 of file RealsenseMappingState.h.

◆ _position_reached

bool rsm::RealsenseMappingState::_position_reached
private

If the current state reached it's goal already

Definition at line 107 of file RealsenseMappingState.h.

◆ _realsense_joint_controller

ros::Publisher rsm::RealsenseMappingState::_realsense_joint_controller
private

Definition at line 96 of file RealsenseMappingState.h.

◆ _reset_realsense_position_client

ros::ServiceClient rsm::RealsenseMappingState::_reset_realsense_position_client
private

Definition at line 97 of file RealsenseMappingState.h.

◆ _swivel_state

int rsm::RealsenseMappingState::_swivel_state
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.


The documentation for this class was generated from the following files:


rsm_additions
Author(s): Marco Steinbrink
autogenerated on Mon Feb 28 2022 23:28:21