AP_PiccoloCAN: Add Currawong ECU message handling

This commit is contained in:
Reilly Callaway 2022-03-30 14:12:20 +11:00 committed by Randy Mackay
parent a18781df65
commit 3634d208e3
2 changed files with 30 additions and 0 deletions

View File

@ -33,6 +33,8 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_EFI/AP_EFI_Currawong_ECU.h>
#include <stdio.h>
// Protocol files for the Velocity ESC
@ -233,6 +235,13 @@ void AP_PiccoloCAN::loop()
break;
}
break;
case MessageGroup::ECU_OUT:
#if HAL_EFI_CURRAWONG_ECU_ENABLED
if (handle_ecu_message(rxFrame)) {
// Returns true if the message was successfully decoded
}
#endif
break;
default:
break;
@ -736,6 +745,18 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
return result;
}
#if HAL_EFI_CURRAWONG_ECU_ENABLED
bool AP_PiccoloCAN::handle_ecu_message(AP_HAL::CANFrame &frame)
{
// Get the ecu instance
AP_EFI_Currawong_ECU* ecu = AP_EFI_Currawong_ECU::get_instance();
if (ecu != nullptr) {
return ecu->handle_message(frame);
}
return false;
}
#endif
/**
* Check if a given servo channel is "active" (has been configured for Piccolo control output)
*/

View File

@ -28,6 +28,8 @@
#include "piccolo_protocol/ServoPackets.h"
#include <AP_EFI/AP_EFI_Currawong_ECU.h>
// maximum number of ESC allowed on CAN bus simultaneously
#define PICCOLO_CAN_MAX_NUM_ESC 16
#define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4)
@ -130,6 +132,11 @@ private:
// interpret a servo message received over CAN
bool handle_servo_message(AP_HAL::CANFrame &frame);
#if HAL_EFI_CURRAWONG_ECU_ENABLED
// interpret an ECU message received over CAN
bool handle_ecu_message(AP_HAL::CANFrame &frame);
#endif
bool _initialized;
char _thread_name[16];
@ -207,6 +214,8 @@ private:
AP_Int32 _srv_bm; //! Servo selection bitmask
AP_Int16 _srv_hz; //! Servo update rate (Hz)
AP_Int8 _ecu_en; //! ECU Enable
HAL_Semaphore _telem_sem;
};