Skip to content

Commit

Permalink
Tools: uploader.py: verify installed firmware
Browse files Browse the repository at this point in the history
  • Loading branch information
rafasaurus committed Feb 3, 2025
1 parent 4fb4556 commit c0682e2
Show file tree
Hide file tree
Showing 136 changed files with 2,223 additions and 348 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -807,7 +807,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che

// save compass offsets learned by the EKF if enabled
Compass &compass = AP::compass();
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
Expand Down
3 changes: 2 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,6 +451,8 @@ AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, c
}
if (mode_guided_custom[i] == nullptr) {
// Allocation failure
free((void*)full_name_copy);
free((void*)short_name_copy);
return nullptr;
}

Expand Down Expand Up @@ -962,7 +964,6 @@ Copter::Copter(void)
flight_modes(&g.flight_mode1),
pos_variance_filt(FS_EKF_FILT_DEFAULT),
vel_variance_filt(FS_EKF_FILT_DEFAULT),
hgt_variance_filt(FS_EKF_FILT_DEFAULT),
flightmode(&mode_stabilize),
simple_cos_yaw(1.0f),
super_simple_cos_yaw(1.0),
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,6 @@ class Copter : public AP_Vehicle {
// thus failsafes should be triggered on filtered values in order to avoid transient errors
LowPassFilterFloat pos_variance_filt;
LowPassFilterFloat vel_variance_filt;
LowPassFilterFloat hgt_variance_filt;
bool variances_valid;
uint32_t last_ekf_check_us;

Expand Down
1 change: 0 additions & 1 deletion ArduCopter/ekf_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,6 @@ bool Copter::ekf_over_threshold()
// always update filtered values as this serves the vibration check as well
position_var = pos_variance_filt.apply(position_var, dt);
vel_var = vel_variance_filt.apply(vel_var, dt);
height_var = hgt_variance_filt.apply(height_var, dt);

last_ekf_check_us = now_us;

Expand Down
3 changes: 2 additions & 1 deletion ArduCopter/mode_systemid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,8 @@ void ModeSystemId::exit()
// should be called at 100hz or more
void ModeSystemId::run()
{
float target_roll, target_pitch;
float target_roll = 0.0f;
float target_pitch = 0.0f;
float target_yaw_rate = 0.0f;
float pilot_throttle_scaled = 0.0f;
float target_climb_rate = 0.0f;
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,6 @@ void Copter::init_ardupilot()

pos_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);
vel_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);
hgt_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);

// flag that initialisation has completed
ap.initialised = true;
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/toy_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1079,9 +1079,9 @@ void ToyMode::arm_check_compass(void)
if (offsets.length() > copter.compass.get_offsets_max() ||
field < 200 || field > 800 ||
!copter.compass.configured(unused_compass_configured_error_message, ARRAY_SIZE(unused_compass_configured_error_message))) {
if (copter.compass.get_learn_type() != Compass::LEARN_INFLIGHT) {
if (copter.compass.get_learn_type() != Compass::LearnType::INFLIGHT) {
gcs().send_text(MAV_SEVERITY_INFO, "Tmode: enable compass learning");
copter.compass.set_learn_type(Compass::LEARN_INFLIGHT, false);
copter.compass.set_learn_type(Compass::LearnType::INFLIGHT, false);
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/AP_Arming_Sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks
auto &ahrs = AP::ahrs();

// save compass offsets learned by the EKF if enabled
if (ahrs.use_compass() && AP::compass().get_learn_type() == Compass::LEARN_EKF) {
if (ahrs.use_compass() && AP::compass().get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
Expand Down
2 changes: 1 addition & 1 deletion Blimp/AP_Arming_Blimp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_chec

// save compass offsets learned by the EKF if enabled
Compass &compass = AP::compass();
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
Expand Down
1 change: 1 addition & 0 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -390,6 +390,7 @@ AP_HW_TM-SYS-Airspeed 5244
# IDs 5250-5269 reserved for Team Black Sheep
AP_HW_TBS_LUCID_H7 5250
AP_HW_TBS_LUCID_PRO 5251
AP_HW_TBS_L431_PERIPH 5252

#IDs 5301-5399 reserved for Sierra Aerospace
AP_HW_Sierra-TrueNavPro-G4 5301
Expand Down
29 changes: 29 additions & 0 deletions Tools/AP_Bootloader/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -836,6 +836,35 @@ void can_start()
if (stm32_was_watchdog_reset()) {
node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::FAIL_REASON_WATCHDOG);
}

{
/*
support termination solder bridge or switch and optional LED
*/
#if defined(HAL_GPIO_PIN_GPIO_CAN1_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH)
const bool can1_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH);
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, can1_term);
# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_LED
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_LED, can1_term? HAL_LED_ON : !HAL_LED_ON);
# endif
#endif

#if defined(HAL_GPIO_PIN_GPIO_CAN2_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH)
const bool can2_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH);
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, can2_term);
# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_LED
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_LED, can2_term? HAL_LED_ON : !HAL_LED_ON);
# endif
#endif

#if defined(HAL_GPIO_PIN_GPIO_CAN3_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH)
const bool can3_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH);
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, can3_term);
# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_LED
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_LED, can3_term? HAL_LED_ON : !HAL_LED_ON);
# endif
#endif
}
}


Expand Down
8 changes: 4 additions & 4 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,11 +160,11 @@ void AP_Periph_FW::init()
}
#endif // AP_PERIPH_GPS_ENABLED

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
compass.init();
#endif

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
baro.init();
#endif

Expand Down Expand Up @@ -425,11 +425,11 @@ void AP_Periph_FW::update()
#if AP_PERIPH_GPS_ENABLED
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
const Vector3f &field = compass.get_field();
hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
Expand Down
8 changes: 4 additions & 4 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -227,11 +227,11 @@ class AP_Periph_FW {
AP_NMEA_Output nmea;
#endif

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
Compass compass;
#endif

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
AP_Baro baro;
#endif

Expand Down Expand Up @@ -449,15 +449,15 @@ class AP_Periph_FW {
#ifdef HAL_PERIPH_ENABLE_EFI
uint32_t last_efi_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
uint32_t last_mag_update_ms;
#endif
#if AP_PERIPH_GPS_ENABLED
uint32_t last_gps_update_ms;
uint32_t last_gps_yaw_ms;
#endif
uint32_t last_relposheading_ms;
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
uint32_t last_baro_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,13 +263,13 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GSCALAR(battery_hide_mask, "BATT_HIDE_MASK", HAL_PERIPH_BATT_HIDE_MASK_DEFAULT),
#endif

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
GOBJECT(compass, "COMPASS_", Compass),
#endif

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
// Baro driver
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ class Parameters {
#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
AP_Int8 led_brightness;
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
AP_Int8 baro_enable;
#endif
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/baro.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED

/*
barometer support
Expand Down Expand Up @@ -60,4 +60,4 @@ void AP_Periph_FW::can_baro_update(void)
}
}

#endif // HAL_PERIPH_ENABLE_BARO
#endif // AP_PERIPH_BARO_ENABLED
46 changes: 38 additions & 8 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,10 +352,10 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
#if AP_PERIPH_BATTERY_ENABLED
AP_Param::setup_object_defaults(&battery, battery_lib.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
AP_Param::setup_object_defaults(&compass, compass.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
AP_Param::setup_object_defaults(&baro, baro.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down Expand Up @@ -1611,20 +1611,50 @@ void AP_Periph_FW::can_start()
}
}
if (!has_uavcan_at_1MHz) {
g.can_protocol[0].set_and_save(uint8_t(AP_CAN::Protocol::DroneCAN));
g.can_protocol[0].set_and_save(AP_CAN::Protocol::DroneCAN);
g.can_baudrate[0].set_and_save(1000000);
}
#endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz

{
/*
support termination parameters, and also a hardware switch
to force termination and an LED to indicate if termination
is active
*/
#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, g.can_terminate[0]);
bool can1_term = g.can_terminate[0];
# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH
can1_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH);
# endif
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, can1_term);
# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_LED
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_LED, can1_term? HAL_LED_ON : !HAL_LED_ON);
# endif
#endif

#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, g.can_terminate[1]);
bool can2_term = g.can_terminate[1];
# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH
can2_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH);
# endif
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, can2_term);
# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_LED
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_LED, can2_term? HAL_LED_ON : !HAL_LED_ON);
# endif
#endif

#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, g.can_terminate[2]);
bool can3_term = g.can_terminate[2];
# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH
can3_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH);
# endif
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, can3_term);
# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_LED
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_LED, can3_term? HAL_LED_ON : !HAL_LED_ON);
# endif
#endif
}

for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
Expand Down Expand Up @@ -1882,7 +1912,7 @@ void AP_Periph_FW::can_update()
if (!hal.run_in_maintenance_mode())
#endif
{
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
can_mag_update();
#endif
#if AP_PERIPH_GPS_ENABLED
Expand All @@ -1894,7 +1924,7 @@ void AP_Periph_FW::can_update()
#if AP_PERIPH_BATTERY_ENABLED
can_battery_update();
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
can_baro_update();
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/compass.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED

/*
magnetometer support
Expand Down Expand Up @@ -97,4 +97,4 @@ void AP_Periph_FW::can_mag_update(void)
#endif // AP_PERIPH_MAG_HIRES
}

#endif // HAL_PERIPH_ENABLE_MAG
#endif // AP_PERIPH_MAG_ENABLED
12 changes: 6 additions & 6 deletions Tools/AP_Periph/msp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,10 @@ void AP_Periph_FW::msp_sensor_update(void)
#if AP_PERIPH_GPS_ENABLED
send_msp_GPS();
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
send_msp_baro();
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
send_msp_compass();
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down Expand Up @@ -125,7 +125,7 @@ void AP_Periph_FW::send_msp_GPS(void)
#endif // AP_PERIPH_GPS_ENABLED


#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
/*
send MSP baro packet
*/
Expand All @@ -149,9 +149,9 @@ void AP_Periph_FW::send_msp_baro(void)

send_msp_packet(MSP2_SENSOR_BAROMETER, &p, sizeof(p));
}
#endif // HAL_PERIPH_ENABLE_BARO
#endif // AP_PERIPH_BARO_ENABLED

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
/*
send MSP compass packet
*/
Expand All @@ -176,7 +176,7 @@ void AP_Periph_FW::send_msp_compass(void)

send_msp_packet(MSP2_SENSOR_COMPASS, &p, sizeof(p));
}
#endif // HAL_PERIPH_ENABLE_MAG
#endif // AP_PERIPH_MAG_ENABLED

#ifdef HAL_PERIPH_ENABLE_AIRSPEED
/*
Expand Down
4 changes: 2 additions & 2 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -954,8 +954,8 @@ def configure_env(self, cfg, env):

AP_PERIPH_GPS_ENABLED = 1,
HAL_PERIPH_ENABLE_AIRSPEED = 1,
HAL_PERIPH_ENABLE_MAG = 1,
HAL_PERIPH_ENABLE_BARO = 1,
AP_PERIPH_MAG_ENABLED = 1,
AP_PERIPH_BARO_ENABLED = 1,
HAL_PERIPH_ENABLE_IMU = 1,
HAL_PERIPH_ENABLE_RANGEFINDER = 1,
AP_PERIPH_BATTERY_ENABLED = 1,
Expand Down
Loading

0 comments on commit c0682e2

Please sign in to comment.