Public Member Functions | Private Member Functions | Private Attributes | List of all members
ServiceStopper Class Reference

#include <service_stopper.h>

Inheritance diagram for ServiceStopper:
Inheritance graph
[legend]

Public Member Functions

virtual bool consume (RobotModeData_V1_X &data)
 
virtual bool consume (RobotModeData_V3_0__1 &data)
 
virtual bool consume (RobotModeData_V3_2 &data)
 
virtual bool consume (MasterBoardData_V1_X &data)
 
virtual bool consume (MasterBoardData_V3_0__1 &data)
 
virtual bool consume (MasterBoardData_V3_2 &data)
 
 ServiceStopper (std::vector< Service * > services)
 
- Public Member Functions inherited from URStatePacketConsumer
virtual bool consume (shared_ptr< StatePacket > packet)
 
- Public Member Functions inherited from IConsumer< StatePacket >
virtual void onTimeout ()
 
virtual void setupConsumer ()
 
virtual void stopConsumer ()
 
virtual void teardownConsumer ()
 

Private Member Functions

bool enableCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &resp)
 
bool handle (SharedRobotModeData &data, bool error)
 
void notify_all (RobotState state)
 

Private Attributes

ActivationMode activation_mode_
 
ros::ServiceServer enable_service_
 
RobotState last_state_
 
ros::NodeHandle nh_
 
std::vector< Service * > services_
 

Detailed Description

Definition at line 46 of file service_stopper.h.

Constructor & Destructor Documentation

ServiceStopper::ServiceStopper ( std::vector< Service * >  services)

Definition at line 21 of file service_stopper.cpp.

Member Function Documentation

virtual bool ServiceStopper::consume ( RobotModeData_V1_X data)
inlinevirtual

Implements URStatePacketConsumer.

Definition at line 62 of file service_stopper.h.

virtual bool ServiceStopper::consume ( RobotModeData_V3_0__1 data)
inlinevirtual

Implements URStatePacketConsumer.

Definition at line 66 of file service_stopper.h.

virtual bool ServiceStopper::consume ( RobotModeData_V3_2 data)
inlinevirtual

Implements URStatePacketConsumer.

Definition at line 70 of file service_stopper.h.

virtual bool ServiceStopper::consume ( MasterBoardData_V1_X data)
inlinevirtual

Implements URStatePacketConsumer.

Definition at line 76 of file service_stopper.h.

virtual bool ServiceStopper::consume ( MasterBoardData_V3_0__1 data)
inlinevirtual

Implements URStatePacketConsumer.

Definition at line 80 of file service_stopper.h.

virtual bool ServiceStopper::consume ( MasterBoardData_V3_2 data)
inlinevirtual

Implements URStatePacketConsumer.

Definition at line 84 of file service_stopper.h.

bool ServiceStopper::enableCallback ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  resp 
)
private

Definition at line 51 of file service_stopper.cpp.

bool ServiceStopper::handle ( SharedRobotModeData data,
bool  error 
)
private

Definition at line 73 of file service_stopper.cpp.

void ServiceStopper::notify_all ( RobotState  state)
private

Definition at line 60 of file service_stopper.cpp.

Member Data Documentation

ActivationMode ServiceStopper::activation_mode_
private

Definition at line 53 of file service_stopper.h.

ros::ServiceServer ServiceStopper::enable_service_
private

Definition at line 50 of file service_stopper.h.

RobotState ServiceStopper::last_state_
private

Definition at line 52 of file service_stopper.h.

ros::NodeHandle ServiceStopper::nh_
private

Definition at line 49 of file service_stopper.h.

std::vector<Service*> ServiceStopper::services_
private

Definition at line 51 of file service_stopper.h.


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


ur_modern_driver
Author(s): Thomas Timm Andersen, Simon Rasmussen
autogenerated on Fri Jun 26 2020 03:37:01