Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Lua bindings for safety checks #108

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion .github/workflows/carbonix_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,9 @@ jobs:
run: sudo apt-get install zip
- name: Archive build output
run: |
zip -r build-output.zip build/
echo build/*/bin/ | xargs -n 1 cp -v ArduPlane/ReleaseNotes.txt
cp -v ArduPlane/ReleaseNotes.txt build/
zip -r build-output.zip build/*/bin/*
- name: Archive production artifacts
uses: actions/upload-artifact@v3
with:
Expand Down
35 changes: 19 additions & 16 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,7 @@ void AP_EFI_Serial_Hirth::send_request()
bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)
{
uint8_t computed_checksum = 0;
throttle = 0;

// clear buffer
memset(raw_data, 0, ARRAY_SIZE(raw_data));
Expand All @@ -199,7 +200,7 @@ bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)
thr = linearise_throttle(thr);
#endif

const uint16_t throttle = thr * THROTTLE_POSITION_FACTOR;
throttle = thr * THROTTLE_POSITION_FACTOR;

uint8_t idx = 0;

Expand Down Expand Up @@ -354,23 +355,24 @@ void AP_EFI_Serial_Hirth::log_status(void)
// @LoggerMessage: EFIS
// @Description: Electronic Fuel Injection data - Hirth specific Status information
// @Field: TimeUS: Time since system startup
// @Field: ETS1: Status of EGT1 excess temperature error
// @Field: ETS2: Status of EGT2 excess temperature error
// @Field: CTS1: Status of CHT1 excess temperature error
// @Field: CTS2: Status of CHT2 excess temperature error
// @Field: ETSS: Status of Engine temperature sensor
// @Field: ATSS: Status of Air temperature sensor
// @Field: APSS: Status of Air pressure sensor
// @Field: ES1: Status of EGT1 excess temperature error
// @Field: ES2: Status of EGT2 excess temperature error
// @Field: CS1: Status of CHT1 excess temperature error
// @Field: CS2: Status of CHT2 excess temperature error
// @Field: ETS: Status of Engine temperature sensor
// @Field: ATS: Status of Air temperature sensor
// @Field: APS: Status of Air pressure sensor
// @Field: TSS: Status of Temperature sensor
// @Field: CRCF: CRC failure count
// @Field: AckF: ACK failure count
// @Field: CRF: CRC failure count
// @Field: AKF: ACK failure count
// @Field: Up: Uptime between 2 messages
// @Field: ThrO: Throttle output as received by the engine
// @Field: ThO: Throttle output as received by the engine
// @Field: ThM: Modified Throttle output sent to the engine
AP::logger().WriteStreaming("EFIS",
"TimeUS,ETS1,ETS2,CTS1,CTS2,ETSS,ATSS,APSS,TSS,CRCF,AckF,Up,ThrO",
"s------------",
"F------------",
"QBBBBBBBBIIIf",
"TimeUS,ES1,ES2,CS1,CS2,ETS,ATS,APS,TSS,CRF,AKF,Up,ThO,ThM",
"s-------------",
"F-------------",
"QBBBBBBBBIIIfH",
AP_HAL::micros64(),
uint8_t(EGT_1_error_excess_temperature_status),
uint8_t(EGT_2_error_excess_temperature_status),
Expand All @@ -383,7 +385,8 @@ void AP_EFI_Serial_Hirth::log_status(void)
uint32_t(crc_fail_cnt),
uint32_t(ack_fail_cnt),
uint32_t(uptime),
float(internal_state.throttle_out));
float(internal_state.throttle_out),
uint16_t(throttle));
}
#endif // HAL_LOGGING_ENABLED

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ class AP_EFI_Serial_Hirth: public AP_EFI_Backend {

// Throttle values
uint16_t last_throttle;
uint16_t throttle;

uint32_t last_fuel_integration_ms;

Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Logger/AP_Logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -309,6 +309,8 @@ class AP_Logger
void Write_Message(const char *message);
void Write_MessageF(const char *fmt, ...);
void Write_ServoStatus(uint64_t time_us, uint8_t id, float position, float force, float speed, uint8_t power_pct);
void Write_PowerCktStatus(uint64_t time_us, uint8_t id, float voltage, float current, uint8_t error_flags);
void Write_DeviceTemperature(uint64_t time_us, uint8_t id, float temperature, uint8_t error_flags);
void Write_Compass();
void Write_Mode(uint8_t mode, const ModeReason reason);

Expand Down
30 changes: 30 additions & 0 deletions libraries/AP_Logger/LogFile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -453,6 +453,36 @@ void AP_Logger::Write_ServoStatus(uint64_t time_us, uint8_t id, float position,
WriteBlock(&pkt, sizeof(pkt));
}

/*
write servo voltage status from CAN servo
*/
void AP_Logger::Write_PowerCktStatus(uint64_t time_us, uint8_t id, float voltage, float current, uint8_t error_flags)
{
const struct log_CSVI pkt {
LOG_PACKET_HEADER_INIT(LOG_CSVI_MSG),
time_us : time_us,
id : id,
voltage : voltage,
current : current,
error_flags : error_flags
};
WriteBlock(&pkt, sizeof(pkt));
}

/*
write servo Temperature datafrom CAN servo
*/
void AP_Logger::Write_DeviceTemperature(uint64_t time_us, uint8_t id, float temperature, uint8_t error_flags)
{
const struct log_TEMP pkt {
LOG_PACKET_HEADER_INIT(LOG_TEMP_MSG),
time_us : time_us,
device_id : id,
temperature : temperature,
error_flags : error_flags
};
WriteBlock(&pkt, sizeof(pkt));
}

// Write a Yaw PID packet
void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info)
Expand Down
23 changes: 23 additions & 0 deletions libraries/AP_Logger/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -487,6 +487,23 @@ struct PACKED log_CSRV {
uint8_t power_pct;
};

struct PACKED log_CSVI {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
float voltage;
float current;
uint8_t error_flags;
};

struct PACKED log_TEMP {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t device_id;
float temperature;
uint8_t error_flags;
};

struct PACKED log_ARSP {
LOG_PACKET_HEADER;
uint64_t time_us;
Expand Down Expand Up @@ -1271,6 +1288,10 @@ LOG_STRUCTURE_FROM_AVOIDANCE \
LOG_STRUCTURE_FROM_ESC_TELEM \
{ LOG_CSRV_MSG, sizeof(log_CSRV), \
"CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000", true }, \
{ LOG_CSVI_MSG, sizeof(log_CSVI), \
"CSVI","QBffB","TimeUS,CId,vol,cur,err", "s#--%", "F-000", true }, \
{ LOG_TEMP_MSG, sizeof(log_TEMP), \
"TEMP","QBfB","TimeUS,CId,tmp,err", "s#-%", "F-00", true }, \
{ LOG_PIDR_MSG, sizeof(log_PID), \
"PIDR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS, true }, \
{ LOG_PIDP_MSG, sizeof(log_PID), \
Expand Down Expand Up @@ -1358,6 +1379,8 @@ enum LogMessages : uint8_t {
LOG_IDS_FROM_CAMERA,
LOG_TERRAIN_MSG,
LOG_CSRV_MSG,
LOG_CSVI_MSG,
LOG_TEMP_MSG,
LOG_IDS_FROM_ESC_TELEM,
LOG_IDS_FROM_BATTMONITOR,
LOG_IDS_FROM_HAL_CHIBIOS,
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -314,6 +314,7 @@ singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t 0 NUM_SERVO_CH
singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null
singleton AP_ESC_Telem method update_rpm void uint8_t 0 NUM_SERVO_CHANNELS uint16_t'skip_check float'skip_check
singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check
singleton AP_ESC_Telem method get_last_telem_data_ms uint32_t uint8_t 0 NUM_SERVO_CHANNELS

include AP_Param/AP_Param.h
singleton AP_Param rename param
Expand Down Expand Up @@ -393,6 +394,8 @@ singleton AP_MotorsMatrix rename MotorsMatrix
singleton AP_MotorsMatrix method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
singleton AP_MotorsMatrix method add_motor_raw void int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float'skip_check float'skip_check float'skip_check uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
singleton AP_MotorsMatrix method set_throttle_factor boolean int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float 0 FLT_MAX
singleton AP_MotorsMatrix method get_lost_motor uint8_t
singleton AP_MotorsMatrix method get_thrust_boost boolean

include AP_Frsky_Telem/AP_Frsky_SPort.h
singleton AP_Frsky_SPort rename frsky_sport
Expand Down Expand Up @@ -572,6 +575,7 @@ ap_object AP_EFI_Backend method handle_scripting boolean EFI_State
singleton AP_EFI depends (AP_EFI_SCRIPTING_ENABLED == 1)
singleton AP_EFI rename efi
singleton AP_EFI method get_backend AP_EFI_Backend uint8_t 0 UINT8_MAX
singleton AP_EFI method get_last_update_ms uint32_t

-- ----END EFI Library----

Expand Down
45 changes: 45 additions & 0 deletions libraries/AP_UAVCAN/AP_UAVCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#include <uavcan/equipment/actuator/ArrayCommand.hpp>
#include <uavcan/equipment/actuator/Command.hpp>
#include <uavcan/equipment/actuator/Status.hpp>
#include <uavcan/equipment/power/CircuitStatus.hpp>
#include <uavcan/equipment/device/Temperature.hpp>

#include <uavcan/equipment/esc/RawCommand.hpp>
#include <uavcan/equipment/esc/Status.hpp>
Expand Down Expand Up @@ -190,6 +192,14 @@ static uavcan::Subscriber<ardupilot::equipment::trafficmonitor::TrafficReport, T
UC_REGISTRY_BINDER(ActuatorStatusCb, uavcan::equipment::actuator::Status);
static uavcan::Subscriber<uavcan::equipment::actuator::Status, ActuatorStatusCb> *actuator_status_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS];

// handler power circuit status
UC_REGISTRY_BINDER(PowerCktStatusCb, uavcan::equipment::power::CircuitStatus);
static uavcan::Subscriber<uavcan::equipment::power::CircuitStatus, PowerCktStatusCb> *power_cktstatus_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS];

// handler device temperature and error flag status
UC_REGISTRY_BINDER(DeviceTemperatureCb, uavcan::equipment::device::Temperature);
static uavcan::Subscriber<uavcan::equipment::device::Temperature, DeviceTemperatureCb> *device_temperature_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS];

// handler ESC status
UC_REGISTRY_BINDER(ESCStatusCb, uavcan::equipment::esc::Status);
static uavcan::Subscriber<uavcan::equipment::esc::Status, ESCStatusCb> *esc_status_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS];
Expand Down Expand Up @@ -407,6 +417,16 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters)
actuator_status_listener[driver_index]->start(ActuatorStatusCb(this, &handle_actuator_status));
}

power_cktstatus_listener[driver_index] = new uavcan::Subscriber<uavcan::equipment::power::CircuitStatus, PowerCktStatusCb>(*_node);
if (power_cktstatus_listener[driver_index]) {
power_cktstatus_listener[driver_index]->start(PowerCktStatusCb(this, &handle_power_cktstatus));
}

device_temperature_listener[driver_index] = new uavcan::Subscriber<uavcan::equipment::device::Temperature, DeviceTemperatureCb>(*_node);
if (device_temperature_listener[driver_index]) {
device_temperature_listener[driver_index]->start(DeviceTemperatureCb(this, &handle_device_temperature));
}

esc_status_listener[driver_index] = new uavcan::Subscriber<uavcan::equipment::esc::Status, ESCStatusCb>(*_node);
if (esc_status_listener[driver_index]) {
esc_status_listener[driver_index]->start(ESCStatusCb(this, &handle_ESC_status));
Expand Down Expand Up @@ -1001,6 +1021,31 @@ void AP_UAVCAN::handle_actuator_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, co
cb.msg->power_rating_pct);
}

/*
handle actuator voltage and current message
*/
void AP_UAVCAN::handle_power_cktstatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const PowerCktStatusCb &cb)
{
// log as CSVI message
AP::logger().Write_PowerCktStatus(AP_HAL::native_micros64(),
cb.msg->circuit_id,
cb.msg->voltage,
cb.msg->current,
cb.msg->error_flags);
}

/*
handle actuator temperature message
*/
void AP_UAVCAN::handle_device_temperature(AP_UAVCAN* ap_uavcan, uint8_t node_id, const DeviceTemperatureCb &cb)
{
// log as CSTE message
AP::logger().Write_DeviceTemperature(AP_HAL::native_micros64(),
cb.msg->device_id,
cb.msg->temperature,
cb.msg->error_flags);
}

/*
handle ESC status message
*/
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_UAVCAN/AP_UAVCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@
class ButtonCb;
class TrafficReportCb;
class ActuatorStatusCb;
class PowerCktStatusCb;
class DeviceTemperatureCb;
class ESCStatusCb;
class DebugCb;
class ParamGetSetCb;
Expand Down Expand Up @@ -341,6 +343,8 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend {
static void handle_button(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ButtonCb &cb);
static void handle_traffic_report(AP_UAVCAN* ap_uavcan, uint8_t node_id, const TrafficReportCb &cb);
static void handle_actuator_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ActuatorStatusCb &cb);
static void handle_power_cktstatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const PowerCktStatusCb &cb);
static void handle_device_temperature(AP_UAVCAN* ap_uavcan, uint8_t node_id, const DeviceTemperatureCb &cb);
static void handle_ESC_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ESCStatusCb &cb);
static bool is_esc_data_index_valid(const uint8_t index);
static void handle_debug(AP_UAVCAN* ap_uavcan, uint8_t node_id, const DebugCb &cb);
Expand Down
Loading