Classes | Public Member Functions | Protected Attributes | List of all members
qbrobotics_research_api::Device Class Reference

General class that allow to get/set parameters from/to qbrobotics devices. More...

#include <qbrobotics_research_api.h>

Inheritance diagram for qbrobotics_research_api::Device:
Inheritance graph
[legend]

Classes

class  Params
 Manage qbrobotics devices parameters. More...
 

Public Member Functions

 Device (std::shared_ptr< Communication > communication, std::string name, std::string serial_port, uint8_t id)
 
 Device (std::shared_ptr< Communication > communication, std::string name, std::string serial_port, uint8_t id, bool init_params)
 
 Device (std::shared_ptr< Communication > communication, std::string name, std::string serial_port, uint8_t id, bool init_params, std::unique_ptr< Params > params)
 
virtual int getAccelerations (std::vector< int16_t > &accelerations)
 Get the motor(s) acceleration(s) More...
 
virtual int getControlReferences (std::vector< int16_t > &control_references)
 Get the reference command sent to the motor(s) of the device. More...
 
virtual int getCurrents (std::vector< int16_t > &currents)
 Get the device current(s) absorbed by the motor(s) More...
 
virtual int getCurrentsAndPositions (std::vector< int16_t > &currents, std::vector< int16_t > &positions)
 Get the device currents absorbed by the motor(s) and its/their position(s) More...
 
virtual int getCycleTime (int16_t &cycle_time)
 
virtual int getInfo (std::string &info)
 Get all system information. More...
 
virtual int getInfo (uint16_t info_type, std::string &info)
 Get the Info of the device. More...
 
virtual int getMotorStates (bool &motor_state)
 Get the device motor state. More...
 
virtual int getParamControlMode ()
 Update the device control mode in the class variable param_. More...
 
virtual int getParamControlMode (uint8_t &control_mode)
 Get the control mode parameter. More...
 
virtual int getParamCurrentLimit ()
 Update the current limits parameters in the class variable param_. More...
 
virtual int getParamCurrentLimit (int16_t &current_limit)
 Get current limit parameter. More...
 
virtual int getParamCurrentPID ()
 Update the device current PID parameters in the class variable param_. More...
 
virtual int getParamCurrentPID (std::vector< float > &current_pid)
 Get the device current PID parameters. More...
 
virtual int getParamEncoderMultipliers ()
 Update the device encoder multipliers in the class variable param_. More...
 
virtual int getParamEncoderMultipliers (std::vector< float > &encoder_multipliers)
 Get the encoder multipliers parameters. More...
 
virtual int getParamEncoderOffsets ()
 Update the device encoder offsets in the class variable param_. More...
 
virtual int getParamEncoderOffsets (std::vector< int16_t > &encoder_offsets)
 Get the encoder offsets parameters. More...
 
virtual int getParamEncoderResolutions ()
 Update the device encoder resolutions in the class variable param_. More...
 
virtual int getParamEncoderResolutions (std::vector< uint8_t > &encoder_resolutions)
 Get the encoder resolution parameters. More...
 
virtual int getParameters (std::vector< int8_t > &param_buffer)
 Get the parameters from the device. More...
 
virtual int getParameters (uint8_t id, std::vector< int8_t > &param_buffer)
 Get the parameters from the device with ID id. More...
 
virtual int getParamId ()
 Update the device ID in the class variable param_. More...
 
virtual int getParamId (uint8_t &id)
 Get the device ID. More...
 
virtual int getParamInputMode ()
 Get the input mode parameter in the class variable param_. More...
 
virtual int getParamInputMode (uint8_t &input_mode)
 Get the input parameter to the correspective value of the input mode. More...
 
virtual int getParamPositionLimits ()
 Update the position limits parameters in the class variable param_. More...
 
virtual int getParamPositionLimits (std::vector< int32_t > &position_limits)
 Get position limits parameters. More...
 
virtual int getParamPositionMaxSteps ()
 Update the max step position parameters in the class variable param_. More...
 
virtual int getParamPositionMaxSteps (std::vector< int32_t > &position_max_steps)
 Get max steps position parameters. More...
 
virtual int getParamPositionPID ()
 Update the device position PID parameters in the class variable param_. More...
 
virtual int getParamPositionPID (std::vector< float > &position_pid)
 Get the device position PID parameters. More...
 
std::shared_ptr< ParamsgetParams ()
 
virtual int getParamStartupActivation ()
 Update the startup activation parameter in the class variable param_. More...
 
virtual int getParamStartupActivation (uint8_t &startup_activation)
 Get the startup activation parameter. More...
 
virtual int getParamUsePositionLimits ()
 Update the the use of position limits in the class variable param_. More...
 
virtual int getParamUsePositionLimits (uint8_t &use_position_limits)
 Get the use of position limits parameter. More...
 
virtual int getPositions (std::vector< int16_t > &positions)
 Get the Positions given by the encoders mounted on the device. More...
 
virtual int getVelocities (std::vector< int16_t > &velocities)
 Get the motor(s) velocitie(s) More...
 
bool isQbmove ()
 
bool isSH2M ()
 
bool isSHPRO ()
 
virtual int ping ()
 
virtual int restoreFactoryDataMemory ()
 Restore factory parameter on 7.X.X firmware devices. More...
 
virtual int restoreUserDataMemory ()
 Restore user parameter on 7.X.X firmware devices. More...
 
virtual int setBootloaderMode ()
 Set the bootloader mode. More...
 
virtual int setControlReferences (const std::vector< int16_t > &control_references)
 Set motor(s) control reference - position[tick]. More...
 
virtual int setControlReferencesAndWait (const std::vector< int16_t > &control_references)
 Set motor(s) control reference and wait for acknowledge - position[tick](only for legacy qbmoves) More...
 
virtual int setMotorStates (bool motor_state)
 Activate or deactivate the motor(s) More...
 
virtual int setParamBaudrate (uint8_t prescaler_divider)
 Set the device baud rate. More...
 
virtual int setParamControlMode (uint8_t control_mode)
 Set the control mode parameter of the device. More...
 
virtual int setParamCurrentLimit (int16_t current_limit)
 Set the cerrent limit parameter of the device. More...
 
virtual int setParamCurrentPID (const std::vector< float > &current_pid)
 Set the current PID parameters of the device. More...
 
virtual int setParamEncoderMultipliers (const std::vector< float > &encoder_multipliers)
 Set the encoder multipliers parameters of the device. More...
 
virtual int setParamEncoderOffsets (const std::vector< int16_t > &encoder_offsets)
 Set the encoder offsets parameters of the device. More...
 
virtual int setParamEncoderResolutions (const std::vector< uint8_t > &encoder_resolutions)
 Set the encoder resolutions parameters of the device. More...
 
virtual int setParameter (uint16_t param_type, const std::vector< int8_t > &param_data)
 Set the Parameter specified by param_type with the values stored in param_data. More...
 
virtual int setParamId (uint8_t id)
 Set the ID of the device. More...
 
virtual int setParamInputMode (uint8_t input_mode)
 Set the input mode parameter of the device. More...
 
virtual int setParamPositionLimits (const std::vector< int32_t > &position_limits)
 Set the position limits parameters of the device. More...
 
virtual int setParamPositionMaxSteps (const std::vector< int32_t > &position_max_steps)
 Set the position max steps parameters of the device. More...
 
virtual int setParamPositionPID (const std::vector< float > &position_pid)
 Set the position PID parameters of the device. More...
 
virtual int setParamStartupActivation (bool startup_activation)
 Set the startup activation parameter of the device. More...
 
virtual int setParamUsePositionLimits (bool use_position_limits)
 Enable or disable the use of position limits. More...
 
virtual int setParamZeros ()
 Set motor(s) zero(s) to actual encoder reading. More...
 
virtual int storeFactoryDataMemory ()
 Store the changed parameters on 7.X.X firmware devices in factory memory. More...
 
virtual int storeUserDataMemory ()
 Store the changed parameters on 7.X.X firmware devices in user memory. More...
 
virtual ~Device ()=default
 

Protected Attributes

std::shared_ptr< Communicationcommunication_
 
std::string name_
 
std::shared_ptr< Paramsparams_
 
std::string serial_port_
 

Detailed Description

General class that allow to get/set parameters from/to qbrobotics devices.

Definition at line 268 of file qbrobotics_research_api.h.

Constructor & Destructor Documentation

◆ Device() [1/3]

Device::Device ( std::shared_ptr< Communication communication,
std::string  name,
std::string  serial_port,
uint8_t  id 
)
explicit

Definition at line 611 of file qbrobotics_research_api.cpp.

◆ Device() [2/3]

Device::Device ( std::shared_ptr< Communication communication,
std::string  name,
std::string  serial_port,
uint8_t  id,
bool  init_params 
)
explicit

Definition at line 614 of file qbrobotics_research_api.cpp.

◆ Device() [3/3]

Device::Device ( std::shared_ptr< Communication communication,
std::string  name,
std::string  serial_port,
uint8_t  id,
bool  init_params,
std::unique_ptr< Params params 
)
explicit

Definition at line 617 of file qbrobotics_research_api.cpp.

◆ ~Device()

virtual qbrobotics_research_api::Device::~Device ( )
virtualdefault

Member Function Documentation

◆ getAccelerations()

int Device::getAccelerations ( std::vector< int16_t > &  accelerations)
virtual

Get the motor(s) acceleration(s)

Parameters
[out]accelerations[tick/s^2]vector passed by reference
Returns
0 on success, -1 on error

Definition at line 687 of file qbrobotics_research_api.cpp.

◆ getControlReferences()

int Device::getControlReferences ( std::vector< int16_t > &  control_references)
virtual

Get the reference command sent to the motor(s) of the device.

Parameters
[out]control_references[tick]vector passed by reference
Returns
0 on success, -1 on error

Reimplemented in qbrobotics_research_api::qbmoveLegacyResearch.

Definition at line 639 of file qbrobotics_research_api.cpp.

◆ getCurrents()

int Device::getCurrents ( std::vector< int16_t > &  currents)
virtual

Get the device current(s) absorbed by the motor(s)

Parameters
[out]currents[mA]vector passed by reference
Returns
0 on success, -1 on error

Definition at line 648 of file qbrobotics_research_api.cpp.

◆ getCurrentsAndPositions()

int Device::getCurrentsAndPositions ( std::vector< int16_t > &  currents,
std::vector< int16_t > &  positions 
)
virtual

Get the device currents absorbed by the motor(s) and its/their position(s)

Parameters
[out]currents[mA]vector passed by reference
[out]positions[tick]vector passed by reference
Returns
0 on success, -1 on error

Definition at line 657 of file qbrobotics_research_api.cpp.

◆ getCycleTime()

int Device::getCycleTime ( int16_t &  cycle_time)
virtual

Definition at line 708 of file qbrobotics_research_api.cpp.

◆ getInfo() [1/2]

int Device::getInfo ( std::string &  info)
virtual

Get all system information.

Parameters
[out]infostd::string passed by reference
Returns
0 on success, -1 on error

Definition at line 745 of file qbrobotics_research_api.cpp.

◆ getInfo() [2/2]

int Device::getInfo ( uint16_t  info_type,
std::string &  info 
)
virtual

Get the Info of the device.

Parameters
info_type- 0 All system information; - 1 Cycles information; - 2 Read Firmware Parameters from SD file; - 3 Read Usage Data from SD file.
info[out]std::string passed by reference
Returns
0 on success, -1 on error

Definition at line 749 of file qbrobotics_research_api.cpp.

◆ getMotorStates()

int Device::getMotorStates ( bool &  motor_state)
virtual

Get the device motor state.

Parameters
[out]motor_stateboolean passed by reference
Returns
0 on success, -1 on error

Definition at line 696 of file qbrobotics_research_api.cpp.

◆ getParamControlMode() [1/2]

int Device::getParamControlMode ( )
virtual

Update the device control mode in the class variable param_.

  • 0 - Classic position control
  • 1 - Direct PWM value
  • 2 - Current control
  • 3 - Position and current control
  • 4 - Deflection control (only for qbmoves)
  • 5 - Deflection and current control (only for qbmoves)
    Returns
    0 on success, -1 on error

Definition at line 837 of file qbrobotics_research_api.cpp.

◆ getParamControlMode() [2/2]

int Device::getParamControlMode ( uint8_t &  control_mode)
virtual

Get the control mode parameter.

Parameters
[out]control_mode
  • 0 - Classic position control
  • 1 - Direct PWM value
  • 2 - Current control
  • 3 - Position and current control
  • 4 - Deflection control (only for qbmoves)
  • 5 - Deflection and current control (only for qbmoves)
Returns
0 on success, -1 on error

Definition at line 841 of file qbrobotics_research_api.cpp.

◆ getParamCurrentLimit() [1/2]

int Device::getParamCurrentLimit ( )
virtual

Update the current limits parameters in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 928 of file qbrobotics_research_api.cpp.

◆ getParamCurrentLimit() [2/2]

int Device::getParamCurrentLimit ( int16_t &  current_limit)
virtual

Get current limit parameter.

Parameters
[out]current_limit[mA]
Returns
0 on success, -1 on error

Definition at line 932 of file qbrobotics_research_api.cpp.

◆ getParamCurrentPID() [1/2]

int Device::getParamCurrentPID ( )
virtual

Update the device current PID parameters in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 798 of file qbrobotics_research_api.cpp.

◆ getParamCurrentPID() [2/2]

int Device::getParamCurrentPID ( std::vector< float > &  current_pid)
virtual

Get the device current PID parameters.

Parameters
[out]current_pid
Returns
0 on success, -1 on error

Definition at line 802 of file qbrobotics_research_api.cpp.

◆ getParamEncoderMultipliers() [1/2]

int Device::getParamEncoderMultipliers ( )
virtual

Update the device encoder multipliers in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 876 of file qbrobotics_research_api.cpp.

◆ getParamEncoderMultipliers() [2/2]

int Device::getParamEncoderMultipliers ( std::vector< float > &  encoder_multipliers)
virtual

Get the encoder multipliers parameters.

Parameters
[out]encoder_multipliers
Returns
0 on success, -1 on error

Definition at line 880 of file qbrobotics_research_api.cpp.

◆ getParamEncoderOffsets() [1/2]

int Device::getParamEncoderOffsets ( )
virtual

Update the device encoder offsets in the class variable param_.

Returns
0 on success, -1 on error

Reimplemented in qbrobotics_research_api::qbmoveLegacyResearch, and qbrobotics_research_api::qbSoftHand2MotorsResearch.

Definition at line 863 of file qbrobotics_research_api.cpp.

◆ getParamEncoderOffsets() [2/2]

int Device::getParamEncoderOffsets ( std::vector< int16_t > &  encoder_offsets)
virtual

Get the encoder offsets parameters.

Parameters
[out]encoder_offsets
Returns
0 on success, -1 on error

Reimplemented in qbrobotics_research_api::qbmoveLegacyResearch, and qbrobotics_research_api::qbSoftHand2MotorsResearch.

Definition at line 867 of file qbrobotics_research_api.cpp.

◆ getParamEncoderResolutions() [1/2]

int Device::getParamEncoderResolutions ( )
virtual

Update the device encoder resolutions in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 850 of file qbrobotics_research_api.cpp.

◆ getParamEncoderResolutions() [2/2]

int Device::getParamEncoderResolutions ( std::vector< uint8_t > &  encoder_resolutions)
virtual

Get the encoder resolution parameters.

Parameters
[out]encoder_resolutions
Returns
0 on success, -1 on error

Definition at line 854 of file qbrobotics_research_api.cpp.

◆ getParameters() [1/2]

int Device::getParameters ( std::vector< int8_t > &  param_buffer)
virtual

Get the parameters from the device.

Parameters
[out]param_buffervector passed by reference
Returns
0 on success, -1 on error

Definition at line 759 of file qbrobotics_research_api.cpp.

◆ getParameters() [2/2]

int Device::getParameters ( uint8_t  id,
std::vector< int8_t > &  param_buffer 
)
virtual

Get the parameters from the device with ID id.

Parameters
[out]iddevice ID
[out]param_buffervector passed by reference
Returns
0 on success, -1 on error
See also
getParameters(uint8_t id, std::vector<int8_t> &param_buffer)

Definition at line 763 of file qbrobotics_research_api.cpp.

◆ getParamId() [1/2]

int Device::getParamId ( )
virtual

Update the device ID in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 772 of file qbrobotics_research_api.cpp.

◆ getParamId() [2/2]

int Device::getParamId ( uint8_t &  id)
virtual

Get the device ID.

Parameters
[out]iddevice ID
Returns
0 on success, -1 on error
See also
getParameters(uint8_t id, std::vector<int8_t> &param_buffer)

Definition at line 776 of file qbrobotics_research_api.cpp.

◆ getParamInputMode() [1/2]

int Device::getParamInputMode ( )
virtual

Get the input mode parameter in the class variable param_.

These values are:

  • 0 - References through external commands
  • 1 - Encoder 3 drives all inputs
  • 2 - Use EMG measure to proportionally drive the position of the motor 1
  • 3 - Use 2 EMG signals to drive motor position
  • 4 - Use 2 EMG. First reaching threshold wins and its value defines hand closure
  • 5 - Use 2 EMG. First reaching threshold wins and its value defines hand closure. Wait for both EMG to lower under threshold
Returns
0 on success, -1 on error

Definition at line 824 of file qbrobotics_research_api.cpp.

◆ getParamInputMode() [2/2]

int Device::getParamInputMode ( uint8_t &  input_mode)
virtual

Get the input parameter to the correspective value of the input mode.

Parameters
[out]input_modeThe possible values are:
  • 0 - References through external commands
  • 1 - Encoder 3 drives all inputs
  • 2 - Use EMG measure to proportionally drive the position of the motor 1
  • 3 - Use 2 EMG signals to drive motor position
  • 4 - Use 2 EMG. First reaching threshold wins and its value defines hand closure
  • 5 - Use 2 EMG. First reaching threshold wins and its value defines hand closure. Wait for both EMG to lower under threshold
Returns
0 on success, -1 on error

Definition at line 828 of file qbrobotics_research_api.cpp.

◆ getParamPositionLimits() [1/2]

int Device::getParamPositionLimits ( )
virtual

Update the position limits parameters in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 902 of file qbrobotics_research_api.cpp.

◆ getParamPositionLimits() [2/2]

int Device::getParamPositionLimits ( std::vector< int32_t > &  position_limits)
virtual

Get position limits parameters.

Parameters
[out]position_limits
Returns
0 on success, -1 on error

Definition at line 906 of file qbrobotics_research_api.cpp.

◆ getParamPositionMaxSteps() [1/2]

int Device::getParamPositionMaxSteps ( )
virtual

Update the max step position parameters in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 915 of file qbrobotics_research_api.cpp.

◆ getParamPositionMaxSteps() [2/2]

int Device::getParamPositionMaxSteps ( std::vector< int32_t > &  position_max_steps)
virtual

Get max steps position parameters.

Parameters
[out]position_max_steps
Returns
0 on success, -1 on error

Definition at line 919 of file qbrobotics_research_api.cpp.

◆ getParamPositionPID() [1/2]

int Device::getParamPositionPID ( )
virtual

Update the device position PID parameters in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 785 of file qbrobotics_research_api.cpp.

◆ getParamPositionPID() [2/2]

int Device::getParamPositionPID ( std::vector< float > &  position_pid)
virtual

Get the device position PID parameters.

Parameters
[out]position_pid
Returns
0 on success, -1 on error

Definition at line 789 of file qbrobotics_research_api.cpp.

◆ getParams()

std::shared_ptr<Params> qbrobotics_research_api::Device::getParams ( )
inline

Definition at line 844 of file qbrobotics_research_api.h.

◆ getParamStartupActivation() [1/2]

int Device::getParamStartupActivation ( )
virtual

Update the startup activation parameter in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 811 of file qbrobotics_research_api.cpp.

◆ getParamStartupActivation() [2/2]

int Device::getParamStartupActivation ( uint8_t &  startup_activation)
virtual

Get the startup activation parameter.

Parameters
[out]startup_activation
Returns
0 on success, -1 on error

Definition at line 815 of file qbrobotics_research_api.cpp.

◆ getParamUsePositionLimits() [1/2]

int Device::getParamUsePositionLimits ( )
virtual

Update the the use of position limits in the class variable param_.

Returns
0 on success, -1 on error

Definition at line 889 of file qbrobotics_research_api.cpp.

◆ getParamUsePositionLimits() [2/2]

int Device::getParamUsePositionLimits ( uint8_t &  use_position_limits)
virtual

Get the use of position limits parameter.

Parameters
[out]use_position_limits0 false, 1 true
Returns
0 on success, -1 on error

Definition at line 893 of file qbrobotics_research_api.cpp.

◆ getPositions()

int Device::getPositions ( std::vector< int16_t > &  positions)
virtual

Get the Positions given by the encoders mounted on the device.

Parameters
[out]positions[tick]vector passed by reference
Returns
0 on success, -1 on error

Definition at line 669 of file qbrobotics_research_api.cpp.

◆ getVelocities()

int Device::getVelocities ( std::vector< int16_t > &  velocities)
virtual

Get the motor(s) velocitie(s)

Parameters
[out]velocities[tick/s]vector passed by reference
Returns
0 on success, -1 on error

Definition at line 678 of file qbrobotics_research_api.cpp.

◆ isQbmove()

bool qbrobotics_research_api::Device::isQbmove ( )
inline

Definition at line 845 of file qbrobotics_research_api.h.

◆ isSH2M()

bool qbrobotics_research_api::Device::isSH2M ( )
inline

Definition at line 847 of file qbrobotics_research_api.h.

◆ isSHPRO()

bool qbrobotics_research_api::Device::isSHPRO ( )
inline

Definition at line 846 of file qbrobotics_research_api.h.

◆ ping()

int Device::ping ( )
virtual

Definition at line 635 of file qbrobotics_research_api.cpp.

◆ restoreFactoryDataMemory()

int Device::restoreFactoryDataMemory ( )
virtual

Restore factory parameter on 7.X.X firmware devices.

For 6.X.X it executes INIT_MEM command

Returns
0 on success, <0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1096 of file qbrobotics_research_api.cpp.

◆ restoreUserDataMemory()

int Device::restoreUserDataMemory ( )
virtual

Restore user parameter on 7.X.X firmware devices.

Warning
not use it in 6.X.X devices.
Returns
0 on success, <0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1110 of file qbrobotics_research_api.cpp.

◆ setBootloaderMode()

int Device::setBootloaderMode ( )
virtual

Set the bootloader mode.

Returns
0 on success, <0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1146 of file qbrobotics_research_api.cpp.

◆ setControlReferences()

int Device::setControlReferences ( const std::vector< int16_t > &  control_references)
virtual

Set motor(s) control reference - position[tick].

Parameters
control_references[tick]
Returns
0 on success, -1 on error

Definition at line 717 of file qbrobotics_research_api.cpp.

◆ setControlReferencesAndWait()

int Device::setControlReferencesAndWait ( const std::vector< int16_t > &  control_references)
virtual

Set motor(s) control reference and wait for acknowledge - position[tick](only for legacy qbmoves)

Parameters
control_references[tick]
Returns
0 on success, -1 on error

Definition at line 725 of file qbrobotics_research_api.cpp.

◆ setMotorStates()

int Device::setMotorStates ( bool  motor_state)
virtual

Activate or deactivate the motor(s)

Parameters
motor_statethe desired motor(s) state(s)
Returns
0 on success, -1 on error

Reimplemented in qbrobotics_research_api::qbSoftHandLegacyResearch, qbrobotics_research_api::qbmoveLegacyResearch, and qbrobotics_research_api::qbSoftHand2MotorsResearch.

Definition at line 737 of file qbrobotics_research_api.cpp.

◆ setParamBaudrate()

int Device::setParamBaudrate ( uint8_t  prescaler_divider)
virtual

Set the device baud rate.

Parameters
prescaler_divider
Returns
0 on success, -1 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1071 of file qbrobotics_research_api.cpp.

◆ setParamControlMode()

int Device::setParamControlMode ( uint8_t  control_mode)
virtual

Set the control mode parameter of the device.

Parameters
control_mode
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 999 of file qbrobotics_research_api.cpp.

◆ setParamCurrentLimit()

int Device::setParamCurrentLimit ( int16_t  current_limit)
virtual

Set the cerrent limit parameter of the device.

Parameters
current_limit
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1055 of file qbrobotics_research_api.cpp.

◆ setParamCurrentPID()

int Device::setParamCurrentPID ( const std::vector< float > &  current_pid)
virtual

Set the current PID parameters of the device.

Parameters
current_piddesired device PID(current) parameters
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 975 of file qbrobotics_research_api.cpp.

◆ setParamEncoderMultipliers()

int Device::setParamEncoderMultipliers ( const std::vector< float > &  encoder_multipliers)
virtual

Set the encoder multipliers parameters of the device.

Parameters
encoder_multipliers
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1023 of file qbrobotics_research_api.cpp.

◆ setParamEncoderOffsets()

int Device::setParamEncoderOffsets ( const std::vector< int16_t > &  encoder_offsets)
virtual

Set the encoder offsets parameters of the device.

Parameters
encoder_offsets
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Reimplemented in qbrobotics_research_api::qbmoveLegacyResearch, and qbrobotics_research_api::qbSoftHand2MotorsResearch.

Definition at line 1015 of file qbrobotics_research_api.cpp.

◆ setParamEncoderResolutions()

int Device::setParamEncoderResolutions ( const std::vector< uint8_t > &  encoder_resolutions)
virtual

Set the encoder resolutions parameters of the device.

Parameters
encoder_resolutions
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1007 of file qbrobotics_research_api.cpp.

◆ setParameter()

int Device::setParameter ( uint16_t  param_type,
const std::vector< int8_t > &  param_data 
)
virtual

Set the Parameter specified by param_type with the values stored in param_data.

Parameters
param_typeID of the parameter to be set
param_datavalue(s) to be set
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Reimplemented in qbrobotics_research_api::qbSoftHandLegacyResearch, qbrobotics_research_api::qbmoveLegacyResearch, and qbrobotics_research_api::qbSoftHand2MotorsResearch.

Definition at line 941 of file qbrobotics_research_api.cpp.

◆ setParamId()

int Device::setParamId ( uint8_t  id)
virtual

Set the ID of the device.

Parameters
iddesired device ID
Returns
0 on success, < 0 on error

Reimplemented in qbrobotics_research_api::qbSoftHandLegacyResearch, qbrobotics_research_api::qbmoveLegacyResearch, and qbrobotics_research_api::qbSoftHand2MotorsResearch.

Definition at line 959 of file qbrobotics_research_api.cpp.

◆ setParamInputMode()

int Device::setParamInputMode ( uint8_t  input_mode)
virtual

Set the input mode parameter of the device.

Parameters
input_mode
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 991 of file qbrobotics_research_api.cpp.

◆ setParamPositionLimits()

int Device::setParamPositionLimits ( const std::vector< int32_t > &  position_limits)
virtual

Set the position limits parameters of the device.

Parameters
position_limits
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1039 of file qbrobotics_research_api.cpp.

◆ setParamPositionMaxSteps()

int Device::setParamPositionMaxSteps ( const std::vector< int32_t > &  position_max_steps)
virtual

Set the position max steps parameters of the device.

Parameters
position_max_steps
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1047 of file qbrobotics_research_api.cpp.

◆ setParamPositionPID()

int Device::setParamPositionPID ( const std::vector< float > &  position_pid)
virtual

Set the position PID parameters of the device.

Parameters
position_piddesired device PID(position) parameters
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 967 of file qbrobotics_research_api.cpp.

◆ setParamStartupActivation()

int Device::setParamStartupActivation ( bool  startup_activation)
virtual

Set the startup activation parameter of the device.

Parameters
startup_activation
Returns
0 on success, < 0 on error

Definition at line 983 of file qbrobotics_research_api.cpp.

◆ setParamUsePositionLimits()

int Device::setParamUsePositionLimits ( bool  use_position_limits)
virtual

Enable or disable the use of position limits.

Parameters
use_position_limits
Returns
0 on success, < 0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1031 of file qbrobotics_research_api.cpp.

◆ setParamZeros()

int Device::setParamZeros ( )
virtual

Set motor(s) zero(s) to actual encoder reading.

Returns
0 on success, -1 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Reimplemented in qbrobotics_research_api::qbSoftHandLegacyResearch, qbrobotics_research_api::qbmoveLegacyResearch, and qbrobotics_research_api::qbSoftHand2MotorsResearch.

Definition at line 1063 of file qbrobotics_research_api.cpp.

◆ storeFactoryDataMemory()

int Device::storeFactoryDataMemory ( )
virtual

Store the changed parameters on 7.X.X firmware devices in factory memory.

Warning
not use it in 6.X.X devices.
Returns
0 on success, <0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1135 of file qbrobotics_research_api.cpp.

◆ storeUserDataMemory()

int Device::storeUserDataMemory ( )
virtual

Store the changed parameters on 7.X.X firmware devices in user memory.

Warning
not use it in 6.X.X devices.
Returns
0 on success, <0 on error
Warning
The improper use of this function could damage the device and invalidate the device warranty. Contact our support team (suppo.nosp@m.rt@q.nosp@m.brobo.nosp@m.tics.nosp@m..com) for more information.

Definition at line 1124 of file qbrobotics_research_api.cpp.

Member Data Documentation

◆ communication_

std::shared_ptr<Communication> qbrobotics_research_api::Device::communication_
protected

Definition at line 853 of file qbrobotics_research_api.h.

◆ name_

std::string qbrobotics_research_api::Device::name_
protected

Definition at line 850 of file qbrobotics_research_api.h.

◆ params_

std::shared_ptr<Params> qbrobotics_research_api::Device::params_
protected

Definition at line 852 of file qbrobotics_research_api.h.

◆ serial_port_

std::string qbrobotics_research_api::Device::serial_port_
protected

Definition at line 851 of file qbrobotics_research_api.h.


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


qb_device_driver
Author(s): qbroboticsĀ®
autogenerated on Thu Apr 27 2023 02:36:32