28 #ifndef QB_DEVICE_HARDWARE_INTERFACE_H 29 #define QB_DEVICE_HARDWARE_INTERFACE_H 98 virtual std::vector<std::string>
getJoints() = 0;
198 virtual int setCommands(
const std::vector<double> &commands);
247 #endif // QB_DEVICE_HARDWARE_INTERFACE_H void resetServicesAndWait(const bool &reinitialize_device=true)
Re-subscribe to all the services advertised by the Communication Handler and wait until all the servi...
qb_device_hardware_interface::qbDeviceHWResources joints_
std::shared_ptr< transmission_interface::Transmission > TransmissionPtr
virtual int getMeasurements(std::vector< double > &positions, std::vector< double > ¤ts, ros::Time &stamp)
Call the service to retrieve device measurements (both positions and currents) and wait for the respo...
void publish()
Construct a qb_device_msgs::StateStamped message of the whole device state with the data retrieved du...
qb_device_joint_limits_interface::qbDeviceJointLimitsResources joint_limits_
qb_device_msgs::Info device_info_
The qbrobotics Device HardWare Resources contains vectors of named joints.
std::shared_ptr< qbDeviceHW > qbDeviceHWPtr
virtual std::string getInfo()
Call the service to retrieve the printable configuration setup of the device and wait for the respons...
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. ...
The qbrobotics Device HardWare interface extends the hardware_interface::RobotHW by providing all the...
~qbDeviceHW() override
Deactivate motors and stop the async spinner.
qb_device_hardware_interface::qbDeviceResources device_
qb_device_hardware_interface::qbDeviceHWResources actuators_
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...
ros::AsyncSpinner spinner_
The qbrobotics Device Joint Limits Resources is a simple class aimed to group all the joint_limits_in...
virtual int deactivateMotors()
Call the service to deactivate the device motors and wait for the response.
ros::NodeHandle node_handle_
qb_device_transmission_interface::qbDeviceTransmissionResources transmission_
virtual int activateMotors()
Call the service to activate the device motors and wait for the response.
The qbrobotics Device HardWare Interfaces is a simple class aimed to group all the hardware_interface...
std::string getDeviceNamespace()
void waitForServices()
Wait until all the services advertised by the Communication Handler are active, then reinitialize the...
void initializeServicesAndWait()
Subscribe to all the services advertised by the Communication Handler and wait until all the services...
std::vector< std::string > addNamespacePrefix(const std::vector< std::string > &vector)
Add the namespace prefix stored in the private namespace_ to all the elements of the given vector...
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 Handl...
The qbrobotics Device Resources contains just few device information.
virtual int initializeDevice()
Call the service to initialize the device with parameters from the Communication Handler and wait for...
void waitForInitialization()
Wait until the device is initialized.
virtual int setCommands(const std::vector< double > &commands)
Call the service to send reference commands to the device and wait for the response.
std::map< std::string, ros::ServiceClient > services_
ros::Publisher state_publisher_
qb_device_hardware_interface::qbDeviceHWInterfaces interfaces_
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 stat...
The qbrobotics Device Transmission Resources is a simple class aimed to group all the transmission_in...
virtual std::vector< std::string > getJoints()=0
This pure virtual method has to be redefined by derived classes to return the controlled joint names ...