Classes | Public Member Functions | List of all members
qbrobotics_research_api::qbmoveResearch Class Reference

#include <qbmove_research_api.h>

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

Classes

class  Params
 

Public Member Functions

int computeAndStoreMaximumStiffness ()
 
int getParamRateLimiter ()
 
int getParamRateLimiter (uint8_t &rate_limiter)
 
 qbmoveResearch (std::shared_ptr< Communication > communication, std::string name, std::string serial_port, uint8_t id)
 
 qbmoveResearch (std::shared_ptr< Communication > communication, std::string name, std::string serial_port, uint8_t id, bool init_params)
 
 qbmoveResearch (std::shared_ptr< Communication > communication, std::string name, std::string serial_port, uint8_t id, bool init_params, std::unique_ptr< Device::Params > params)
 
int setParamRateLimiter (uint8_t rate_limiter)
 
int setPositionAndStiffnessReferences (int16_t position, int16_t stiffness)
 
 ~qbmoveResearch () override=default
 
- Public Member Functions inherited from qbrobotics_research_api::Device
 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
 

Additional Inherited Members

- Protected Attributes inherited from qbrobotics_research_api::Device
std::shared_ptr< Communicationcommunication_
 
std::string name_
 
std::shared_ptr< Paramsparams_
 
std::string serial_port_
 

Detailed Description

Definition at line 60 of file qbmove_research_api.h.

Constructor & Destructor Documentation

◆ qbmoveResearch() [1/3]

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

Definition at line 37 of file qbmove_research_api.cpp.

◆ qbmoveResearch() [2/3]

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

Definition at line 40 of file qbmove_research_api.cpp.

◆ qbmoveResearch() [3/3]

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

Definition at line 43 of file qbmove_research_api.cpp.

◆ ~qbmoveResearch()

qbrobotics_research_api::qbmoveResearch::~qbmoveResearch ( )
overridedefault

Member Function Documentation

◆ computeAndStoreMaximumStiffness()

int qbmoveResearch::computeAndStoreMaximumStiffness ( )

Definition at line 46 of file qbmove_research_api.cpp.

◆ getParamRateLimiter() [1/2]

int qbmoveResearch::getParamRateLimiter ( )

Definition at line 62 of file qbmove_research_api.cpp.

◆ getParamRateLimiter() [2/2]

int qbmoveResearch::getParamRateLimiter ( uint8_t &  rate_limiter)

Definition at line 66 of file qbmove_research_api.cpp.

◆ setParamRateLimiter()

int qbmoveResearch::setParamRateLimiter ( uint8_t  rate_limiter)

Definition at line 75 of file qbmove_research_api.cpp.

◆ setPositionAndStiffnessReferences()

int qbmoveResearch::setPositionAndStiffnessReferences ( int16_t  position,
int16_t  stiffness 
)

Definition at line 54 of file qbmove_research_api.cpp.


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