Class ActuatorInterface
Defined in File actuator_interface.hpp
Class Documentation
-
class ActuatorInterface
Actuator for commanding the MyActuator RMD actuator series.
Public Functions
-
ActuatorInterface() = delete
Class constructor.
- Parameters:
driver – [in] The driver communicating over the network interface
actuator_id – [in] The actuator id [1, 32]
-
ActuatorInterface(ActuatorInterface const&) = default
-
ActuatorInterface &operator=(ActuatorInterface const&) = default
-
ActuatorInterface(ActuatorInterface&&) = default
-
ActuatorInterface &operator=(ActuatorInterface&&) = default
-
std::int32_t getAcceleration()
Reads the current acceleration.
- Returns:
The current acceleration in dps with a resolution of 1 dps
-
std::uint16_t getCanId()
Get the CAN ID of the device.
- Returns:
The CAN ID of the device starting at 0x240
-
Gains getControllerGains()
Reads the currently used controller gains.
- Returns:
The currently used controller gains for current, speed and position as unsigned 8-bit integers
-
ControlMode getControlMode()
Reads the currently used control mode.
- Returns:
The currently used control mode
-
std::string getMotorModel()
Reads the motor model currently in use by the actuator.
- Returns:
The motor model string currently in use by the actuator, e.g. ‘X8S2V10’
-
float getMotorPower()
Reads the current motor power consumption in Watt.
- Returns:
The current motor power consumption in Watt with a resolution of 0.1
-
MotorStatus1 getMotorStatus1()
Reads the motor status 1.
- Returns:
The motor status 1 containing temperature, voltage and error codes
-
MotorStatus2 getMotorStatus2()
Reads the motor status 2.
- Returns:
The motor status 2 containing current, speed and position
-
MotorStatus3 getMotorStatus3()
Reads the motor status 3.
- Returns:
The motor status 3 containing detailed current information
-
float getMultiTurnAngle()
Read the multi-turn angle.
- Returns:
The current multi-turn angle with a resolution of 0.01 deg
-
std::int32_t getMultiTurnEncoderPosition()
Read the multi-turn encoder position subtracted by the encoder multi-turn zero offset.
- Returns:
The multi-turn encoder position
-
std::int32_t getMultiTurnEncoderOriginalPosition()
Read the raw multi-turn encoder position without taking into consideration the multi-turn zero offset.
- Returns:
The multi-turn encoder position
-
std::int32_t getMultiTurnEncoderZeroOffset()
Read the multi-turn encoder zero offset.
- Returns:
The multi-turn encoder zero offset
-
std::chrono::milliseconds getRuntime()
Reads the uptime of the actuator in milliseconds.
- Returns:
The uptime of the actuator in milliseconds
-
float getSingleTurnAngle()
Read the single-turn angle.
Warning
This does not seem to give correct values with my X8-PRO V2 actuator!
- Returns:
The current single-turn angle with a resolution of 0.01 deg
-
std::int16_t getSingleTurnEncoderPosition()
Read the single-turn encoder position.
- Returns:
The single-turn encoder position
-
std::uint32_t getVersionDate()
Reads the version date of the actuator firmware.
- Returns:
The version date of the firmware on the actuator, e.g. ‘20220206’
-
void lockBrake()
Close the holding brake. The motor won’t be able to turn anymore.
-
void releaseBrake()
Open the holding brake leaving the motor in a movable state.
-
void reset()
Reset the actuator.
-
Feedback sendCurrentSetpoint(float const current)
Send a current set-point to the actuator.
- Parameters:
current – [in] The current set-point in Ampere
- Returns:
Feedback control message containing actuator position, velocity, torque and temperature
-
Feedback sendPositionAbsoluteSetpoint(float const position, float const max_speed = 500.0)
Send an absolute position set-point to the actuator additionally specifying a maximum velocity.
- Parameters:
position – [in] The position set-point in degree
max_speed – [in] The maximum speed for the motion in degree per second
- Returns:
Feedback control message containing actuator position, velocity, torque and temperature
-
Feedback sendTorqueSetpoint(float const torque, float const torque_constant)
Send a torque set-point to the actuator by setting the current.
- Parameters:
torque – [in] The desired torque in [Nm]
torque_constant – [in] The motor’s torque constant [Nm/A], depends on the model of the motor, refer to actuator_constants.hpp for the torque constant of your actuator
- Returns:
Feedback control message containing actuator position, velocity, torque and temperature
-
Feedback sendVelocitySetpoint(float const speed)
Send a velocity set-point to the actuator.
- Parameters:
speed – [in] The speed set-point in degree per second
- Returns:
Feedback control message containing actuator position, velocity, torque and temperature
-
void setAcceleration(std::uint32_t const acceleration, AccelerationType const mode)
Write the acceleration/deceleration for the different modes to RAM and ROM (persistent)
- Parameters:
acceleration – [in] The desired acceleration/deceleration in dps with a resolution of 1 dps/s [100, 60000] For continuous motions the acceleration should be set to the value 0, see https://github.com/2b-t/myactuator_rmd/issues/10#issuecomment-2195847459
mode – [in] The mode of the desired acceleration/deceleration to be set
-
void setCanBaudRate(CanBaudRate const baud_rate)
Set the communication Baud rate for CAN bus.
- Parameters:
baud_rate – [in] Communication Baud rate that the actuator should operator with
-
void setCanId(std::uint16_t const can_id)
Set the CAN ID of the device.
- Parameters:
can_id – [in] The CAN ID of the device in the range [1, 32]
-
std::int32_t setCurrentPositionAsEncoderZero()
Set the zero offset (initial position) of the encoder to the current position.
Warning
Motor has be restarted in order for this to become effective
- Returns:
Current encoder position that was set to be zero
-
void setEncoderZero(std::int32_t const encoder_offset)
Set the zero offset (initial position) of the encoder to a given value.
Warning
Motor has be restarted in order for this to become effective
- Parameters:
encoder_offset – [in] Encoder offset that should be set as zero
-
Gains setControllerGains(Gains const &gains, bool const is_persistent = false)
Write the currently used controller gains either to RAM (not persistent after reboot) or ROM (persistent)
- Parameters:
gains – [in] The PI-gains for current, speed and position to be set
is_persistent – [in] Boolean argument signaling whether the controller gains should be persistent after reboot of the actuator or not
- Returns:
The currently used controller gains for current, speed and position as unsigned 8-bit integers
-
void setTimeout(std::chrono::milliseconds const &timeout)
Set the communication interruption protection time setting. The break will be triggered if the communication is interrupted for longer than the set time. The value 0 disables this feature.
- Parameters:
timeout – [in] The desired interruption protection time, 0 in case it should be disabled
-
void shutdownMotor()
Turn off the motor.
-
void stopMotor()
Stop the motor if running closed loop command.
-
ActuatorInterface() = delete