UCLV Dynamixel Utils
Loading...
Searching...
No Matches
uclv::dynamixel_utils::Hand Class Reference

The Hand class represents a robotic hand with multiple motors. More...

#include <hand.hpp>

Public Member Functions

 Hand (const std::string &serial_port, int baudrate, float protocol_version, dynamixel::PortHandler *const &portHandler, dynamixel::PacketHandler *const &packetHandler)
 Constructs a Hand object.
 
 Hand (const std::string &serial_port, int baudrate, float protocol_version)
 Constructs a Hand object.
 
 Hand ()
 Default constructor.
 
 ~Hand ()
 Destructor.
 
bool initialize ()
 Initializes the hand.
 
void setSerialPort (const std::string &serial_port)
 Sets the serial port.
 
void setBaudrate (int baudrate)
 Sets the baudrate.
 
void setProtocolVersion (float protocol_version)
 Sets the protocol version.
 
std::string getSerialPort ()
 Gets the serial port.
 
int getBaudrate ()
 Gets the baudrate.
 
float getProtocolVersion ()
 Gets the protocol version.
 
void setPortHandler (dynamixel::PortHandler *portHandler)
 Sets the port handler.
 
void setPacketHandler (dynamixel::PacketHandler *packetHandler)
 Sets the packet handler.
 
void setSerialPortLowLatency (const std::string &serial_port)
 Sets the serial port to low latency mode.
 
std::shared_ptr< FingerMotorcreateFingerMotor (uint8_t id)
 Creates a finger motor.
 
std::shared_ptr< WristMotorcreateWristMotor (uint8_t id)
 Creates a wrist motor.
 
const std::vector< std::shared_ptr< FingerMotor > > & addFingerMotor (uint8_t id)
 Adds a finger motor to the hand.
 
const std::vector< std::shared_ptr< WristMotor > > & addWristMotor (uint8_t id)
 Adds a wrist motor to the hand.
 
std::vector< std::shared_ptr< FingerMotor > > getFingerMotors ()
 Gets the finger motors.
 
std::vector< std::shared_ptr< WristMotor > > getWristMotors ()
 Gets the wrist motors.
 
void printFingerMotors () const
 Prints the finger motors.
 
void printWristMotors () const
 Prints the wrist motors.
 
void removeFingerMotor (uint8_t id)
 Removes a finger motor from the hand.
 
void removeWristMotor (uint8_t id)
 Removes a wrist motor from the hand.
 
void moveFingerMotor (const uint8_t &id, const float &position)
 Moves a finger motor to a specified position.
 
void moveWristMotor (const uint8_t &id, const float &position)
 Moves a wrist motor to a specified position.
 
uint16_t readFingerMotorPosition (const uint8_t &id)
 Reads the position of a finger motor.
 
uint16_t readWristMotorPosition (const uint8_t &id)
 Reads the position of a wrist motor.
 
void moveMotors (const std::vector< uint8_t > &ids, const std::vector< float > &positions)
 Moves multiple motors using bulk write.
 
std::vector< uint32_t > readMotorsPositions (const std::vector< uint8_t > &ids)
 Reads the positions of multiple motors using bulk read.
 

Detailed Description

The Hand class represents a robotic hand with multiple motors.

Constructor & Destructor Documentation

◆ Hand() [1/3]

Hand::Hand ( const std::string & serial_port,
int baudrate,
float protocol_version,
dynamixel::PortHandler *const & portHandler,
dynamixel::PacketHandler *const & packetHandler )

Constructs a Hand object.

Constructs a Hand object with the specified parameters.

Parameters
serial_portThe serial port to which the hand is connected.
baudrateThe baudrate for the serial communication.
protocol_versionThe protocol version used for communication.
portHandlerPointer to the port handler.
packetHandlerPointer to the packet handler.
serial_portThe serial port to be used for communication.
baudrateThe baudrate for serial communication.
protocol_versionThe protocol version to be used.
portHandlerPointer to the port handler.
packetHandlerPointer to the packet handler.

◆ Hand() [2/3]

Hand::Hand ( const std::string & serial_port,
int baudrate,
float protocol_version )

Constructs a Hand object.

Constructs a Hand object with the specified parameters and initializes the port and packet handlers.

Parameters
serial_portThe serial port to which the hand is connected.
baudrateThe baudrate for the serial communication.
protocol_versionThe protocol version used for communication.
serial_portThe serial port to be used for communication.
baudrateThe baudrate for serial communication.
protocol_versionThe protocol version to be used.

◆ Hand() [3/3]

Hand::Hand ( )

Default constructor.

Default constructor for Hand.

◆ ~Hand()

Hand::~Hand ( )

Destructor.

Destructor for Hand. Cleans up the port and packet handlers.

Member Function Documentation

◆ addFingerMotor()

const std::vector< std::shared_ptr< FingerMotor > > & Hand::addFingerMotor ( uint8_t id)

Adds a finger motor to the hand.

Adds a finger motor to the list if it does not already exist.

Parameters
idThe identifier of the motor.
Returns
A constant reference to the vector of finger motors.

This function checks if a FingerMotor with the specified ID already exists in the list. If it does not, a new FingerMotor is created and added to the list.

Parameters
idThe ID of the FingerMotor to be added.
Returns
const std::vector<std::shared_ptr<FingerMotor>>& A reference to the list of FingerMotors.

◆ addWristMotor()

const std::vector< std::shared_ptr< WristMotor > > & Hand::addWristMotor ( uint8_t id)

Adds a wrist motor to the hand.

Adds a wrist motor to the list if it does not already exist.

Parameters
idThe identifier of the motor.
Returns
A constant reference to the vector of wrist motors.

This function checks if a WristMotor with the specified ID already exists in the list. If it does not, a new WristMotor is created and added to the list.

Parameters
idThe ID of the WristMotor to be added.
Returns
const std::vector<std::shared_ptr<WristMotor>>& A reference to the list of WristMotors.

◆ createFingerMotor()

std::shared_ptr< FingerMotor > Hand::createFingerMotor ( uint8_t id)

Creates a finger motor.

Creates a finger motor with the specified ID.

Parameters
idThe identifier of the motor.
Returns
A shared pointer to the created finger motor.
Parameters
idThe ID of the finger motor.
Returns
A shared pointer to the created FingerMotor.

◆ createWristMotor()

std::shared_ptr< WristMotor > Hand::createWristMotor ( uint8_t id)

Creates a wrist motor.

Creates a wrist motor with the specified ID.

Parameters
idThe identifier of the motor.
Returns
A shared pointer to the created wrist motor.
Parameters
idThe ID of the wrist motor.
Returns
A shared pointer to the created WristMotor.

◆ getBaudrate()

int Hand::getBaudrate ( )

Gets the baudrate.

Returns
The baudrate for the serial communication.
The baudrate used for serial communication.

◆ getFingerMotors()

std::vector< std::shared_ptr< FingerMotor > > Hand::getFingerMotors ( )

Gets the finger motors.

Gets the list of finger motors.

Returns
A vector of shared pointers to the finger motors.

◆ getProtocolVersion()

float Hand::getProtocolVersion ( )

Gets the protocol version.

Returns
The protocol version used for communication.
The protocol version used.

◆ getSerialPort()

std::string Hand::getSerialPort ( )

Gets the serial port.

Returns
The serial port to which the hand is connected.
The serial port used for communication.

◆ getWristMotors()

std::vector< std::shared_ptr< WristMotor > > Hand::getWristMotors ( )

Gets the wrist motors.

Gets the list of wrist motors.

Returns
A vector of shared pointers to the wrist motors.

◆ initialize()

bool Hand::initialize ( )

Initializes the hand.

Initializes the serial port and sets the baudrate.

◆ moveFingerMotor()

void Hand::moveFingerMotor ( const uint8_t & id,
const float & position )

Moves a finger motor to a specified position.

Parameters
idThe identifier of the motor.
positionThe target position.

This function sets the target position for a FingerMotor identified by its ID. The position value should be within the range of 0 to 4095.

Parameters
idThe ID of the FingerMotor to be moved.
positionThe target position for the FingerMotor. It should be a value between 0 and 4095.

◆ moveMotors()

void Hand::moveMotors ( const std::vector< uint8_t > & ids,
const std::vector< float > & positions )

Moves multiple motors using bulk write.

Moves multiple motors to specified target positions using bulk write.

Parameters
idsA vector of motor identifiers.
positionsA vector of target positions.

This function moves a set of motors (both finger and wrist motors) to specified positions in a single bulk write operation.

Parameters
idsA vector of motor IDs to be moved.
positionsA vector of target positions corresponding to each motor ID. Values should be in the range 0 to 4095.

◆ moveWristMotor()

void Hand::moveWristMotor ( const uint8_t & id,
const float & position )

Moves a wrist motor to a specified position.

Parameters
idThe identifier of the motor.
positionThe target position.

This function sets the target position for a WristMotor identified by its ID. The position value should be within the range of 0 to 4095.

Parameters
idThe ID of the WristMotor to be moved.
positionThe target position for the WristMotor. It should be a value between 0 and 4095.

◆ printFingerMotors()

void Hand::printFingerMotors ( ) const

Prints the finger motors.

Prints the IDs of all finger motors.

This function prints the index and ID of each finger motor in the list. If no finger motors are found, it prints a message indicating this.

◆ printWristMotors()

void Hand::printWristMotors ( ) const

Prints the wrist motors.

Prints the IDs of all wrist motors.

This function prints the index and ID of each wrist motor in the list. If no wrist motors are found, it prints a message indicating this.

◆ readFingerMotorPosition()

uint16_t Hand::readFingerMotorPosition ( const uint8_t & id)

Reads the position of a finger motor.

Reads the current position of a specified finger motor.

Parameters
idThe identifier of the motor.
Returns
The position of the motor.

This function retrieves the current position of a FingerMotor identified by its ID.

Parameters
idThe ID of the FingerMotor whose position is to be read.
Returns
The current position of the FingerMotor. The position is a value between 0 and 4095.

◆ readMotorsPositions()

std::vector< uint32_t > Hand::readMotorsPositions ( const std::vector< uint8_t > & ids)

Reads the positions of multiple motors using bulk read.

Parameters
idsA vector of motor identifiers.
Returns
A vector of positions corresponding to the motor identifiers.

This function reads the current positions of a set of motors (both finger and wrist motors) in a single bulk read operation.

Parameters
idsA vector of motor IDs whose positions are to be read.
Returns
A vector of positions corresponding to each motor ID. The positions are in the range 0 to 4095.

◆ readWristMotorPosition()

uint16_t Hand::readWristMotorPosition ( const uint8_t & id)

Reads the position of a wrist motor.

Reads the current position of a specified wrist motor.

Parameters
idThe identifier of the motor.
Returns
The position of the motor.

This function retrieves the current position of a WristMotor identified by its ID.

Parameters
idThe ID of the WristMotor whose position is to be read.
Returns
The current position of the WristMotor. The position is a value between 0 and 4095.

◆ removeFingerMotor()

void Hand::removeFingerMotor ( uint8_t id)

Removes a finger motor from the hand.

Removes a finger motor from the list by its ID.

Parameters
idThe identifier of the motor to be removed.

This function searches for a finger motor with the specified ID and removes it from the list of finger motors if found.

Parameters
idThe ID of the finger motor to remove.

◆ removeWristMotor()

void Hand::removeWristMotor ( uint8_t id)

Removes a wrist motor from the hand.

Removes a wrist motor from the list by its ID.

Parameters
idThe identifier of the motor to be removed.

This function searches for a wrist motor with the specified ID and removes it from the list of wrist motors if found.

Parameters
idThe ID of the wrist motor to remove.

◆ setBaudrate()

void Hand::setBaudrate ( int baudrate)

Sets the baudrate.

Parameters
baudrateThe baudrate for the serial communication.
baudrateThe baudrate for serial communication.

◆ setPacketHandler()

void Hand::setPacketHandler ( dynamixel::PacketHandler * packetHandler)

Sets the packet handler.

Parameters
packetHandlerPointer to the packet handler.

◆ setPortHandler()

void Hand::setPortHandler ( dynamixel::PortHandler * portHandler)

Sets the port handler.

Parameters
portHandlerPointer to the port handler.

◆ setProtocolVersion()

void Hand::setProtocolVersion ( float protocol_version)

Sets the protocol version.

Parameters
protocol_versionThe protocol version used for communication.
protocol_versionThe protocol version to be used.

◆ setSerialPort()

void Hand::setSerialPort ( const std::string & serial_port)

Sets the serial port.

Parameters
serial_portThe serial port to which the hand is connected.
serial_portThe serial port to be used for communication.

◆ setSerialPortLowLatency()

void Hand::setSerialPortLowLatency ( const std::string & serial_port)

Sets the serial port to low latency mode.

Parameters
serial_portThe serial port to which the hand is connected.
serial_portThe serial port to be used.

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