![]() |
Arduino-I2C-KM1
2.0.2
KeiganMotor Arduino Library
|
Class to handle KeiganMotor via I2C Communication [詳解]
#include <KM1_I2C.h>
公開メンバ関数 | |
KeiganMotor (uint8_t address, int clock=1000000) | |
Initialize by specifying I2C Address [詳解] | |
void | begin () |
start I2C communication via Wire library [詳解] | |
bool | write (uint8_t command, uint8_t *value, uint8_t value_len, bool response=false) |
Write command function [詳解] | |
error_t | getError () |
Get the error that master retains. getError() is designed to use after getting response of write command. [詳解] | |
Write register | |
bool | enableCheckSum (bool isEnabled, bool response=false) |
Set checksum validadtion enabled. [詳解] | |
bool | interface (uint8_t flag, bool response=false) |
Set available interface [詳解] | |
bool | limitCurrent (float value, bool response=false) |
Limit current [詳解] | |
bool | writeResponse (bool isEnabled, bool response=false) |
Set write response enabled or disabled [詳解] | |
bool | safeRun (bool isEnabled, uint32_t timeout, uint8_t op, bool response=false) |
Set safe run mode to stop motor automatically when it cannot receive next command within a certain period (timeout). [詳解] | |
bool | motorMeasurementInterval (uint8_t interval, bool response=false) |
Set motor measurement interval [詳解] | |
bool | saveAllRegisters (bool response=false) |
Save all the registers KeiganMotor retains. [詳解] | |
bool | resetRegister (uint8_t reg, bool response=false) |
Reset a register value to default. [詳解] | |
bool | resetAllRegisters (bool response=false) |
Reset all the registers to default. [詳解] | |
Write register (PID Controller) | |
bool | qCurrentP (float value, bool response=false) |
Set Q-axis current PID controller gain P. [詳解] | |
bool | qCurrentI (float value, bool response=false) |
Set Q-axis current PID controller gain I. [詳解] | |
bool | qCurrentD (float value, bool response=false) |
Set Q-axis current PID controller gain D. [詳解] | |
bool | speedP (float value, bool response=false) |
Set Speed PID controller gain P. [詳解] | |
bool | speedI (float value, bool response=false) |
Set Speed PID controller gain I. [詳解] | |
bool | speedD (float value, bool response=false) |
Set Speed PID controller gain D. [詳解] | |
bool | positionP (float value, bool response=false) |
Set Position PID controller gain P [詳解] | |
bool | positionI (float value, bool response=false) |
Set Position PID controller gain I [詳解] | |
bool | positionD (float value, bool response=false) |
Set Position PID controller gain D [詳解] | |
bool | positionIDThreshold (float value, bool response=false) |
Set the threshold [radian] to determine Position PID control available range [詳解] | |
bool | positionIDThresholdDegree (float value, bool response=false) |
Set the threshold [degree] to determine Position PID control available range [詳解] | |
bool | resetPID (bool response=false) |
Reset all the PID parameters to default [詳解] | |
Read data | |
bool | readRegister (uint8_t reg, uint8_t *value, uint8_t value_len) |
Read register function [詳解] | |
status_t | readStatus (void) |
Read status function [詳解] | |
float | readMaxSpeed (void) |
Read the maximum speed [詳解] | |
float | readMinSpeed (void) |
Read the minimum speed [詳解] | |
uint8_t | readCurveType (void) |
Read the curveType fo motion control. See CURVE_TYPE_NONE and CURVE_TYPE_TRAPEZOID. [詳解] | |
float | readAcc (void) |
Read the acceleration value [詳解] | |
float | readDec (void) |
Read the deceleration value [詳解] | |
float | readMaxTorque (void) |
Read the resister value of max torque (limitation) [詳解] | |
bool | readMotorMeasurement (void) |
Read motor measurement data [詳解] | |
bool | readIMUMeasurement (void) |
Read IMU measurement data [詳解] | |
bool | readDeviceName (char *name) |
Read the KeiganMotor device name [詳解] | |
bool | readDeviceInfo (uint8_t type, char *str) |
Read the device information [詳解] | |
error_t | readError (void) |
Read the latest error [詳解] | |
Read PID controller parameters | |
float | readQCurrentP (void) |
Read the resister value of Current PID controller P gain [詳解] | |
float | readQCurrentI (void) |
Read the resister value of Current PID controller I gain [詳解] | |
float | readQCurrentD (void) |
Read the resister value of Current PID controller D gain [詳解] | |
float | readSpeedP (void) |
Read the resister value of Speed PID controller P gain [詳解] | |
float | readSpeedI (void) |
Read the resister value of Speed PID controller I gain [詳解] | |
float | readSpeedD (void) |
Read the resister value of Speed PID controller D gain [詳解] | |
float | readPositionP (void) |
Read the resister value of Position PID controller P gain [詳解] | |
float | readPositionI (void) |
Read the resister value of Position PID controller I gain [詳解] | |
float | readPositionD (void) |
Read the resister value of Position PID controller D gain [詳解] | |
float | readPositionIDThreshold (void) |
Read the threshold [radian] to determine Position PID control available range [詳解] | |
float | readPositionIDThresholdDegree (void) |
Read the threshold [degree] to determine Position PID control available range [詳解] | |
Enable or Disable motor action | |
bool | disable (bool response=false) |
Disable motor action. [詳解] | |
bool | enable (bool response=false) |
Enable motor action. [詳解] | |
Motor control Settings | |
bool | maxSpeed (float value, bool response=false) |
Set max speed function to limit absolute value of velocity [詳解] | |
bool | minSpeed (float value, bool response=false) |
Set min speed. It is used in case of "prepare playback motion" [詳解] | |
bool | curveType (uint8_t type, bool response=false) |
Set curve type for motion control. [詳解] | |
bool | acc (float value, bool response=false) |
Set acceleration value. It is ignored when curve type is 0(CURVETYPE_NONE). [詳解] | |
bool | dec (float value, bool response=false) |
Set deceleration value. It is ignored when curve type is 0(CURVETYPE_NONE). [詳解] | |
bool | maxTorque (float value, bool response=false) |
Set Max torque value to limit current not to be above the torque. [詳解] | |
bool | speed (float value, bool response=false) |
Set anglular speed [radian/second] [詳解] | |
bool | speedRpm (float rpm, bool response=false) |
Set anglular speed [rotation/minute] (rpm) [詳解] | |
bool | presetPosition (float value, bool response=false) |
Set the current position as a certain position [radian] [詳解] | |
bool | presetPositionDegree (float degree, bool response=false) |
Set the current position as a certain position [degree] [詳解] | |
Motor action (Velocity Control) | |
bool | runAtVelocity (float value, bool response=false) |
Run at a certain velocity [radian/second] [詳解] | |
bool | runAtVelocityRpm (float rpm, bool response=false) |
Run at a certain velocity [rotation/minute] (rpm) [詳解] | |
bool | runForward (bool response=false) |
Run forward [詳解] | |
bool | runReverse (bool response=false) |
Run Reverse [詳解] | |
bool | stop (bool response=false) |
Stop [詳解] | |
Motor action (Position Control) | |
bool | moveToPosition (float position, bool response=false) |
Move to an absolute position [radian] [詳解] | |
bool | moveToPositionDegree (float degree, bool response=false) |
Move to an absolute position [degree] [詳解] | |
bool | moveByDistance (float distance, bool response=false) |
Move by a distance (move to an relative position) [radian] [詳解] | |
bool | moveByDistanceDegree (float degree, bool response=false) |
Move by a distance (move to an relative position) [degree] [詳解] | |
Motor action (others) | |
bool | free (bool response=false) |
De-energize motor (make motor free) [詳解] | |
Queue | |
bool | wait (uint32_t time, bool response=false) |
Wait for execution of next commands for time [msec]. [詳解] | |
Others | |
bool | i2cSlaveAddress (uint8_t address, bool response=false) |
Set I2C slave address. [詳解] | |
bool | reboot (bool response=false) |
Reboot KeiganMotor [詳解] | |
bool | startMotorMeasurement (bool response=false) |
Start motor measurement timer [詳解] | |
bool | stopMotorMeasurement (bool response=false) |
Stop motor measurement timer [詳解] | |
bool | startIMUMeasurement (bool response=false) |
Start IMU measurement timer [詳解] | |
bool | stopIMUMeasurement (bool response=false) |
Stop IMU measurement timer [詳解] | |
LED | |
bool | led (uint8_t state, uint8_t r, uint8_t g, uint8_t b, bool response=false) |
Set LED lit [詳解] | |
公開変数類 | |
status_t | status |
Status of KeiganMotor KeiganMotor のステータス [詳解] | |
motor_meas_t | measurement |
Motor measurement data [詳解] | |
float | position |
motor angle position [radian] [詳解] | |
float | degree |
motor angle position [degree] [詳解] | |
float | velocity |
motor angle velocity [radian/second] [詳解] | |
float | rpm |
motor angle velocity [rotation/minute] (rpm) [詳解] | |
float | torque |
motor torque [N*m] [詳解] | |
imu_meas_t | imu |
IMU measurement data [詳解] | |
error_t | error |
Error or success information [詳解] | |
Class to handle KeiganMotor via I2C Communication
KeiganMotor Class
It is able to control motor, change settings and read measurement data KeiganMotor を I2C 経由で扱うためのクラス モーターの制御や設定、測定値の取得を行う
KeiganMotor::KeiganMotor | ( | uint8_t | address, |
int | clock = 1000000 |
||
) |
Initialize by specifying I2C Address
KeiganMotorコンストラクタ.
[in] | address | I2C slave address (7bit: 0x01~0x7E) |
[in] | clock | (It can be up to 4000000. default:1000000) |
bool KeiganMotor::acc | ( | float | value, |
bool | response = false |
||
) |
Set acceleration value. It is ignored when curve type is 0(CURVETYPE_NONE).
[in] | value | float acceleration to set [radian/second^2] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
void KeiganMotor::begin | ( | ) |
start I2C communication via Wire library
bool KeiganMotor::curveType | ( | uint8_t | type, |
bool | response = false |
||
) |
Set curve type for motion control.
[in] | type | CurveType to set
|
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::dec | ( | float | value, |
bool | response = false |
||
) |
Set deceleration value. It is ignored when curve type is 0(CURVETYPE_NONE).
[in] | value | float deceleration to set [radian/second^2] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::disable | ( | bool | response = false | ) |
Disable motor action.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::enable | ( | bool | response = false | ) |
Enable motor action.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::enableCheckSum | ( | bool | isEnabled, |
bool | response = false |
||
) |
Set checksum validadtion enabled.
KeiganMotor will validate received data after receiving this command.
[in] | isEnabled | true if make Checksum validation enabled |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::free | ( | bool | response = false | ) |
De-energize motor (make motor free)
It keeps viscosity a little bit. You should use disable() to turn off rotational resistance completely.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
error_t KeiganMotor::getError | ( | ) |
Get the error that master retains.
getError() is designed to use after getting response of write command.
bool KeiganMotor::i2cSlaveAddress | ( | uint8_t | address, |
bool | response = false |
||
) |
Set I2C slave address.
[in] | address | I2C address (0x00~0x7F) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::interface | ( | uint8_t | flag, |
bool | response = false |
||
) |
Set available interface
You can enable or disable the data interfaces(physical 3 buttons, I2C, USB, BLE and so on).
The motor chooses the output interface of motor measurement values and IMU values as
(High priority)BLE > UART1(USB) > I2C(Low priority) by default.
If you want to force it to send measurement values through USB,
you need to set bit0(BLE) to OFF(0) and bit3(USB) to ON(1). For example, if you call set_interface(0b10001000),
Physical 3 buttons: enabled, I2C: disabled, USB: enabled and BLE: disabled.
To save this setting to the flash memory, ensure you call saveAllRegisters().
[in] | flag | uint8_t value consists of the following bit flag.
|
[in] | response | true if you get response after sending command, default: false // Enable I2C and disable both of BLE and USB
// Notification will be sent via I2C.
uint8_t flag = 0;
flag |= INTERFACE_BIT_I2C; // Enable I2C
flag |= INTERFACE_BIT_BUTTON; // Enable buttons
m.interface(flag);
m.saveAllRegisters();
m.reboot();
|
bool KeiganMotor::led | ( | uint8_t | state, |
uint8_t | r, | ||
uint8_t | g, | ||
uint8_t | b, | ||
bool | response = false |
||
) |
Set LED lit
[in] | state | LedState
|
[in] | r | Red brightness (0-255) |
[in] | g | Green brightness (0-255) |
[in] | b | Blue brightness (0-255) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::limitCurrent | ( | float | value, |
bool | response = false |
||
) |
Limit current
[in] | value | Max current to limit. |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::maxSpeed | ( | float | value, |
bool | response = false |
||
) |
Set max speed function to limit absolute value of velocity
[in] | value | float speed to set [radian/second] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::maxTorque | ( | float | value, |
bool | response = false |
||
) |
Set Max torque value to limit current not to be above the torque.
[in] | value | float max torque to set [N*m] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::minSpeed | ( | float | value, |
bool | response = false |
||
) |
Set min speed. It is used in case of "prepare playback motion"
[in] | value | float speed to set [radian/second] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::motorMeasurementInterval | ( | uint8_t | interval, |
bool | response = false |
||
) |
Set motor measurement interval
[in] | interval | the following integer value
|
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::moveByDistance | ( | float | distance, |
bool | response = false |
||
) |
Move by a distance (move to an relative position) [radian]
It uses preset speed value by function speed()
[in] | distance | distance [radian] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::moveByDistanceDegree | ( | float | degree, |
bool | response = false |
||
) |
Move by a distance (move to an relative position) [degree]
It uses preset speed value by function speed()
[in] | degree | degree [degree] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::moveToPosition | ( | float | position, |
bool | response = false |
||
) |
Move to an absolute position [radian]
It uses preset speed value by function speed()
[in] | position | position [radian] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::moveToPositionDegree | ( | float | degree, |
bool | response = false |
||
) |
Move to an absolute position [degree]
It uses preset speed value by function speed()
[in] | degree | degree [degree] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::positionD | ( | float | value, |
bool | response = false |
||
) |
Set Position PID controller gain D
[in] | value | Position PID controller gain D (differential). |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::positionI | ( | float | value, |
bool | response = false |
||
) |
Set Position PID controller gain I
[in] | value | Position PID controller gain I (integral) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::positionIDThreshold | ( | float | value, |
bool | response = false |
||
) |
Set the threshold [radian] to determine Position PID control available range
Position PID control is available within the range determined by this threshold,
while only Position P control is available out of the range.
The conditions are as follows.
[in] | value | the threshold to determine the available range of PID control. [radian] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::positionIDThresholdDegree | ( | float | value, |
bool | response = false |
||
) |
Set the threshold [degree] to determine Position PID control available range
See KeiganMotor::positionIDThreshold.
[in] | value | The threshold determines the available area of PID control. [degree] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::positionP | ( | float | value, |
bool | response = false |
||
) |
Set Position PID controller gain P
[in] | value | Position PID controller gain P (proportional) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::presetPosition | ( | float | value, |
bool | response = false |
||
) |
Set the current position as a certain position [radian]
presetPosition(0) makes the current position as "Zero" point.
[in] | value | preset position [radian] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::presetPositionDegree | ( | float | degree, |
bool | response = false |
||
) |
Set the current position as a certain position [degree]
presetPositionDegree(30) makes the current position as "30 degree".
[in] | degree | preset position [degree] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::qCurrentD | ( | float | value, |
bool | response = false |
||
) |
Set Q-axis current PID controller gain D.
[in] | value | Q-axis current PID controller gain D (differential) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::qCurrentI | ( | float | value, |
bool | response = false |
||
) |
Set Q-axis current PID controller gain I.
[in] | value | Q-axis current PID controller gain I (integral) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::qCurrentP | ( | float | value, |
bool | response = false |
||
) |
Set Q-axis current PID controller gain P.
[in] | value | Q-axis current PID controller gain P (proportional) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
float KeiganMotor::readAcc | ( | void | ) |
Read the acceleration value
uint8_t KeiganMotor::readCurveType | ( | void | ) |
Read the curveType fo motion control.
See CURVE_TYPE_NONE and CURVE_TYPE_TRAPEZOID.
float KeiganMotor::readDec | ( | void | ) |
Read the deceleration value
bool KeiganMotor::readDeviceInfo | ( | uint8_t | type, |
char * | str | ||
) |
Read the device information
bool KeiganMotor::readDeviceName | ( | char * | name | ) |
Read the KeiganMotor device name
The name is like "KM-1U AI09#3R9"
error_t KeiganMotor::readError | ( | void | ) |
Read the latest error
The response data is the same formart as error response of write command.
bool KeiganMotor::readIMUMeasurement | ( | void | ) |
Read IMU measurement data
IMU values are available after sending this command. See imu_t.
true | received data from KeiganMotor successfully |
false | got an error |
float KeiganMotor::readMaxSpeed | ( | void | ) |
Read the maximum speed
float KeiganMotor::readMaxTorque | ( | void | ) |
Read the resister value of max torque (limitation)
You can do torque control during velocity or position control
float KeiganMotor::readMinSpeed | ( | void | ) |
Read the minimum speed
bool KeiganMotor::readMotorMeasurement | ( | void | ) |
Read motor measurement data
Position, velocity and torque values are available from property after sending this command.
In addition to it, you can get degree and rpm values as property of KeiganMotor. .
true | received data from KeiganMotor successfully |
false | got an error if(m.readMotorMeasurement()){
Serial.print(degree: );
Serial.println(m.degree);
} else {
Serial.println("error");
}
|
float KeiganMotor::readPositionD | ( | void | ) |
Read the resister value of Position PID controller D gain
float KeiganMotor::readPositionI | ( | void | ) |
Read the resister value of Position PID controller I gain
float KeiganMotor::readPositionIDThreshold | ( | void | ) |
Read the threshold [radian] to determine Position PID control available range
float KeiganMotor::readPositionIDThresholdDegree | ( | void | ) |
Read the threshold [degree] to determine Position PID control available range
float KeiganMotor::readPositionP | ( | void | ) |
Read the resister value of Position PID controller P gain
float KeiganMotor::readQCurrentD | ( | void | ) |
Read the resister value of Current PID controller D gain
float KeiganMotor::readQCurrentI | ( | void | ) |
Read the resister value of Current PID controller I gain
float KeiganMotor::readQCurrentP | ( | void | ) |
Read the resister value of Current PID controller P gain
bool KeiganMotor::readRegister | ( | uint8_t | reg, |
uint8_t * | value, | ||
uint8_t | value_len | ||
) |
Read register function
[in] | reg | register |
[out] | *value | value pointer to read |
[in] | value_len | value length |
true | received data successfully |
false | got an error |
float KeiganMotor::readSpeedD | ( | void | ) |
Read the resister value of Speed PID controller D gain
float KeiganMotor::readSpeedI | ( | void | ) |
Read the resister value of Speed PID controller I gain
float KeiganMotor::readSpeedP | ( | void | ) |
Read the resister value of Speed PID controller P gain
status_t KeiganMotor::readStatus | ( | void | ) |
Read status function
You can see the current status of KeiganMotor.
bool KeiganMotor::reboot | ( | bool | response = false | ) |
Reboot KeiganMotor
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::resetAllRegisters | ( | bool | response = false | ) |
Reset all the registers to default.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::resetPID | ( | bool | response = false | ) |
Reset all the PID parameters to default
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::resetRegister | ( | uint8_t | reg, |
bool | response = false |
||
) |
Reset a register value to default.
[in] | reg | Register (See command_list.h) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::runAtVelocity | ( | float | value, |
bool | response = false |
||
) |
Run at a certain velocity [radian/second]
This function combines speed and runForward or runReverse function.
[in] | value | velocity [radian/second] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::runAtVelocityRpm | ( | float | rpm, |
bool | response = false |
||
) |
Run at a certain velocity [rotation/minute] (rpm)
Plus direction is counter clockwise when viewed from the rotation axis.
This function combines speed and runForward or runReverse function.
[in] | rpm | rpm [rotation/minute] (rpm) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::runForward | ( | bool | response = false | ) |
Run forward
It uses preset speed value by function speed()
Forward direction is counter clockwise when viewed from the rotation axis.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::runReverse | ( | bool | response = false | ) |
Run Reverse
It uses preset speed value by function speed()
Forward direction is counter clockwise when viewed from the rotation axis.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::safeRun | ( | bool | isEnabled, |
uint32_t | timeout, | ||
uint8_t | op, | ||
bool | response = false |
||
) |
Set safe run mode to stop motor automatically when it cannot receive next command within a certain period (timeout).
[in] | isEnabled | true if you want KeiganMotor stop automatically |
[in] | timeout | timeout [millisecond] |
[in] | op | SafeRunOption (stop behaviour in case of timeout) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::saveAllRegisters | ( | bool | response = false | ) |
Save all the registers KeiganMotor retains.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::speed | ( | float | value, |
bool | response = false |
||
) |
Set anglular speed [radian/second]
[in] | value | anglular speed [radian/second] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::speedD | ( | float | value, |
bool | response = false |
||
) |
Set Speed PID controller gain D.
[in] | value | Speed PID controller gain D (differential). |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::speedI | ( | float | value, |
bool | response = false |
||
) |
Set Speed PID controller gain I.
[in] | value | Speed PID controller gain I (integral) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::speedP | ( | float | value, |
bool | response = false |
||
) |
Set Speed PID controller gain P.
[in] | value | Speed PID controller gain P (proportional) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::speedRpm | ( | float | rpm, |
bool | response = false |
||
) |
Set anglular speed [rotation/minute] (rpm)
[in] | rpm | anglular speed [rotation/minute] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::startIMUMeasurement | ( | bool | response = false | ) |
Start IMU measurement timer
This function will start IMU measurement notfication
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::startMotorMeasurement | ( | bool | response = false | ) |
Start motor measurement timer
This function will start motor measurement notfication
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::stop | ( | bool | response = false | ) |
Stop
Keep velocity 0 by velocity control
Forward direction is counter clockwise when viewed from the rotation axis.
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::stopIMUMeasurement | ( | bool | response = false | ) |
Stop IMU measurement timer
This function will stop IMU measurement notfication
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::stopMotorMeasurement | ( | bool | response = false | ) |
Stop motor measurement timer
This function will stop motor measurement notfication
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::wait | ( | uint32_t | time, |
bool | response = false |
||
) |
Wait for execution of next commands for time [msec].
KeiganMotor has a FIFO queue inside, and this function make its execution paused for the time.
This function uses the internal timer of KeiganMotor.
[in] | time | time to stop the queue [milliseconds] |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::write | ( | uint8_t | command, |
uint8_t * | value, | ||
uint8_t | value_len, | ||
bool | response = false |
||
) |
Write command function
[in] | command | command |
[in] | *value | value pointer to write |
[in] | value_len | value length |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
bool KeiganMotor::writeResponse | ( | bool | isEnabled, |
bool | response = false |
||
) |
Set write response enabled or disabled
It response is enabled, KeiganMotor will send write response after receiving write command.
[in] | isEnabled | true if write response is enabled (default: true) |
[in] | response | true if you get response after sending command, default: false |
true | received response from KeiganMotor successfully |
false | got an error |
float KeiganMotor::degree |
motor angle position [degree]
error_t KeiganMotor::error |
Error or success information
imu_meas_t KeiganMotor::imu |
IMU measurement data
motor_meas_t KeiganMotor::measurement |
Motor measurement data
float KeiganMotor::position |
motor angle position [radian]
float KeiganMotor::rpm |
motor angle velocity [rotation/minute] (rpm)
status_t KeiganMotor::status |
Status of KeiganMotor KeiganMotor のステータス
float KeiganMotor::torque |
motor torque [N*m]
float KeiganMotor::velocity |
motor angle velocity [radian/second]