|
UCLV Dynamixel Utils
|
The Motor class represents a single motor connected to the system. More...
#include <motor.hpp>
Public Member Functions | |
| 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. | |
The Motor class represents a single motor connected to the system.
| 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.
Constructor of the Motor class.
| serial_port | The serial port to which the motor is connected. |
| baudrate | The baudrate for the serial communication. |
| protocol_version | The protocol version used for communication. |
| portHandler | Pointer to the port handler. |
| packetHandler | Pointer to the packet handler. |
| id | Identifier of the motor. |
This constructor initializes the Motor class with the provided parameters.
| serial_port | The serial port to which the motor is connected. |
| baudrate | The baudrate of the serial communication. |
| protocol_version | The version of the protocol used. |
| portHandler | Pointer to the port handler. |
| packetHandler | Pointer to the packet handler. |
| id | The identifier of the motor. |
| Motor::Motor | ( | const std::string & | serial_port, |
| int | baudrate, | ||
| float | protocol_version, | ||
| uint8_t | id ) |
Constructs a Motor object with specified parameters.
Constructor of the Motor class.
| serial_port | The serial port to which the motor is connected. |
| baudrate | The baudrate for the serial communication. |
| protocol_version | The protocol version used for communication. |
| id | Identifier of the motor. |
This constructor initializes the Motor class with the provided parameters. It creates the port and packet handlers based on the serial port and protocol version.
| serial_port | The serial port to which the motor is connected. |
| baudrate | The baudrate of the serial communication. |
| protocol_version | The version of the protocol used. |
| id | The identifier of the motor. |
| Motor::Motor | ( | ) |
| bool Motor::disableTorque | ( | ) |
Disables torque for the motor.
This method disables torque for the motor by writing a value of 0 to the torque enable address.
| bool Motor::enableTorque | ( | ) |
Enables torque for the motor.
This method enables torque for the motor by writing a value of 1 to the torque enable address.
| uint16_t Motor::getAddrPresentPosition | ( | ) | const |
Gets the address for the present position.
| uint16_t Motor::getAddrTargetPosition | ( | ) | const |
Gets the address for the target position.
| uint8_t Motor::getId | ( | ) |
Gets the identifier of the motor.
Gets the ID of the motor.
| uint16_t Motor::getLenAddrPresentPosition | ( | ) | const |
Gets the size (nr of bytes to write) for address of the present position.
| uint16_t Motor::getLenAddrTargetPosition | ( | ) | const |
Gets the size (nr of bytes to write) for address of the target position.
| uint8_t Motor::read1FromAddress | ( | uint8_t | id, |
| uint16_t | address ) |
Reads a byte from the specified address of the motor.
Reads a 1-byte value from a specified address on the motor.
| id | Identifier of the motor. |
| address | Address to read from. |
| id | The identifier of the motor. |
| address | The address to read the data from. |
| uint16_t Motor::read2FromAddress | ( | uint8_t | id, |
| uint16_t | address ) |
Reads two bytes from the specified address of the motor.
Reads a 2-byte value from a specified address on the motor.
| id | Identifier of the motor. |
| address | Address to read from. |
| id | The identifier of the motor. |
| address | The address to read the data from. |
| uint16_t Motor::readPresentPosition | ( | ) |
Reads the present position of the motor.
| id | The identifier of the motor. |
| void Motor::setAddrPresentPosition | ( | uint16_t | addrPresentPosition | ) |
Sets the address for the present position.
| addrPresentPosition | The address to be set for the present position. |
| void Motor::setAddrTargetPosition | ( | uint16_t | addrTargetPosition | ) |
Sets the address for the target position.
| addrTargetPosition | The address to be set for the target position. |
| void Motor::setId | ( | uint8_t | id | ) |
Sets the identifier of the motor.
Sets the ID of the motor.
| id | Identifier of the motor. |
| id | The new identifier of the motor. |
| void Motor::setLenAddrPresentPosition | ( | uint16_t | lenAddrPresentPosition | ) |
Sets the size (nr of bytes to write) for address of the present position.
| lenAddrPresentPosition | The size to be set for length of address for present position. |
| void Motor::setLenAddrTargetPosition | ( | uint16_t | lenAddrTargetPosition | ) |
Sets the size (nr of bytes to write) for address of the target position.
| lenAddrTargetPosition | The size to be set for length of address for target position. |
| void Motor::setTargetPosition | ( | float | position | ) |
Sets the target position of the motor.
Sets the target position for the motor.
| position | Target position. |
| id | The identifier of the motor. |
| position | The target position to set. |
| void Motor::write1OnAddress | ( | uint8_t | id, |
| uint16_t | address, | ||
| uint8_t | data ) |
Writes a byte to the specified address of the motor.
Writes a 1-byte value to a specified address on the motor.
| id | Identifier of the motor. |
| address | Address to write to. |
| data | Data to write. |
| id | The identifier of the motor. |
| address | The address to write the data to. |
| data | The data to write. |
| void Motor::write2OnAddress | ( | uint8_t | id, |
| uint16_t | address, | ||
| uint16_t | data ) |
Writes two bytes to the specified address of the motor.
Writes a 2-byte value to a specified address on the motor.
| id | Identifier of the motor. |
| address | Address to write to. |
| data | Data to write. |
| id | The identifier of the motor. |
| address | The address to write the data to. |
| data | The data to write. |