mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_PiccoloCAN: Add Currawong ECU message handling
This commit is contained in:
parent
813c21ffc0
commit
080c0a77e8
@ -33,6 +33,8 @@
|
|||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
|
#include <AP_EFI/AP_EFI_Currawong_ECU.h>
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
// Protocol files for the Velocity ESC
|
// Protocol files for the Velocity ESC
|
||||||
@ -233,6 +235,13 @@ void AP_PiccoloCAN::loop()
|
|||||||
break;
|
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;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
@ -736,6 +745,18 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
|
|||||||
return result;
|
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)
|
* Check if a given servo channel is "active" (has been configured for Piccolo control output)
|
||||||
*/
|
*/
|
||||||
|
@ -28,6 +28,8 @@
|
|||||||
|
|
||||||
#include "piccolo_protocol/ServoPackets.h"
|
#include "piccolo_protocol/ServoPackets.h"
|
||||||
|
|
||||||
|
#include <AP_EFI/AP_EFI_Currawong_ECU.h>
|
||||||
|
|
||||||
// maximum number of ESC allowed on CAN bus simultaneously
|
// maximum number of ESC allowed on CAN bus simultaneously
|
||||||
#define PICCOLO_CAN_MAX_NUM_ESC 16
|
#define PICCOLO_CAN_MAX_NUM_ESC 16
|
||||||
#define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4)
|
#define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4)
|
||||||
@ -130,6 +132,11 @@ private:
|
|||||||
|
|
||||||
// interpret a servo message received over CAN
|
// interpret a servo message received over CAN
|
||||||
bool handle_servo_message(AP_HAL::CANFrame &frame);
|
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;
|
bool _initialized;
|
||||||
char _thread_name[16];
|
char _thread_name[16];
|
||||||
@ -207,6 +214,8 @@ private:
|
|||||||
AP_Int32 _srv_bm; //! Servo selection bitmask
|
AP_Int32 _srv_bm; //! Servo selection bitmask
|
||||||
AP_Int16 _srv_hz; //! Servo update rate (Hz)
|
AP_Int16 _srv_hz; //! Servo update rate (Hz)
|
||||||
|
|
||||||
|
AP_Int8 _ecu_en; //! ECU Enable
|
||||||
|
|
||||||
HAL_Semaphore _telem_sem;
|
HAL_Semaphore _telem_sem;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user