Public Member Functions | List of all members
qb_device_hardware_interface::qbDeviceHWMock Class Reference

#include <mocks.h>

Inheritance diagram for qb_device_hardware_interface::qbDeviceHWMock:
Inheritance graph
[legend]

Public Member Functions

 MOCK_METHOD0 (activate, int())
 
 MOCK_METHOD0 (close, int())
 
 MOCK_METHOD0 (deactivate, int())
 
 MOCK_METHOD0 (getInfo, std::string())
 
 MOCK_METHOD0 (isActive, bool())
 
 MOCK_METHOD0 (isOpen, bool())
 
 MOCK_METHOD0 (open, int())
 
 MOCK_METHOD0 (retrieveSerialPort, int())
 
 MOCK_METHOD1 (open, int(const std::string &serial_port))
 
 MOCK_METHOD1 (set, int(const std::vector< double > &commands))
 
 MOCK_METHOD2 (get, int(std::vector< double > &positions, std::vector< double > &currents))
 
 MOCK_METHOD2 (retrieveDeviceParameters, int(std::vector< int > &limits, std::vector< int > &resolutions))
 
 qbDeviceHWMock (qb_device_driver::qbDeviceAPIPtr api_mock)
 
int realActivate ()
 
int realClose ()
 
int realDeactivate ()
 
int realGet (std::vector< double > &positions, std::vector< double > &currents)
 
std::string realGetInfo ()
 
bool realIsActive ()
 
bool realIsOpen ()
 
int realOpen ()
 
int realOpen (const std::string &serial_port)
 
int realRetrieveDeviceParameters (std::vector< int > &limits, std::vector< int > &resolutions)
 
int realRetrieveSerialPort ()
 
int realSet (const std::vector< double > &commands)
 
- Public Member Functions inherited from qb_device_hardware_interface::qbDeviceHW
int getDeviceId ()
 
std::string getDeviceNamespace ()
 
virtual std::vector< std::string > getJoints ()=0
 This pure virtual method has to be redefined by derived classes to return the controlled joint names vector. More...
 
bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
 The init function is called to initialize the RobotHW from a non-realtime thread. More...
 
 qbDeviceHW (qb_device_transmission_interface::TransmissionPtr transmission, const std::vector< std::string > &actuators, const std::vector< std::string > &joints)
 Initialize HW resources and interfaces, and wait until it is initialized from the Communication Handler. More...
 
void read (const ros::Time &time, const ros::Duration &period) override
 Read actuator state from the hardware, propagate it to joint states and publish the whole device state to a namespaced "~state" topic (each instance of qbDeviceHW should publish on its own topic). More...
 
void write (const ros::Time &time, const ros::Duration &period) override
 Enforce joint limits for all registered joint limit interfaces, propagate joint commands to actuators, and send actuator commands to the hardware. More...
 
 ~qbDeviceHW () override
 Deactivate motors and stop the async spinner. More...
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
 RobotHW ()
 
virtual ~RobotHW ()
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Additional Inherited Members

- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 
- Protected Member Functions inherited from qb_device_hardware_interface::qbDeviceHW
virtual int activateMotors ()
 Call the service to activate the device motors and wait for the response. More...
 
virtual int deactivateMotors ()
 Call the service to deactivate the device motors and wait for the response. More...
 
virtual std::string getInfo ()
 Call the service to retrieve the printable configuration setup of the device and wait for the response. More...
 
virtual int getMeasurements (std::vector< double > &positions, std::vector< double > &currents, ros::Time &stamp)
 Call the service to retrieve device measurements (both positions and currents) and wait for the response. More...
 
virtual int initializeDevice ()
 Call the service to initialize the device with parameters from the Communication Handler and wait for the response. More...
 
virtual int setCommands (const std::vector< double > &commands)
 Call the service to send reference commands to the device and wait for the response. More...
 
- Protected Attributes inherited from qb_device_hardware_interface::qbDeviceHW
qb_device_hardware_interface::qbDeviceHWResources actuators_
 
qb_device_hardware_interface::qbDeviceResources device_
 
qb_device_msgs::Info device_info_
 
qb_device_hardware_interface::qbDeviceHWInterfaces interfaces_
 
qb_device_joint_limits_interface::qbDeviceJointLimitsResources joint_limits_
 
qb_device_hardware_interface::qbDeviceHWResources joints_
 
ros::NodeHandle node_handle_
 
std::map< std::string, ros::ServiceClientservices_
 
ros::AsyncSpinner spinner_
 
ros::Publisher state_publisher_
 
qb_device_transmission_interface::qbDeviceTransmissionResources transmission_
 
urdf::Model urdf_model_
 
bool use_simulator_mode_
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 120 of file mocks.h.

Constructor & Destructor Documentation

qb_device_hardware_interface::qbDeviceHWMock::qbDeviceHWMock ( qb_device_driver::qbDeviceAPIPtr  api_mock)
inline

Definition at line 122 of file mocks.h.

Member Function Documentation

qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( activate  ,
int()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( close  ,
int()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( deactivate  ,
int()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( getInfo  ,
std::string()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( isActive  ,
bool()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( isOpen  ,
bool()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( open  ,
int()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD0 ( retrieveSerialPort  ,
int()   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD1 ( open  ,
int(const std::string &serial_port)   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD1 ( set  ,
int(const std::vector< double > &commands)   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD2 ( get  ,
int(std::vector< double > &positions, std::vector< double > &currents)   
)
qb_device_hardware_interface::qbDeviceHWMock::MOCK_METHOD2 ( retrieveDeviceParameters  ,
int(std::vector< int > &limits, std::vector< int > &resolutions)   
)
int qb_device_hardware_interface::qbDeviceHWMock::realActivate ( )
inline

Definition at line 163 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realClose ( )
inline

Definition at line 166 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realDeactivate ( )
inline

Definition at line 169 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realGet ( std::vector< double > &  positions,
std::vector< double > &  currents 
)
inline

Definition at line 172 of file mocks.h.

std::string qb_device_hardware_interface::qbDeviceHWMock::realGetInfo ( )
inline

Definition at line 175 of file mocks.h.

bool qb_device_hardware_interface::qbDeviceHWMock::realIsActive ( )
inline

Definition at line 178 of file mocks.h.

bool qb_device_hardware_interface::qbDeviceHWMock::realIsOpen ( )
inline

Definition at line 181 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realOpen ( )
inline

Definition at line 184 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realOpen ( const std::string &  serial_port)
inline

Definition at line 187 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realRetrieveDeviceParameters ( std::vector< int > &  limits,
std::vector< int > &  resolutions 
)
inline

Definition at line 190 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realRetrieveSerialPort ( )
inline

Definition at line 193 of file mocks.h.

int qb_device_hardware_interface::qbDeviceHWMock::realSet ( const std::vector< double > &  commands)
inline

Definition at line 196 of file mocks.h.


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


qb_device_hardware_interface
Author(s): qbroboticsĀ®
autogenerated on Thu Jun 6 2019 19:46:29