Skip to content

Commit

Permalink
working
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Apr 13, 2024
1 parent be6bbc3 commit 42211de
Show file tree
Hide file tree
Showing 9 changed files with 28 additions and 28 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1040,9 +1040,9 @@ class Plane : public AP_Vehicle {

void one_second_loop(void);
void three_hz_loop(void);
#if AP_AIRSPEED_AUTOCAL_ENABLE

void airspeed_ratio_update(void);
#endif

void compass_save(void);
void update_logging10(void);
void update_logging25(void);
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,9 +186,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
case AUX_FUNC::AIRMODE:
case AUX_FUNC::WEATHER_VANE_ENABLE:
#endif
#if AP_AIRSPEED_AUTOCAL_ENABLE

case AUX_FUNC::ARSPD_CALIBRATE:
#endif

case AUX_FUNC::TER_DISABLE:
case AUX_FUNC::CROW_SELECT:
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
Expand Down Expand Up @@ -343,7 +343,7 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
#endif

case AUX_FUNC::ARSPD_CALIBRATE:
#if AP_AIRSPEED_AUTOCAL_ENABLE

switch (ch_flag) {
case AuxSwitchPos::HIGH:
plane.airspeed.set_calibration_enabled(true);
Expand All @@ -354,7 +354,7 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
plane.airspeed.set_calibration_enabled(false);
break;
}
#endif

break;

case AUX_FUNC::LANDING_FLARE:
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL/Util.h
Original file line number Diff line number Diff line change
Expand Up @@ -212,10 +212,10 @@ class AP_HAL::Util {
// log info on stack usage
virtual void log_stack_info(void) {}

#if AP_CRASHDUMP_ENABLED

virtual size_t last_crash_dump_size() const { return 0; }
virtual void* last_crash_dump_ptr() const { return nullptr; }
#endif


#if HAL_ENABLE_DFU_BOOT
virtual void boot_to_dfu(void) {}
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/Scheduler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -468,7 +468,7 @@ void Scheduler::_monitor_thread(void *arg)
try_force_mutex();
}

#if AP_CRASHDUMP_ENABLED

if (loop_delay >= 1800 && using_watchdog) {
// we are about to watchdog, better to trigger a hardfault
// now and get a crash dump file
Expand All @@ -477,7 +477,7 @@ void Scheduler::_monitor_thread(void *arg)
fptr gptr = (fptr) (void *)ptr;
gptr();
}
#endif


#if HAL_LOGGING_ENABLED
if (log_wd_counter++ == 10 && hal.util->was_watchdog_reset()) {
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/Util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -832,7 +832,7 @@ void Util::log_stack_info(void)
#endif
}

#if AP_CRASHDUMP_ENABLED

size_t Util::last_crash_dump_size() const
{
// get dump size
Expand All @@ -856,7 +856,7 @@ void* Util::last_crash_dump_ptr() const
}
return (void*)stm32_crash_dump_addr();
}
#endif // AP_CRASHDUMP_ENABLED


#if HAL_ENABLE_DFU_BOOT && !defined(HAL_BOOTLOADER_BUILD)
void Util::boot_to_dfu()
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/Util.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,11 +159,11 @@ class ChibiOS::Util : public AP_HAL::Util {
// log info on stack usage
void log_stack_info(void) override;

#if AP_CRASHDUMP_ENABLED

// get last crash dump
size_t last_crash_dump_size() const override;
void* last_crash_dump_ptr() const override;
#endif


#if HAL_ENABLE_DFU_BOOT
void boot_to_dfu() override;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
#include "hwdef/common/watchdog.h"
#include "hwdef/common/stm32_util.h"
#include <AP_Vehicle/AP_Vehicle_Type.h>
#if AP_CRASHDUMP_ENABLED

#include <CrashCatcher.h>
#endif

#include <ch.h>
#include "hal.h"
#include <hrt.h>
Expand Down
16 changes: 8 additions & 8 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -654,9 +654,9 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
case AUX_FUNC::SCRIPTING_6:
case AUX_FUNC::SCRIPTING_7:
case AUX_FUNC::SCRIPTING_8:
#if AP_VIDEOTX_ENABLED

case AUX_FUNC::VTX_POWER:
#endif

case AUX_FUNC::OPTFLOW_CAL:
case AUX_FUNC::TURBINE_START:
case AUX_FUNC::MOUNT1_ROLL:
Expand Down Expand Up @@ -722,7 +722,7 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
}
}

#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED


const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
{ AUX_FUNC::SAVE_WP,"SaveWaypoint"},
Expand Down Expand Up @@ -804,7 +804,7 @@ const char *RC_Channel::string_for_aux_pos(AuxSwitchPos pos) const
return "";
}

#endif // AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED


/*
read an aux channel. Return true if a switch has changed
Expand All @@ -816,15 +816,15 @@ bool RC_Channel::read_aux()
// may wish to add special cases for other "AUXSW" things
// here e.g. RCMAP_ROLL etc once they become options
return false;
#if AP_VIDEOTX_ENABLED

} else if (_option == AUX_FUNC::VTX_POWER) {
int8_t position;
if (read_6pos_switch(position)) {
AP::vtx().change_power(position);
return true;
}
return false;
#endif // AP_VIDEOTX_ENABLED

}

AuxSwitchPos new_position;
Expand All @@ -844,13 +844,13 @@ bool RC_Channel::read_aux()
return false;
}

#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED

// announce the change to the GCS:
const char *aux_string = string_for_aux_function(_option);
if (aux_string != nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RC%i: %s %s", ch_in+1, aux_string, string_for_aux_pos(new_position));
}
#endif


// debounced; undertake the action:
run_aux_function(_option, new_position, AuxFuncTriggerSource::RC);
Expand Down
8 changes: 4 additions & 4 deletions libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -309,10 +309,10 @@ class RC_Channel {
// wrapper function around do_aux_function which allows us to log
bool run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source);

#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED

const char *string_for_aux_function(AUX_FUNC function) const;
const char *string_for_aux_pos(AuxSwitchPos pos) const;
#endif

// pwm value under which we consider that Radio value is invalid
static const uint16_t RC_MIN_LIMIT_PWM = 800;
// pwm value above which we consider that Radio value is invalid
Expand Down Expand Up @@ -422,15 +422,15 @@ class RC_Channel {
// switch high!
bool init_position_on_first_radio_read(AUX_FUNC func) const;

#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED

// Structure to lookup switch change announcements
struct LookupTable{
AUX_FUNC option;
const char *announcement;
};

static const LookupTable lookuptable[];
#endif

};


Expand Down

0 comments on commit 42211de

Please sign in to comment.