2019-12-09 00:30:58 -04:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*
|
2022-03-30 02:16:24 -03:00
|
|
|
* Author: Oliver Walters / Currawong Engineering Pty Ltd
|
2019-12-09 00:30:58 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2020-05-31 09:36:45 -03:00
|
|
|
#include <AP_CANManager/AP_CANDriver.h>
|
2019-12-09 00:30:58 -04:00
|
|
|
|
2020-09-02 00:52:19 -03:00
|
|
|
#include <AP_Param/AP_Param.h>
|
2021-02-27 13:12:21 -04:00
|
|
|
#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>
|
2020-09-02 00:52:19 -03:00
|
|
|
|
2023-05-21 22:57:51 -03:00
|
|
|
#include "AP_PiccoloCAN_Device.h"
|
|
|
|
#include "AP_PiccoloCAN_ESC.h"
|
|
|
|
#include "AP_PiccoloCAN_ECU.h"
|
|
|
|
#include "AP_PiccoloCAN_Servo.h"
|
2022-03-30 00:12:20 -03:00
|
|
|
#include <AP_EFI/AP_EFI_Currawong_ECU.h>
|
|
|
|
|
2019-12-09 00:47:42 -04:00
|
|
|
#if HAL_PICCOLO_CAN_ENABLE
|
2019-12-09 00:30:58 -04:00
|
|
|
|
2020-09-02 00:55:55 -03:00
|
|
|
#define PICCOLO_MSG_RATE_HZ_MIN 1
|
|
|
|
#define PICCOLO_MSG_RATE_HZ_MAX 500
|
|
|
|
#define PICCOLO_MSG_RATE_HZ_DEFAULT 50
|
2020-09-02 00:52:19 -03:00
|
|
|
|
2021-02-27 13:12:21 -04:00
|
|
|
class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend
|
2019-12-09 00:30:58 -04:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_PiccoloCAN();
|
|
|
|
~AP_PiccoloCAN();
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_PiccoloCAN);
|
2019-12-09 00:30:58 -04:00
|
|
|
|
2020-09-02 00:52:19 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2019-12-09 00:30:58 -04:00
|
|
|
// Return PiccoloCAN from @driver_index or nullptr if it's not ready or doesn't exist
|
|
|
|
static AP_PiccoloCAN *get_pcan(uint8_t driver_index);
|
|
|
|
|
|
|
|
// initialize PiccoloCAN bus
|
|
|
|
void init(uint8_t driver_index, bool enable_filters) override;
|
2020-05-31 09:36:45 -03:00
|
|
|
bool add_interface(AP_HAL::CANIface* can_iface) override;
|
2019-12-09 00:30:58 -04:00
|
|
|
|
|
|
|
// called from SRV_Channels
|
|
|
|
void update();
|
|
|
|
|
2020-11-10 00:35:03 -04:00
|
|
|
// send ESC telemetry messages over MAVLink
|
|
|
|
void send_esc_telemetry_mavlink(uint8_t mav_chan);
|
|
|
|
|
|
|
|
// return true if a particular servo is 'active' on the Piccolo interface
|
|
|
|
bool is_servo_channel_active(uint8_t chan);
|
|
|
|
|
2020-01-23 00:31:44 -04:00
|
|
|
// return true if a particular ESC is 'active' on the Piccolo interface
|
|
|
|
bool is_esc_channel_active(uint8_t chan);
|
|
|
|
|
2020-11-10 00:35:03 -04:00
|
|
|
// return true if a particular servo has been detected on the CAN interface
|
|
|
|
bool is_servo_present(uint8_t chan, uint64_t timeout_ms = 2000);
|
|
|
|
|
|
|
|
// return true if a particular ESC has been detected on the CAN interface
|
|
|
|
bool is_esc_present(uint8_t chan, uint64_t timeout_ms = 2000);
|
|
|
|
|
|
|
|
// return true if a particular servo is enabled
|
|
|
|
bool is_servo_enabled(uint8_t chan);
|
2019-12-09 00:30:58 -04:00
|
|
|
|
2019-12-20 00:13:44 -04:00
|
|
|
// return true if a particular ESC is enabled
|
|
|
|
bool is_esc_enabled(uint8_t chan);
|
|
|
|
|
2019-12-09 00:30:58 -04:00
|
|
|
// test if the Piccolo CAN driver is ready to be armed
|
|
|
|
bool pre_arm_check(char* reason, uint8_t reason_len);
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
// loop to send output to ESCs in background thread
|
|
|
|
void loop();
|
|
|
|
|
|
|
|
// write frame on CAN bus, returns true on success
|
2020-05-31 09:36:45 -03:00
|
|
|
bool write_frame(AP_HAL::CANFrame &out_frame, uint64_t timeout);
|
2019-12-09 00:30:58 -04:00
|
|
|
|
|
|
|
// read frame on CAN bus, returns true on succses
|
2020-05-31 09:36:45 -03:00
|
|
|
bool read_frame(AP_HAL::CANFrame &recv_frame, uint64_t timeout);
|
2019-12-09 00:30:58 -04:00
|
|
|
|
|
|
|
// send ESC commands over CAN
|
|
|
|
void send_esc_messages(void);
|
|
|
|
|
|
|
|
// interpret an ESC message received over CAN
|
2020-05-31 09:36:45 -03:00
|
|
|
bool handle_esc_message(AP_HAL::CANFrame &frame);
|
2019-12-09 00:30:58 -04:00
|
|
|
|
2020-11-10 00:35:03 -04:00
|
|
|
// send servo commands over CAN
|
|
|
|
void send_servo_messages(void);
|
|
|
|
|
|
|
|
// interpret a servo message received over CAN
|
|
|
|
bool handle_servo_message(AP_HAL::CANFrame &frame);
|
2023-03-15 20:05:59 -03:00
|
|
|
|
|
|
|
#if AP_EFI_CURRAWONG_ECU_ENABLED
|
2022-03-30 02:16:24 -03:00
|
|
|
void send_ecu_messages(void);
|
|
|
|
|
2022-03-30 00:12:20 -03:00
|
|
|
// interpret an ECU message received over CAN
|
|
|
|
bool handle_ecu_message(AP_HAL::CANFrame &frame);
|
|
|
|
#endif
|
2020-11-10 00:35:03 -04:00
|
|
|
|
2019-12-09 00:30:58 -04:00
|
|
|
bool _initialized;
|
2019-12-30 17:36:47 -04:00
|
|
|
char _thread_name[16];
|
2019-12-09 00:30:58 -04:00
|
|
|
uint8_t _driver_index;
|
2020-05-31 09:36:45 -03:00
|
|
|
AP_HAL::CANIface* _can_iface;
|
|
|
|
HAL_EventHandle _event_handle;
|
2019-12-09 00:30:58 -04:00
|
|
|
|
2023-05-21 22:57:51 -03:00
|
|
|
AP_PiccoloCAN_Servo _servos[PICCOLO_CAN_MAX_NUM_SERVO];
|
|
|
|
AP_PiccoloCAN_ESC _escs[PICCOLO_CAN_MAX_NUM_ESC];
|
2020-11-09 22:51:03 -04:00
|
|
|
|
2022-03-30 02:16:24 -03:00
|
|
|
struct CurrawongECU_Info_t {
|
|
|
|
float command;
|
|
|
|
bool newCommand;
|
|
|
|
} _ecu_info;
|
|
|
|
|
2020-09-02 00:52:19 -03:00
|
|
|
// Piccolo CAN parameters
|
|
|
|
AP_Int32 _esc_bm; //! ESC selection bitmask
|
2020-09-03 01:05:33 -03:00
|
|
|
AP_Int16 _esc_hz; //! ESC update rate (Hz)
|
2020-09-02 00:52:19 -03:00
|
|
|
|
2020-11-10 00:35:03 -04:00
|
|
|
AP_Int32 _srv_bm; //! Servo selection bitmask
|
|
|
|
AP_Int16 _srv_hz; //! Servo update rate (Hz)
|
2021-06-24 03:23:14 -03:00
|
|
|
|
2022-03-30 02:16:24 -03:00
|
|
|
AP_Int16 _ecu_id; //! ECU Node ID
|
|
|
|
AP_Int16 _ecu_hz; //! ECU update rate (Hz)
|
2022-03-30 00:12:20 -03:00
|
|
|
|
2021-06-24 03:23:14 -03:00
|
|
|
HAL_Semaphore _telem_sem;
|
2019-12-09 00:30:58 -04:00
|
|
|
};
|
2019-12-09 00:47:42 -04:00
|
|
|
|
|
|
|
#endif // HAL_PICCOLO_CAN_ENABLE
|