AP_ToshibaCAN: Using the maximum number of ESCs definition
AP_ToshibaCAN: Using the maximum number of ESCs definition
This commit is contained in:
parent
0e6ae6c5b4
commit
bd688ef412
@ -302,7 +302,7 @@ void AP_ToshibaCAN::loop()
|
||||
uavcan::CanFrame recv_frame;
|
||||
while (read_frame(recv_frame, timeout)) {
|
||||
// decode rpm and voltage data
|
||||
if ((recv_frame.id >= MOTOR_DATA1) && (recv_frame.id <= MOTOR_DATA1 + 12)) {
|
||||
if ((recv_frame.id >= MOTOR_DATA1) && (recv_frame.id <= MOTOR_DATA1 + TOSHIBACAN_MAX_NUM_ESCS)) {
|
||||
// copy contents to our structure
|
||||
motor_reply_data1_t reply_data;
|
||||
memcpy(reply_data.data, recv_frame.data, sizeof(reply_data.data));
|
||||
@ -328,7 +328,7 @@ void AP_ToshibaCAN::loop()
|
||||
}
|
||||
|
||||
// decode temperature data
|
||||
if ((recv_frame.id >= MOTOR_DATA2) && (recv_frame.id <= MOTOR_DATA2 + 12)) {
|
||||
if ((recv_frame.id >= MOTOR_DATA2) && (recv_frame.id <= MOTOR_DATA2 + TOSHIBACAN_MAX_NUM_ESCS)) {
|
||||
// motor data2 data format is 8 bytes (64 bits)
|
||||
// 10 bits: U temperature
|
||||
// 10 bits: V temperature
|
||||
@ -352,7 +352,7 @@ void AP_ToshibaCAN::loop()
|
||||
}
|
||||
|
||||
// decode cumulative usage data
|
||||
if ((recv_frame.id >= MOTOR_DATA3) && (recv_frame.id <= MOTOR_DATA3 + 12)) {
|
||||
if ((recv_frame.id >= MOTOR_DATA3) && (recv_frame.id <= MOTOR_DATA3 + TOSHIBACAN_MAX_NUM_ESCS)) {
|
||||
// motor data3 data format is 8 bytes (64 bits)
|
||||
// 3 bytes: usage in seconds
|
||||
// 2 bytes: number of times rotors started and stopped
|
||||
|
Loading…
Reference in New Issue
Block a user