Public Member Functions | Private Member Functions | List of all members
qb_device_driver::qbDeviceAPI Class Reference

This class wraps the qbrobotics device-independent API to easily use it within the Communication Handler ROS node. More...

#include <qb_device_driver.h>

Public Member Functions

virtual void activate (comm_settings *file_descriptor, const int &id, bool activate_command)
 Activate (or deactivate, according to the given command) the motors of the device connected to the serial port relative to the given file descriptor. More...
 
virtual void close (comm_settings *file_descriptor)
 Close the communication with all the devices connected to the serial port relative to the given file descriptor. More...
 
virtual int getCurrents (comm_settings *file_descriptor, const int &id, std::vector< short int > &currents)
 Retrieve the motor currents of the given device. More...
 
virtual int getDeviceIds (comm_settings *file_descriptor, std::array< char, 255 > &device_ids)
 Retrieve the list of devices connected to the serial port of the given file descriptor. More...
 
virtual std::string getInfo (comm_settings *file_descriptor, const int &id)
 Retrieve the printable configuration setup of the given device. More...
 
virtual int getMeasurements (comm_settings *file_descriptor, const int &id, std::vector< short int > &measurements)
 Retrieve the motor positions of the given device. More...
 
virtual void getParameters (comm_settings *file_descriptor, const int &id, std::vector< int > &input_mode, std::vector< int > &control_mode, std::vector< int > &resolutions, std::vector< int > &limits)
 Retrieve some of the parameters from the given device. More...
 
virtual int getPositions (comm_settings *file_descriptor, const int &id, std::vector< short int > &positions)
 Retrieve the motor positions of the given device. More...
 
virtual int getSerialPorts (std::array< char[255], 10 > &serial_ports)
 Retrieve the list of serial ports connected to the system. More...
 
virtual bool getStatus (comm_settings *file_descriptor, const int &id, bool &activate_status)
 Retrieve the motor activation status of the given device. More...
 
virtual bool getStatus (comm_settings *file_descriptor, const int &id)
 Retrieve the connection status of the given device. More...
 
virtual void open (comm_settings *file_descriptor, const std::string &serial_port)
 Open the serial communication on the given serial port. More...
 
virtual int setCommandsAndWait (comm_settings *file_descriptor, const int &id, std::vector< short int > &commands)
 Send the reference command to the motors of the given device and wait for acknowledge. More...
 
virtual int setCommandsAsync (comm_settings *file_descriptor, const int &id, std::vector< short int > &commands)
 Send the reference command to the motors of the given device in a non-blocking fashion. More...
 
virtual int setPID (comm_settings *file_descriptor, const int &id, std::vector< float > &pid)
 Set the position control PID parameters of the given device, temporarily (until power off). More...
 

Private Member Functions

template<class T >
void getParameter (const int &parameter_id, unsigned char *parameter_buffer, std::vector< int > &parameter_vector)
 Extract the specified parameter from the given buffer where all the device parameters are stored. More...
 
template<class T >
void getParameter (const int &parameter_id, unsigned char *parameter_buffer, std::vector< float > &parameter_vector)
 Extract the specified parameter from the given buffer where all the device parameters are stored. More...
 

Detailed Description

This class wraps the qbrobotics device-independent API to easily use it within the Communication Handler ROS node.

Definition at line 41 of file qb_device_driver.h.

Member Function Documentation

virtual void qb_device_driver::qbDeviceAPI::activate ( comm_settings file_descriptor,
const int &  id,
bool  activate_command 
)
inlinevirtual

Activate (or deactivate, according to the given command) the motors of the device connected to the serial port relative to the given file descriptor.

Do nothing if the file descriptor is wrong or not open.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device to be activated (or deactivated), in range [1, 128].
activate_commandtrue to turn motors on, false to turn them off.
See also
getStatus()

Definition at line 51 of file qb_device_driver.h.

virtual void qb_device_driver::qbDeviceAPI::close ( comm_settings file_descriptor)
inlinevirtual

Close the communication with all the devices connected to the serial port relative to the given file descriptor.

Do nothing if the file descriptor is wrong or not open.

Parameters
file_descriptorThe file descriptor of the serial port that has to be closed.
See also
open()

Definition at line 62 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::getCurrents ( comm_settings file_descriptor,
const int &  id,
std::vector< short int > &  currents 
)
inlinevirtual

Retrieve the motor currents of the given device.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
[out]currentsThe two-element device motor current vector, expressed in mA: if the device is a qbhand only the first element is filled while the other remains always 0; in the case of a qbmove both the elements contain relevant data, i.e. the currents respectively of motor_1 and motor_2.
Returns
0 on success.
See also
getMeasurements(), getPositions()

Definition at line 76 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::getDeviceIds ( comm_settings file_descriptor,
std::array< char, 255 > &  device_ids 
)
inlinevirtual

Retrieve the list of devices connected to the serial port of the given file descriptor.

Parameters
file_descriptorThe file descriptor of the serial port to be scanned.
device_idsThe retrieved device ID vector, each in range [1, 128].
Returns
The number of devices connected to the given serial port.
See also
getSerialPorts()

Definition at line 88 of file qb_device_driver.h.

virtual std::string qb_device_driver::qbDeviceAPI::getInfo ( comm_settings file_descriptor,
const int &  id 
)
inlinevirtual

Retrieve the printable configuration setup of the given device.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
Returns
The configuration setup formatted as a plain text string (empty string on communication error).
See also
getParameters()

Definition at line 99 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::getMeasurements ( comm_settings file_descriptor,
const int &  id,
std::vector< short int > &  measurements 
)
inlinevirtual

Retrieve the motor positions of the given device.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
[out]measurementsThe device measurements vector composed by:
  • The two-element device motor current vector, expressed in mA: if the device is a qbhand only the first element is filled while the other remains always 0; in the case of a qbmove both the elements contain relevant data, i.e. the currents respectively of motor_1 and motor_2.
  • The device position vector, expressed in ticks: if the device is a qbhand only the first element is filled while the others remain always 0; in the case of a qbmove all the elements contain relevant data, i.e. the positions respectively of motor_1, motor_2 and motor_shaft (which is not directly actuated).
Returns
0 on success.
See also
getCurrents(), getPositions()

Definition at line 142 of file qb_device_driver.h.

template<class T >
void qb_device_driver::qbDeviceAPI::getParameter ( const int &  parameter_id,
unsigned char *  parameter_buffer,
std::vector< int > &  parameter_vector 
)
inlineprivate

Extract the specified parameter from the given buffer where all the device parameters are stored.

Template Parameters
TThe data type of the single field of the parameter to be retrieved, e.g. int32_t.
Parameters
parameter_idThe specific value of the parameter to be retrieved, mapped in the device firmware.
[out]parameter_vectorThe vector where the values are stored (note: it is initially cleared).
See also
getParameters()

Definition at line 267 of file qb_device_driver.h.

template<class T >
void qb_device_driver::qbDeviceAPI::getParameter ( const int &  parameter_id,
unsigned char *  parameter_buffer,
std::vector< float > &  parameter_vector 
)
inlineprivate

Extract the specified parameter from the given buffer where all the device parameters are stored.

Template Parameters
TThe data type of the single field of the parameter to be retrieved, e.g. float.
Parameters
parameter_idThe specific value of the parameter to be retrieved, mapped in the device firmware.
[out]parameter_vectorThe vector where the values are stored (note: it is initially cleared).
See also
getParameters()

Definition at line 288 of file qb_device_driver.h.

virtual void qb_device_driver::qbDeviceAPI::getParameters ( comm_settings file_descriptor,
const int &  id,
std::vector< int > &  input_mode,
std::vector< int > &  control_mode,
std::vector< int > &  resolutions,
std::vector< int > &  limits 
)
inlinevirtual

Retrieve some of the parameters from the given device.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
[out]limitsThe vector of motor position limits expressed in ticks: two values for each motor, respectively [lower_limit, upper_limit].
[out]resolutionsThe vector of encoder resolutions, each in range [0, 8]: one value for each encoder (note: the qbmove has also the shaft encoder even if it is not actuated). The word "resolution" could be misunderstood: taken the resolution r, $2^r$ is the number of turns of the wire inside the device mechanics. It is used essentially to convert the measured position of the motors in ticks to radians or degrees.
See also
getParameter(), getInfo()

Definition at line 117 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::getPositions ( comm_settings file_descriptor,
const int &  id,
std::vector< short int > &  positions 
)
inlinevirtual

Retrieve the motor positions of the given device.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
[out]positionsThe device position vector, expressed in ticks: if the device is a qbhand only the first element is filled while the others remain always 0; in the case of a qbmove all the elements contain relevant data, i.e. the positions respectively of motor_1, motor_2 and motor_shaft (which is not directly actuated).
Returns
The number of positions retrieved, i.e. the number of encoder equipped on the given device.
See also
getMeasurements(), getCurrents()

Definition at line 158 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::getSerialPorts ( std::array< char[255], 10 > &  serial_ports)
inlinevirtual

Retrieve the list of serial ports connected to the system.

Each port of the type /dev/ttyUSB* connected to the system is considered a candidate to be scanned for qbrobotics devices.

Parameters
serial_portsThe array of serial ports connected to the system.
Returns
The number of serial ports connected to the system.
See also
getDeviceIds()

Definition at line 170 of file qb_device_driver.h.

virtual bool qb_device_driver::qbDeviceAPI::getStatus ( comm_settings file_descriptor,
const int &  id,
bool &  activate_status 
)
inlinevirtual

Retrieve the motor activation status of the given device.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
[out]activate_statustrue if motors are on, false if off.
Returns
true on success.
See also
activate()

Definition at line 182 of file qb_device_driver.h.

virtual bool qb_device_driver::qbDeviceAPI::getStatus ( comm_settings file_descriptor,
const int &  id 
)
inlinevirtual

Retrieve the connection status of the given device.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
[out]activate_statustrue if motors are on, false if off.
Returns
true on success.
See also
activate()

Definition at line 197 of file qb_device_driver.h.

virtual void qb_device_driver::qbDeviceAPI::open ( comm_settings file_descriptor,
const std::string &  serial_port 
)
inlinevirtual

Open the serial communication on the given serial port.

Parameters
[out]file_descriptorThe structure where the file descriptor has to be stored (filled with INVALID_HANDLE_VALUE on error).
serial_portThe serial port which has to be opened, e.g. /dev/ttyUSB0.
See also
close()

Definition at line 209 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::setCommandsAndWait ( comm_settings file_descriptor,
const int &  id,
std::vector< short int > &  commands 
)
inlinevirtual

Send the reference command to the motors of the given device and wait for acknowledge.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
commandsThe reference command vector, expressed in ticks: if the device is a qbhand only the first element is meaningful while the other remains always 0; in the case of a qbmove both the elements contain relevant data, i.e. the commands respectively of motor_1 and motor_2.
Returns
0 on success.
See also
setCommandsAsync()

Definition at line 223 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::setCommandsAsync ( comm_settings file_descriptor,
const int &  id,
std::vector< short int > &  commands 
)
inlinevirtual

Send the reference command to the motors of the given device in a non-blocking fashion.

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
commandsThe reference command vector, expressed in ticks: if the device is a qbhand only the first element is meaningful while the other remains always 0; in the case of a qbmove both the elements contain relevant data, i.e. the commands respectively of motor_1 and motor_2.
Returns
Always 0 (note that this is a non reliable method).
See also
setCommandsAndWait()

Definition at line 238 of file qb_device_driver.h.

virtual int qb_device_driver::qbDeviceAPI::setPID ( comm_settings file_descriptor,
const int &  id,
std::vector< float > &  pid 
)
inlinevirtual

Set the position control PID parameters of the given device, temporarily (until power off).

Parameters
file_descriptorThe file descriptor of the serial port on which the device is connected.
idThe ID of the device of interest, in range [1, 128].
pidThe three-element [P, I, D] vector of parameters to be set.
Returns
Always 0 (note that this is a non reliable method).

Definition at line 252 of file qb_device_driver.h.


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


qb_device_driver
Author(s): qbroboticsĀ®
autogenerated on Wed Oct 9 2019 03:45:42