UCLV Dynamixel Utils
Loading...
Searching...
No Matches
FingerMotor Class Reference

The FingerMotor class represents a finger motor, which is a specific type of motor. More...

#include <fingermotor.hpp>

Inheritance diagram for FingerMotor:
uclv::dynamixel_utils::Motor

Public Member Functions

 FingerMotor (const std::string &serial_port, int baudrate, float protocol_version, dynamixel::PortHandler *const &portHandler, dynamixel::PacketHandler *const &packetHandler, uint8_t id)
 Constructs a FingerMotor object with specified parameters.
 
 FingerMotor (const std::string &serial_port, int baudrate, float protocol_version, uint8_t id)
 Constructs a FingerMotor object with specified parameters.
 
 FingerMotor ()
 Default constructor.
 
- Public Member Functions inherited from uclv::dynamixel_utils::Motor
 Motor (const std::string &serial_port, int baudrate, float protocol_version, dynamixel::PortHandler *const &portHandler, dynamixel::PacketHandler *const &packetHandler, uint8_t id)
 Constructs a Motor object with specified parameters.
 
 Motor (const std::string &serial_port, int baudrate, float protocol_version, uint8_t id)
 Constructs a Motor object with specified parameters.
 
 Motor ()
 Default constructor.
 
void setId (uint8_t id)
 Sets the identifier of the motor.
 
uint8_t getId ()
 Gets the identifier of the motor.
 
void setAddrTargetPosition (uint16_t addrTargetPosition)
 Sets the address for the target position.
 
uint16_t getAddrTargetPosition () const
 Gets the address for the target position.
 
void setAddrPresentPosition (uint16_t addrPresentPosition)
 Sets the address for the present position.
 
uint16_t getAddrPresentPosition () const
 Gets the address for the present position.
 
void setLenAddrTargetPosition (uint16_t lenAddrTargetPosition)
 Sets the size (nr of bytes to write) for address of the target position.
 
uint16_t getLenAddrTargetPosition () const
 Gets the size (nr of bytes to write) for address of the target position.
 
void setLenAddrPresentPosition (uint16_t lenAddrPresentPosition)
 Sets the size (nr of bytes to write) for address of the present position.
 
uint16_t getLenAddrPresentPosition () const
 Gets the size (nr of bytes to write) for address of the present position.
 
void setAddrTorqueEnable (uint16_t addrTorqueEnable)
 
uint16_t getAddrTorqueEnable () const
 
void setTargetPosition (float position)
 Sets the target position of the motor.
 
uint16_t readPresentPosition ()
 Reads the present position of the motor.
 
void write1OnAddress (uint8_t id, uint16_t address, uint8_t data)
 Writes a byte to the specified address of the motor.
 
void write2OnAddress (uint8_t id, uint16_t address, uint16_t data)
 Writes two bytes to the specified address of the motor.
 
uint8_t read1FromAddress (uint8_t id, uint16_t address)
 Reads a byte from the specified address of the motor.
 
uint16_t read2FromAddress (uint8_t id, uint16_t address)
 Reads two bytes from the specified address of the motor.
 
bool enableTorque ()
 Enables torque for the motor.
 
bool disableTorque ()
 Disables torque for the motor.
 

Detailed Description

The FingerMotor class represents a finger motor, which is a specific type of motor.

Constructor & Destructor Documentation

◆ FingerMotor() [1/3]

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

Constructs a FingerMotor object with specified parameters.

Constructor of the FingerMotor class.

Parameters
serial_portThe serial port to which the motor 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.
idIdentifier of the motor.

This constructor initializes the FingerMotor class with the provided parameters.

Parameters
serial_portThe serial port to which the motor is connected.
baudrateThe baudrate of the serial communication.
protocol_versionThe version of the protocol used.
portHandlerPointer to the port handler.
packetHandlerPointer to the packet handler.
idThe identifier of the motor.

◆ FingerMotor() [2/3]

FingerMotor::FingerMotor ( const std::string & serial_port,
int baudrate,
float protocol_version,
uint8_t id )

Constructs a FingerMotor object with specified parameters.

Constructor of the FingerMotor class.

Parameters
serial_portThe serial port to which the motor is connected.
baudrateThe baudrate for the serial communication.
protocol_versionThe protocol version used for communication.
idIdentifier of the motor.

This constructor initializes the FingerMotor class with the provided parameters. It creates the port and packet handlers based on the serial port and protocol version.

Parameters
serial_portThe serial port to which the motor is connected.
baudrateThe baudrate of the serial communication.
protocol_versionThe version of the protocol used.
idThe identifier of the motor.

◆ FingerMotor() [3/3]

FingerMotor::FingerMotor ( )

Default constructor.

Default constructor of the FingerMotor class.

This constructor initializes the FingerMotor class with default values.


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