Arduino-I2C-KM1  2.0.2
KeiganMotor Arduino Library
KeiganMotor クラス

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::KeiganMotor ( uint8_t  address,
int  clock = 1000000 
)

Initialize by specifying I2C Address

KeiganMotorコンストラクタ.

引数
[in]addressI2C slave address (7bit: 0x01~0x7E)
[in]clock(It can be up to 4000000. default:1000000)

関数詳解

◆ acc()

bool KeiganMotor::acc ( float  value,
bool  response = false 
)

Set acceleration value. It is ignored when curve type is 0(CURVETYPE_NONE).

引数
[in]valuefloat acceleration to set [radian/second^2]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ begin()

void KeiganMotor::begin ( )

start I2C communication via Wire library

◆ curveType()

bool KeiganMotor::curveType ( uint8_t  type,
bool  response = false 
)

Set curve type for motion control.

引数
[in]typeCurveType to set
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ dec()

bool KeiganMotor::dec ( float  value,
bool  response = false 
)

Set deceleration value. It is ignored when curve type is 0(CURVETYPE_NONE).

引数
[in]valuefloat deceleration to set [radian/second^2]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ disable()

bool KeiganMotor::disable ( bool  response = false)

Disable motor action.

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ enable()

bool KeiganMotor::enable ( bool  response = false)

Enable motor action.

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ enableCheckSum()

bool KeiganMotor::enableCheckSum ( bool  isEnabled,
bool  response = false 
)

Set checksum validadtion enabled.

KeiganMotor will validate received data after receiving this command.

引数
[in]isEnabledtrue if make Checksum validation enabled
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ free()

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]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ getError()

error_t KeiganMotor::getError ( )

Get the error that master retains.
getError() is designed to use after getting response of write command.

戻り値
the latest error that Arduino retains (see error_t)
bool result = m.runFoward(true);
if(result != 0){
error_t error = m.getError();
Serial.print("error code is ");
Serial.println(error.code);
}
覚え書き
The difference between getError() and readError() function is that
getError() just returns the latest error data retained by master (Arduino), while readError()
send a command to request the latest error data that KeiganMotor retains.

◆ i2cSlaveAddress()

bool KeiganMotor::i2cSlaveAddress ( uint8_t  address,
bool  response = false 
)

Set I2C slave address.

引数
[in]addressI2C address (0x00~0x7F)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
saveAllRegisters() and reboot() is required to reflact the address value.
if(m.i2cSlaveAddress(0x30)){
m.saveAllRegisters();
delay(3000);
m.reboot();
}

◆ interface()

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]flaguint8_t value consists of the following bit flag.
[in]responsetrue 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();
覚え書き
The following interfaces share a common resource, so you cannot set 1 to all of them.
  • BLE and Linkage
  • UART1(USB) and UART2
  • I2C, DigitalIO and UART2

◆ led()

bool KeiganMotor::led ( uint8_t  state,
uint8_t  r,
uint8_t  g,
uint8_t  b,
bool  response = false 
)

Set LED lit

引数
[in]stateLedState
[in]rRed brightness (0-255)
[in]gGreen brightness (0-255)
[in]bBlue brightness (0-255)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ limitCurrent()

bool KeiganMotor::limitCurrent ( float  value,
bool  response = false 
)

Limit current

引数
[in]valueMax current to limit.
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
Make this value big enough when you want to draw maximum energy from power source.

◆ maxSpeed()

bool KeiganMotor::maxSpeed ( float  value,
bool  response = false 
)

Set max speed function to limit absolute value of velocity

引数
[in]valuefloat speed to set [radian/second]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ maxTorque()

bool KeiganMotor::maxTorque ( float  value,
bool  response = false 
)

Set Max torque value to limit current not to be above the torque.

引数
[in]valuefloat max torque to set [N*m]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ minSpeed()

bool KeiganMotor::minSpeed ( float  value,
bool  response = false 
)

Set min speed. It is used in case of "prepare playback motion"

引数
[in]valuefloat speed to set [radian/second]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ motorMeasurementInterval()

bool KeiganMotor::motorMeasurementInterval ( uint8_t  interval,
bool  response = false 
)

Set motor measurement interval

引数
[in]intervalthe following integer value
  • 0: INTERVAL_MS_2MS = 2 [ms]
  • 1: INTERVAL_MS_5MS = 5 [ms]
  • 2: INTERVAL_MS_10MS = 10 [ms]
  • 3: INTERVAL_MS_20MS = 20 [ms]
  • 4: INTERVAL_MS_50MS = 50 [ms]
  • 5: INTERVAL_MS_100MS = 100 [ms]
  • 6: INTERVAL_MS_200MS = 200 [ms]
  • 7: INTERVAL_MS_500MS = 500 [ms]
  • 8: INTERVAL_MS_1000MS = 1000 [ms]
  • 9: INTERVAL_MS_2000MS = 2000 [ms]
  • 10:INTERVAL_MS_5000MS = 5000 [ms]
  • 11:INTERVAL_MS_10000MS =10000 [ms]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
覚え書き
The default value is 100ms. The value less than 100ms will be ignored only in case of BLE (Bluetooth)
See interface function

◆ moveByDistance()

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]distancedistance [radian]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ moveByDistanceDegree()

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]degreedegree [degree]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ moveToPosition()

bool KeiganMotor::moveToPosition ( float  position,
bool  response = false 
)

Move to an absolute position [radian]

It uses preset speed value by function speed()

引数
[in]positionposition [radian]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ moveToPositionDegree()

bool KeiganMotor::moveToPositionDegree ( float  degree,
bool  response = false 
)

Move to an absolute position [degree]

It uses preset speed value by function speed()

引数
[in]degreedegree [degree]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ positionD()

bool KeiganMotor::positionD ( float  value,
bool  response = false 
)

Set Position PID controller gain D

引数
[in]valuePosition PID controller gain D (differential).
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
Position integral and differential term are ignored out of positionIDThreshold range. (See positionIDThreshold function)

◆ positionI()

bool KeiganMotor::positionI ( float  value,
bool  response = false 
)

Set Position PID controller gain I

引数
[in]valuePosition PID controller gain I (integral)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
Position integral and differential term are ignored out of positionIDThreshold range. (See positionIDThreshold function)

◆ positionIDThreshold()

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.

if(|currentPosition - targetPosition| < threshold) // do PID control.
else {// do P control}
覚え書き
Position integral and differential gains are ignored out of the range.If you want to always do PID control,
set the this value large enough.
引数
[in]valuethe threshold to determine the available range of PID control. [radian]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ positionIDThresholdDegree()

bool KeiganMotor::positionIDThresholdDegree ( float  value,
bool  response = false 
)

Set the threshold [degree] to determine Position PID control available range

See KeiganMotor::positionIDThreshold.

引数
[in]valueThe threshold determines the available area of PID control. [degree]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ positionP()

bool KeiganMotor::positionP ( float  value,
bool  response = false 
)

Set Position PID controller gain P

引数
[in]valuePosition PID controller gain P (proportional)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ presetPosition()

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]valuepreset position [radian]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ presetPositionDegree()

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]degreepreset position [degree]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ qCurrentD()

bool KeiganMotor::qCurrentD ( float  value,
bool  response = false 
)

Set Q-axis current PID controller gain D.

引数
[in]valueQ-axis current PID controller gain D (differential)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ qCurrentI()

bool KeiganMotor::qCurrentI ( float  value,
bool  response = false 
)

Set Q-axis current PID controller gain I.

引数
[in]valueQ-axis current PID controller gain I (integral)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ qCurrentP()

bool KeiganMotor::qCurrentP ( float  value,
bool  response = false 
)

Set Q-axis current PID controller gain P.

引数
[in]valueQ-axis current PID controller gain P (proportional)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ readAcc()

float KeiganMotor::readAcc ( void  )

Read the acceleration value

戻り値
float acceleration [radian/second^2]

◆ readCurveType()

uint8_t KeiganMotor::readCurveType ( void  )

Read the curveType fo motion control.
See CURVE_TYPE_NONE and CURVE_TYPE_TRAPEZOID.

戻り値
curveType

◆ readDec()

float KeiganMotor::readDec ( void  )

Read the deceleration value

戻り値
float deceleration [radian/second^2]

◆ readDeviceInfo()

bool KeiganMotor::readDeviceInfo ( uint8_t  type,
char *  str 
)

Read the device information

todo:

◆ readDeviceName()

bool KeiganMotor::readDeviceName ( char *  name)

Read the KeiganMotor device name

The name is like "KM-1U AI09#3R9"

覚え書き
Please set char *name size more than 14 bytes.

◆ readError()

error_t KeiganMotor::readError ( void  )

Read the latest error

The response data is the same formart as error response of write command.

戻り値
the latest error (see error_t)
覚え書き
The difference between getError() and this function is that
getError() just returns the retained error data by master (Arduino), while readError() send a command to request the latest error data that KeiganMotor retains.

◆ readIMUMeasurement()

bool KeiganMotor::readIMUMeasurement ( void  )

Read IMU measurement data

IMU values are available after sending this command. See imu_t.

if(m.readIMUMeasurement()){
Serial.print(gyro-x: );
Serial.println(m.imu.gyroX);
} else {
Serial.println("error");
}
戻り値
truereceived data from KeiganMotor successfully
falsegot an error

◆ readMaxSpeed()

float KeiganMotor::readMaxSpeed ( void  )

Read the maximum speed

戻り値
float max speed [radian/second]

◆ readMaxTorque()

float KeiganMotor::readMaxTorque ( void  )

Read the resister value of max torque (limitation)

戻り値
float max torque [N*m]

You can do torque control during velocity or position control

◆ readMinSpeed()

float KeiganMotor::readMinSpeed ( void  )

Read the minimum speed

戻り値
float min speed [radian/second]

◆ readMotorMeasurement()

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. .

戻り値
truereceived data from KeiganMotor successfully
falsegot an error
if(m.readMotorMeasurement()){
Serial.print(degree: );
Serial.println(m.degree);
} else {
Serial.println("error");
}

◆ readPositionD()

float KeiganMotor::readPositionD ( void  )

Read the resister value of Position PID controller D gain

戻り値
float gain

◆ readPositionI()

float KeiganMotor::readPositionI ( void  )

Read the resister value of Position PID controller I gain

戻り値
float gain

◆ readPositionIDThreshold()

float KeiganMotor::readPositionIDThreshold ( void  )

Read the threshold [radian] to determine Position PID control available range

戻り値
float threshold [radian]

◆ readPositionIDThresholdDegree()

float KeiganMotor::readPositionIDThresholdDegree ( void  )

Read the threshold [degree] to determine Position PID control available range

戻り値
float threshold [degree]

◆ readPositionP()

float KeiganMotor::readPositionP ( void  )

Read the resister value of Position PID controller P gain

戻り値
float gain

◆ readQCurrentD()

float KeiganMotor::readQCurrentD ( void  )

Read the resister value of Current PID controller D gain

戻り値
float gain

◆ readQCurrentI()

float KeiganMotor::readQCurrentI ( void  )

Read the resister value of Current PID controller I gain

戻り値
float gain

◆ readQCurrentP()

float KeiganMotor::readQCurrentP ( void  )

Read the resister value of Current PID controller P gain

戻り値
float gain

◆ readRegister()

bool KeiganMotor::readRegister ( uint8_t  reg,
uint8_t *  value,
uint8_t  value_len 
)

Read register function

引数
[in]regregister
[out]*valuevalue pointer to read
[in]value_lenvalue length
戻り値
truereceived data successfully
falsegot an error
覚え書き
Use getError().code to get error code.

◆ readSpeedD()

float KeiganMotor::readSpeedD ( void  )

Read the resister value of Speed PID controller D gain

戻り値
float gain

◆ readSpeedI()

float KeiganMotor::readSpeedI ( void  )

Read the resister value of Speed PID controller I gain

戻り値
float gain

◆ readSpeedP()

float KeiganMotor::readSpeedP ( void  )

Read the resister value of Speed PID controller P gain

戻り値
float gain

◆ readStatus()

status_t KeiganMotor::readStatus ( void  )

Read status function

You can see the current status of KeiganMotor.

戻り値
status Status of KeiganMotor (See status_t.)

◆ reboot()

bool KeiganMotor::reboot ( bool  response = false)

Reboot KeiganMotor

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ resetAllRegisters()

bool KeiganMotor::resetAllRegisters ( bool  response = false)

Reset all the registers to default.

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
saveAllRegisters() is required to save in flash.

◆ resetPID()

bool KeiganMotor::resetPID ( bool  response = false)

Reset all the PID parameters to default

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
saveAllRegisters() is required to save in flash.

◆ resetRegister()

bool KeiganMotor::resetRegister ( uint8_t  reg,
bool  response = false 
)

Reset a register value to default.

引数
[in]regRegister (See command_list.h)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
The register values are saved by this command permanently in the flash.

◆ runAtVelocity()

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]valuevelocity [radian/second]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ runAtVelocityRpm()

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]rpmrpm [rotation/minute] (rpm)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ runForward()

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]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ runReverse()

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]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ safeRun()

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]isEnabledtrue if you want KeiganMotor stop automatically
[in]timeouttimeout [millisecond]
[in]opSafeRunOption (stop behaviour in case of timeout)
参照
SAFE_RUN_TIMEOUT_FREE = 0
SAFE_RUN_TIMEOUT_DISABLE = 1
SAFE_RUN_TIMEOUT_STOP = 2
SAFE_RUN_TIMEOUT_POS_FIX = 3
引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ saveAllRegisters()

bool KeiganMotor::saveAllRegisters ( bool  response = false)

Save all the registers KeiganMotor retains.

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈
The register values are saved by this command permanently in the flash.

◆ speed()

bool KeiganMotor::speed ( float  value,
bool  response = false 
)

Set anglular speed [radian/second]

引数
[in]valueanglular speed [radian/second]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ speedD()

bool KeiganMotor::speedD ( float  value,
bool  response = false 
)

Set Speed PID controller gain D.

引数
[in]valueSpeed PID controller gain D (differential).
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ speedI()

bool KeiganMotor::speedI ( float  value,
bool  response = false 
)

Set Speed PID controller gain I.

引数
[in]valueSpeed PID controller gain I (integral)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ speedP()

bool KeiganMotor::speedP ( float  value,
bool  response = false 
)

Set Speed PID controller gain P.

引数
[in]valueSpeed PID controller gain P (proportional)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ speedRpm()

bool KeiganMotor::speedRpm ( float  rpm,
bool  response = false 
)

Set anglular speed [rotation/minute] (rpm)

引数
[in]rpmanglular speed [rotation/minute]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ startIMUMeasurement()

bool KeiganMotor::startIMUMeasurement ( bool  response = false)

Start IMU measurement timer

This function will start IMU measurement notfication

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ startMotorMeasurement()

bool KeiganMotor::startMotorMeasurement ( bool  response = false)

Start motor measurement timer

This function will start motor measurement notfication

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ stop()

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]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ stopIMUMeasurement()

bool KeiganMotor::stopIMUMeasurement ( bool  response = false)

Stop IMU measurement timer

This function will stop IMU measurement notfication

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ stopMotorMeasurement()

bool KeiganMotor::stopMotorMeasurement ( bool  response = false)

Stop motor measurement timer

This function will stop motor measurement notfication

引数
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ wait()

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]timetime to stop the queue [milliseconds]
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error

◆ write()

bool KeiganMotor::write ( uint8_t  command,
uint8_t *  value,
uint8_t  value_len,
bool  response = false 
)

Write command function

引数
[in]commandcommand
[in]*valuevalue pointer to write
[in]value_lenvalue length
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
覚え書き
Use getError().code to get error code.

◆ writeResponse()

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]isEnabledtrue if write response is enabled (default: true)
[in]responsetrue if you get response after sending command, default: false
戻り値
truereceived response from KeiganMotor successfully
falsegot an error
注釈

メンバ詳解

◆ degree

float KeiganMotor::degree

motor angle position [degree]

◆ error

error_t KeiganMotor::error

Error or success information

◆ imu

imu_meas_t KeiganMotor::imu

IMU measurement data

◆ measurement

motor_meas_t KeiganMotor::measurement

Motor measurement data

◆ position

float KeiganMotor::position

motor angle position [radian]

◆ rpm

float KeiganMotor::rpm

motor angle velocity [rotation/minute] (rpm)

◆ status

status_t KeiganMotor::status

Status of KeiganMotor KeiganMotor のステータス

◆ torque

float KeiganMotor::torque

motor torque [N*m]

◆ velocity

float KeiganMotor::velocity

motor angle velocity [radian/second]


このクラス詳解は次のファイルから抽出されました:
KeiganMotor::degree
float degree
motor angle position [degree]
Definition: KM1_I2C.h:147
error_t
Error or success information received from KeiganMotor
Definition: KM1_I2C.h:28
KeiganMotor::error
error_t error
Error or success information
Definition: KM1_I2C.h:160
error_t::code
uint8_t code
Definition: KM1_I2C.h:32
INTERFACE_BIT_I2C
#define INTERFACE_BIT_I2C
Definition: Definitions.h:24
INTERFACE_BIT_BUTTON
#define INTERFACE_BIT_BUTTON
Definition: Definitions.h:27