Class qbDeviceCommunicationHandler

Class Documentation

class qbDeviceCommunicationHandler

The Communication Handler class is aimed to instantiate a ROS node which provides several ROS services to communicate with one - or many - qbrobotics devices connected to the ROS ecosystem.

Each hardware interface which manage a single qbrobotics device must first request the initialization of its ID to the Communication Handler and then interact with it through specific ROS services - blocking by nature. The Communication Handler essentially manage the shared serial port resources and lets all the hardware interfaces to get access to them. This could seem a bottleneck in the architecture, but the real bottleneck is the shared resource itself; moreover this structure is also necessary since the multi-process nature of ROS which does not easily allow to share common resources among distinct processes. Actually the implementation of qbrobotics classes could be reshaped to exploit the multi-threading approach, e.g. using nodelet or similar plugins each device node could handle the communication process by itself, without the intermediary Communication Handler. The advantage of such a restyle in term of communication speed does not worth the effort though.

Public Functions

qbDeviceCommunicationHandler(rclcpp::Node::SharedPtr &node)

Wait until at least one device is connected and then initialize the Communication Handler.

qbDeviceCommunicationHandler(bool scan, rclcpp::Node::SharedPtr &node)

Construct a new qb Device Communication Handler object.

Parameters:

scantrue if you want to scan serial ports and check the connection otherwise with false you will not either start the spinner

virtual ~qbDeviceCommunicationHandler()

Close all the still open serial ports.

See also

close()

Protected Functions

virtual int activate(const int &id, const int &max_repeats)

Activate the motors of the given device. Do nothing if the device is not connected in the Communication Handler.

See also

activateCallback(), activate(const int &, const bool &, const int &), isActive()

Parameters:
  • id – The ID of the device to be activated, in range [1, 128].

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

bool activateCallback(const std::shared_ptr<qb_device_msgs::srv::Trigger::Request> request, std::shared_ptr<qb_device_msgs::srv::Trigger::Response> response)

Activate the motors of the device relative to the node requesting the service.

Parameters:
  • request – The request of the given service (see qb_device_msgs::Trigger for details).

  • response – The response of the given service (see qb_device_msgs::Trigger for details).

Returns:

true if the call succeed (actually response.success may be false).

virtual int close(const std::string &serial_port)

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

See also

open(), qbrobotics_research_api::Communication::closeSerialPort

Parameters:

serial_port – The serial port which has to be closed, e.g. /dev/ttyUSB0.

void checkActivation()

Starts walltimer then check comunication

void checkConnectionAndPublish()

Called by check_connection_status_timer_. It verify if a qbdevice is connected or not

virtual int deactivate(const int &id, const int &max_repeats)

Deactivate the motors of the given device. Do nothing if the device is not connected in the Communication Handler.

See also

deactivateCallback(), activate(const int &, const bool &, const int &), isActive()

Parameters:
  • id – The ID of the device to be deactivated, in range [1, 128].

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

bool deactivateCallback(const std::shared_ptr<qb_device_msgs::srv::Trigger::Request> request, std::shared_ptr<qb_device_msgs::srv::Trigger::Response> response)

Deactivate the motors of the device relative to the node requesting the service.

See also

deactivate()

Parameters:
  • request – The request of the given service (see qb_device_msgs::Trigger for details).

  • response – The response of the given service (see qb_device_msgs::Trigger for details).

Returns:

true if the call succeed (actually response.success may be false).

virtual int getCurrents(const int &id, const int &max_repeats, std::vector<short int> &currents)

Retrieve the motor currents of the given device.

See also

qb_device_driver::qbDeviceAPI::getCurrents(), getMeasurementsCallback(), getMeasurements()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • currents[out] 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.

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

Returns:

The number of failure reads between 0 and max_repeats.

virtual int getInfo(const int &id, const int &max_repeats, std::string &info)

Retrieve the printable configuration setup of the given device.

See also

qb_device_driver::qbDeviceAPI::getInfo(), getInfoCallback(), getParameters()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

  • info – The configuration setup formatted as a plain text string (empty string on communication error).

Returns:

The number of failure reads between 0 and max_repeats.

bool getInfoCallback(const std::shared_ptr<qb_device_msgs::srv::Trigger::Request> request, std::shared_ptr<qb_device_msgs::srv::Trigger::Response> response)

Retrieve the printable configuration setup of the device relative to the node requesting the service.

See also

getInfo()

Parameters:
  • request – The request of the given service (see qb_device_msgs::Trigger for details).

  • response – The response of the given service (see qb_device_msgs::Trigger for details).

Returns:

true if the call succeed (actually response.success may be false).

virtual int getCommands(const int &id, const int &max_repeats, std::vector<short int> &commands)

Retrieve the reference command to the motors of the given device.

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • commands[out] The reference command vector, expressed in ticks: 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 commands respectively of motor_1 and motor_2.

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

Returns:

The number of commands retrieved, i.e. the number of motors equipped on the given device.

virtual int getMeasurements(const int &id, const int &max_repeats, std::vector<short int> &currents, std::vector<short int> &positions)

Retrieve the motor currents of the given device.

See also

qb_device_driver::qbDeviceAPI::getMeasurements(), getMeasurementsCallback(), getCurrents(), getPositions()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • currents[out] 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.

  • positions[out] 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).

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

Returns:

The number of failure reads between 0 and max_repeats.

bool getMeasurementsCallback(const std::shared_ptr<qb_device_msgs::srv::GetMeasurements::Request> request, std::shared_ptr<qb_device_msgs::srv::GetMeasurements::Response> response)

Retrieve the motor positions and currents of the device relative to the node requesting the service.

Parameters:
  • request – The request of the given service (see qb_device_msgs::GetMeasurements for details).

  • response – The response of the given service (see qb_device_msgs::GetMeasurements for details).

Returns:

true if the call succeed (actually response.success may be false).

virtual int getParameters(const int &id, std::vector<int32_t> &limits, std::vector<uint8_t> &resolutions)

Retrieve some of the parameters from the given device.

See also

qb_device_driver::qbDeviceAPI::getParameters(), getInfo(), initializeCallback()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • limits[out] The vector of motor position limits expressed in ticks: two values for each motor, respectively [lower_limit, upper_limit].

  • resolutions[out] The 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.

Returns:

0 on success.

virtual int getPositions(const int &id, const int &max_repeats, std::vector<short int> &positions)

Retrieve the motor positions of the given device.

See also

qb_device_driver::qbDeviceAPI::getPositions(), getMeasurementsCallback(), getMeasurements()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • positions[out] 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).

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

Returns:

The number of failure reads between 0 and max_repeats.

virtual int getSerialPortsAndDevices(const int &max_repeats)

Scan for all the serial ports of type /dev/ttyUSB* detected in the system and retrieve all the qbrobotics devices connected to them. For each device, store its ID in the private map connected_devices_, i.e. insert a pair [device_id, serial_port]. The map connected_devices_ is constructed from scratch at each call.

See also

open(), qbrobotics_research_api::Communication::listSerialPorts, qbrobotics_research_api::Communication::listConnectedDevices, close()

Parameters:

max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

Returns:

the number of connected devices.

virtual int isActive(const int &id, const int &max_repeats, bool &status)

Check whether the motors of the device specified by the given ID are active.

See also

qbrobotics_research_api::getMotorStates()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

  • statustrue if the device motors are on.

Returns:

The number of failure reads between 0 and max_repeats.

virtual int isConnected(const int &id, const int &max_repeats)

Check whether the the device specified by the given ID is connected through the serial port.

See also

qb_device_driver::qbDeviceAPI::getStatus()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

Returns:

The number of failure reads between 0 and max_repeats.

virtual bool isInConnectedSet(const int &id)

Check whether the physical device specified by the given ID is connected to the Communication Handler.

Parameters:

id – The ID of the device of interest, in range [1, 128].

Returns:

true if the given device belongs to the connected device vector, i.e. connected_devices_.

virtual bool initializeCallback(const std::shared_ptr<qb_device_msgs::srv::InitializeDevice::Request> request, std::shared_ptr<qb_device_msgs::srv::InitializeDevice::Response> response)

Check whether the given serial port is managed by the Communication Handler, i.e. is open.

See also

open(), close() Initialize the device node requesting the service to the Communication Handler if the relative physical device is connected through any serial port to the system (can re-scan the serial resources if specified in the request). If the device is found, retrieve some of its parameter and activate its motors, if requested.

Parameters:
  • serial_port – The name of the serial port of interest, e.g. /dev/ttyUSB0.

  • request – The request of the given service (see qb_device_msgs::InitializeDevice for details).

  • response – The response of the given service (see qb_device_msgs::InitializeDevice for details).

Returns:

true if the given serial port belongs to the open file descriptor map, i.e. file_descriptors_.

Returns:

true if the call succeed (actually response.success may be false).

virtual int setCommandsAndWait(const int &id, const int &max_repeats, std::vector<short int> &commands)

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

See also

qb_device_driver::qbDeviceAPI::setCommandsAndWait(), setCommandsCallback()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • max_repeats – The maximum number of consecutive repetitions to mark retrieved data as corrupted.

  • commands – The 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.

virtual int setCommandsAsync(const int &id, std::vector<short int> &commands)

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

See also

qb_device_driver::qbDeviceAPI::setCommandsAsync(), setCommandsCallback()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • commands – The 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).

bool setCommandsCallback(const std::shared_ptr<qb_device_msgs::srv::SetCommands::Request> request, std::shared_ptr<qb_device_msgs::srv::SetCommands::Response> response)

Send the reference command to the motors of the device relative to the node requesting the service.

Parameters:
  • request – The request of the given service (see qb_device_msgs::SetCommands for details).

  • response – The response of the given service (see qb_device_msgs::SetCommands for details).

Returns:

true if the call succeed (actually response.success may be false).

int setPID(const int &id, const int &max_repeats, std::vector<float> &pid)

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

See also

qb_device_driver::qbDeviceAPI::setPID(), setPIDCallback()

Parameters:
  • file_descriptor – The file descriptor of the serial port on which the device is connected.

  • id – The ID of the device of interest, in range [1, 128].

  • pid – The three-element [P, I, D] vector of parameters to be set.

Returns:

Always 0 (note that this is a non reliable method).

bool setPIDCallback(const std::shared_ptr<qb_device_msgs::srv::SetPid::Request> request, std::shared_ptr<qb_device_msgs::srv::SetPid::Response> response)

Set (temporarily, i.e. until power off) the position control PID parameters of the device relative to the node requesting the service.

See also

setPID()

Parameters:
  • request – The request of the given service (see qb_device_msgs::SetPid for details).

  • response – The response of the given service (see qb_device_msgs::SetPid for details).

Returns:

true if the call succeed (actually response.success may be false).

int setControlMode(const int &id, const int &max_repeats, uint8_t &control_id)

Set control mode for qbmove.

See also

qb_device_driver::qbDeviceAPI::setPID(), setPIDCallback()

Parameters:
  • id – The ID of the device of interest, in range [1, 128].

  • control_id – the control id for qbmove: 0 -> POSITION, 4 -> DEFLECTION.

Returns:

Always 0 (note that this is a non reliable method).

bool setControlModeCallback(const std::shared_ptr<qb_device_msgs::srv::SetControlMode::Request> request, std::shared_ptr<qb_device_msgs::srv::SetControlMode::Response> response)

Set (temporarily, i.e. until power off) the control mode parameters of the device relative to the node requesting the service.

See also

setControlMode()

Parameters:
  • request – The request of the given service (see qb_device_msgs::setControlMode for details).

  • response – The response of the given service (see qb_device_msgs::setControlMode for details).

Returns:

true if the call succeed (actually response.success may be false).

bool goToHomeCallback(const std::shared_ptr<qb_device_msgs::srv::Trigger::Request> request, std::shared_ptr<qb_device_msgs::srv::Trigger::Response> response)

Send the device to HOME position.

Warning

if this service is used while a trajectory for the device is defined, the device will move to home and then will return to the position preceding the call of this service. In such a case, use the service in qbdevice_control.

Parameters:
  • request – The request of the given service (see qb_device_msgs::setControlMode for details).

  • response – The response of the given service (see qb_device_msgs::setControlMode for details).

Returns:

true if the call succeed (actually response.success may be false).

Protected Attributes

rclcpp::Node::SharedPtr node_handle_
std::map<std::string, std::unique_ptr<std::mutex>> serial_protectors_
std::map<int, std::string> connected_devices_
std::shared_ptr<qbrobotics_research_api::Communication> communication_handler_
std::shared_ptr<qbrobotics_research_api::Communication> communication_handler_legacy_
std::vector<serial::PortInfo> serial_ports_
std::map<int, std::shared_ptr<qbrobotics_research_api::Device>> devices_
std::vector<qbrobotics_research_api::Communication::ConnectedDeviceInfo> device_ids_