Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into raw_IMU_hz
Browse files Browse the repository at this point in the history
  • Loading branch information
Astik-2002 authored Feb 17, 2024
2 parents b1150cd + 9986fb9 commit 7cab4be
Show file tree
Hide file tree
Showing 314 changed files with 55,626 additions and 57,275 deletions.
1 change: 1 addition & 0 deletions .github/workflows/test_sitl_periph.yml
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,7 @@ jobs:
- name: run dronecan dsdlc generator test
run: |
PATH="/github/home/.local/bin:$PATH"
python -m pip install --upgrade dronecan
python modules/DroneCAN/dronecan_dsdlc/dronecan_dsdlc.py -O dsdlc_generated modules/DroneCAN/DSDL/uavcan modules/DroneCAN/DSDL/dronecan modules/DroneCAN/DSDL/com --run-test
- name: build sitl_periph_universal
Expand Down
10 changes: 5 additions & 5 deletions AntennaTracker/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,15 +87,15 @@ const struct LogStructure Tracker::log_structure[] = {
"VPOS", "QLLefff", "TimeUS,Lat,Lng,Alt,VelX,VelY,VelZ", "sddmnnn", "FGGB000", true }
};

void Tracker::Log_Write_Vehicle_Startup_Messages()
uint8_t Tracker::get_num_log_structures() const
{
logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED);
gps.Write_AP_Logger_Log_Startup_messages();
return ARRAY_SIZE(log_structure);
}

void Tracker::log_init(void)
void Tracker::Log_Write_Vehicle_Startup_Messages()
{
logger.Init(log_structure, ARRAY_SIZE(log_structure));
logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED);
gps.Write_AP_Logger_Log_Startup_messages();
}

#endif // HAL_LOGGING_ENABLED
29 changes: 5 additions & 24 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -566,12 +566,6 @@ const AP_Param::Info Tracker::var_info[] = {
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
PARAM_VEHICLE_INFO,

#if HAL_LOGGING_ENABLED
// @Group: LOG
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
GOBJECT(logger, "LOG", AP_Logger),
#endif

#if HAL_NAVEKF2_AVAILABLE
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
Expand All @@ -590,23 +584,7 @@ const AP_Param::Info Tracker::var_info[] = {

void Tracker::load_parameters(void)
{
if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {

// erase all parameters
hal.console->printf("Firmware change: erasing EEPROM...\n");
StorageManager::erase();
AP_Param::erase_all();

// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
hal.console->printf("done.\n");
}
g.format_version.set_default(Parameters::k_format_version);

uint32_t before = AP_HAL::micros();
// Load all auto-loaded EEPROM variables
AP_Param::load_all();
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);

#if AP_STATS_ENABLED
// PARAMETER_CONVERSION - Added: Jan-2024
Expand All @@ -618,7 +596,10 @@ void Tracker::load_parameters(void)
AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, 0, true);
#endif

hal.console->printf("load_all took %luus\n", (unsigned long)(AP_HAL::micros() - before));
// PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-4.6
#if HAL_LOGGING_ENABLED
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
#endif

#if HAL_HAVE_SAFETY_SWITCH
// configure safety switch to allow stopping the motors while armed
Expand Down
7 changes: 0 additions & 7 deletions AntennaTracker/Tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,13 +164,6 @@ void Tracker::stats_update(void)

const AP_HAL::HAL& hal = AP_HAL::get_HAL();

Tracker::Tracker(void)
#if HAL_LOGGING_ENABLED
: logger(g.log_bitmask)
#endif
{
}

Tracker tracker;
AP_Vehicle& vehicle = tracker;

Expand Down
16 changes: 9 additions & 7 deletions AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,6 @@ class Tracker : public AP_Vehicle {
friend class ModeGuided;
friend class Mode;

Tracker(void);

void arm_servos();
void disarm_servos();

Expand All @@ -74,10 +72,6 @@ class Tracker : public AP_Vehicle {

uint32_t start_time_ms = 0;

#if HAL_LOGGING_ENABLED
AP_Logger logger;
#endif

/**
antenna control channels
*/
Expand Down Expand Up @@ -160,12 +154,20 @@ class Tracker : public AP_Vehicle {
// GCS_Mavlink.cpp
void send_nav_controller_output(mavlink_channel_t chan);

#if HAL_LOGGING_ENABLED
// methods for AP_Vehicle:
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
const struct LogStructure *get_log_structures() const override {
return log_structure;
}
uint8_t get_num_log_structures() const override;

// Log.cpp
void Log_Write_Attitude();
void Log_Write_Vehicle_Baro(float pressure, float altitude);
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);
void Log_Write_Vehicle_Startup_Messages();
void log_init(void);
#endif

// Parameters.cpp
void load_parameters(void) override;
Expand Down
4 changes: 0 additions & 4 deletions AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,6 @@ void Tracker::init_ardupilot()
// try to initialise stream rates in the main loop.
gcs().update_send();

#if HAL_LOGGING_ENABLED
log_init();
#endif

// initialise compass
AP::compass().set_log_bit(MASK_LOG_COMPASS);
AP::compass().init();
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,12 +233,12 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)

// Inverted flight feature disabled for Heli Single and Dual frames
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
rc().find_channel_for_option(RC_Channel::aux_func_t::INVERTED) != nullptr) {
rc().find_channel_for_option(RC_Channel::AUX_FUNC::INVERTED) != nullptr) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Inverted flight option not supported");
return false;
}
// Ensure an Aux Channel is configured for motor interlock
if (rc().find_channel_for_option(RC_Channel::aux_func_t::MOTOR_INTERLOCK) == nullptr) {
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) == nullptr) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Motor Interlock not configured");
return false;
}
Expand Down
3 changes: 0 additions & 3 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -820,9 +820,6 @@ bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const
*/
Copter::Copter(void)
:
#if HAL_LOGGING_ENABLED
logger(g.log_bitmask),
#endif
flight_modes(&g.flight_mode1),
simple_cos_yaw(1.0f),
super_simple_cos_yaw(1.0),
Expand Down
12 changes: 7 additions & 5 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -251,10 +251,6 @@ class Copter : public AP_Vehicle {
RC_Channel *channel_throttle;
RC_Channel *channel_yaw;

#if HAL_LOGGING_ENABLED
AP_Logger logger;
#endif

// flight modes convenience array
AP_Int8 *flight_modes;
const uint8_t num_flight_modes = 6;
Expand Down Expand Up @@ -846,6 +842,13 @@ class Copter : public AP_Vehicle {
void standby_update();

#if HAL_LOGGING_ENABLED
// methods for AP_Vehicle:
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
const struct LogStructure *get_log_structures() const override {
return log_structure;
}
uint8_t get_num_log_structures() const override;

// Log.cpp
void Log_Write_Control_Tuning();
void Log_Write_Attitude();
Expand All @@ -866,7 +869,6 @@ class Copter : public AP_Vehicle {
void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out);
void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z);
void Log_Write_Vehicle_Startup_Messages();
void log_init(void);
#endif // HAL_LOGGING_ENABLED

// mode.cpp
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -560,6 +560,11 @@ const struct LogStructure Copter::log_structure[] = {
"GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true },
};

uint8_t Copter::get_num_log_structures() const
{
return ARRAY_SIZE(log_structure);
}

void Copter::Log_Write_Vehicle_Startup_Messages()
{
// only 200(?) bytes are guaranteed by AP_Logger
Expand All @@ -571,9 +576,4 @@ void Copter::Log_Write_Vehicle_Startup_Messages()
gps.Write_AP_Logger_Log_Startup_messages();
}

void Copter::log_init(void)
{
logger.Init(log_structure, ARRAY_SIZE(log_structure));
}

#endif // HAL_LOGGING_ENABLED
32 changes: 6 additions & 26 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -554,12 +554,6 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(camera_mount, "MNT", AP_Mount),
#endif

#if HAL_LOGGING_ENABLED
// @Group: LOG
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
GOBJECT(logger, "LOG", AP_Logger),
#endif

// @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT(battery, "BATT", AP_BattMonitor),
Expand Down Expand Up @@ -1238,6 +1232,7 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
// @DisplayName: EKF Failsafe filter cutoff
// @Description: EKF Failsafe filter cutoff frequency. EKF variances are filtered using this value to avoid spurious failsafes from transient high variances. A higher value means the failsafe is more likely to trigger.
// @Range: 0 10
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("FS_EKF_FILT", 8, ParametersG2, fs_ekf_filt_hz, FS_EKF_FILT_DEFAULT),

Expand Down Expand Up @@ -1344,25 +1339,8 @@ const AP_Param::ConversionInfo conversion_table[] = {

void Copter::load_parameters(void)
{
hal.util->set_soft_armed(false);

if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {

// erase all parameters
DEV_PRINTF("Firmware change: erasing EEPROM...\n");
StorageManager::erase();
AP_Param::erase_all();
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);

// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
DEV_PRINTF("done.\n");
}
g.format_version.set_default(Parameters::k_format_version);

uint32_t before = micros();
// Load all auto-loaded EEPROM variables
AP_Param::load_all();
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));

#if AP_LANDINGGEAR_ENABLED
Expand Down Expand Up @@ -1410,11 +1388,13 @@ void Copter::load_parameters(void)
}
#endif

hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
#if HAL_LOGGING_ENABLED
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
#endif

// setup AP_Param frame type flags
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);

}

// handle conversion of PID gains
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ RC_Channel * RC_Channels_Copter::get_arming_channel(void) const
}

// init_aux_switch_function - initialize aux functions
void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
{
// init channel options
switch(ch_option) {
Expand Down Expand Up @@ -156,7 +156,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
}

// do_aux_function - implement the function invoked by auxiliary switches
bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
{
switch(ch_option) {
case AUX_FUNC::FLIP:
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ class RC_Channel_Copter : public RC_Channel

protected:

void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;

private:

Expand Down
28 changes: 28 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,32 @@
ArduPilot Copter Release Notes:
-------------------------------

Copter 4.5.0-beta2 14-February-2024

Changes from 4.5.0-beta1:

1) New Autopilots supported
- YJUAV_A6Ultra
- AnyLeaf H7

2) System level changes
- fixed float rounding issue in HAL_Linux millis and micros functions
- fixed loading of defaults.parm parameters for dynamic parameter subtrees
- fixed discrimination between GHST and CRSF protocols
- fixed bug in DroneCAN packet parsing for corrupt packets that could cause a crash
- fixed handling of network sockets in scripting when used after close
- fixed bit timing of CANFD buses

3) Copter specific changes
- added filter to EKF variances for EKF failsafe

4) Camera and gimbal enhancements
- wait for non-zero camera version in SIYI driver

5) Miscellaneous
- do relay parameter conversion for parachute parameters if ever has been used
- broaden acceptance criteria for GPS yaw measurement for moving baseline yaw

------------------------------------------------------------------
Copter 4.5.0-beta1 30-Jan-2025
Changes from 4.4.4
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/ekf_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ bool Copter::ekf_over_threshold()
}

uint32_t now_us = AP_HAL::micros();
float dt = (now_us - last_ekf_check_us) / 1000000.0f;
float dt = (now_us - last_ekf_check_us) * 1e-6f;

// always update filtered values as this serves the vibration check as well
position_var = pos_variance_filt.apply(position_var, dt);
Expand Down
4 changes: 0 additions & 4 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,6 @@ void Copter::init_ardupilot()
osd.init();
#endif

#if HAL_LOGGING_ENABLED
log_init();
#endif

// update motor interlock state
update_using_interlock();

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/tuning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ void Copter::tuning()
}

// exit immediately if a function is assigned to channel 6
if ((RC_Channel::aux_func_t)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) {
if ((RC_Channel::AUX_FUNC)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) {
return;
}

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -420,6 +420,7 @@ void Plane::stabilize()
}
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct);
#endif
} else {
plane.control_mode->run();
Expand Down
Loading

0 comments on commit 7cab4be

Please sign in to comment.