Class GetMotorPowerResponse

Inheritance Relationships

Base Type

Class Documentation

class GetMotorPowerResponse : public myactuator_rmd::SingleMotorResponse<CommandType::READ_MOTOR_POWER>

Response to request for reading the motor model.

Public Functions

GetMotorPowerResponse() = delete
GetMotorPowerResponse(GetMotorPowerResponse const&) = default
GetMotorPowerResponse &operator=(GetMotorPowerResponse const&) = default
GetMotorPowerResponse(GetMotorPowerResponse&&) = default
GetMotorPowerResponse &operator=(GetMotorPowerResponse&&) = default
float getPower() const noexcept

Get the current motor power.

Returns:

The current motor power in Watt with a resolution of 0.1

constexpr SingleMotorResponse(std::array<std::uint8_t, 8> const &data)
constexpr SingleMotorResponse() = delete
SingleMotorResponse(SingleMotorResponse const&) = default
SingleMotorResponse(SingleMotorResponse&&) = default