Skip to content

Commit

Permalink
Merge branch 'master' into automate_apm_pdef_xml_creation
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas authored Feb 6, 2025
2 parents 2f036b5 + 034a760 commit f53bd9a
Show file tree
Hide file tree
Showing 28 changed files with 301 additions and 233 deletions.
4 changes: 3 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50, 24),
#endif
SCHED_TASK(auto_disarm_check, 10, 50, 27),
SCHED_TASK(auto_trim, 10, 75, 30),
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
SCHED_TASK_CLASS(RC_Channels_Copter, &copter.g2.rc_channels, auto_trim_run, 10, 75, 30),
#endif
#if AP_RANGEFINDER_ENABLED
SCHED_TASK(read_rangefinder, 20, 100, 33),
#endif
Expand Down
9 changes: 0 additions & 9 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -496,10 +496,6 @@ class Copter : public AP_Vehicle {
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
uint32_t arm_time_ms;

// Used to exit the roll and pitch auto trim function
uint8_t auto_trim_counter;
bool auto_trim_started = false;

// Camera
#if AP_CAMERA_ENABLED
AP_Camera camera{MASK_LOG_CAMERA};
Expand Down Expand Up @@ -997,11 +993,6 @@ class Copter : public AP_Vehicle {
// takeoff_check.cpp
void takeoff_check();

// RC_Channel.cpp
void save_trim();
void auto_trim();
void auto_trim_cancel();

// system.cpp
void init_ardupilot() override;
void startup_INS_ground();
Expand Down
90 changes: 53 additions & 37 deletions ArduCopter/RC_Channel_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ bool RC_Channel_Copter::do_aux_function(const AuxFuncTrigger &trigger)
if ((ch_flag == AuxSwitchPos::HIGH) &&
(copter.flightmode->allows_save_trim()) &&
(copter.channel_throttle->get_control_in() == 0)) {
copter.save_trim();
copter.g2.rc_channels.save_trim();
}
break;

Expand Down Expand Up @@ -631,6 +631,12 @@ bool RC_Channel_Copter::do_aux_function(const AuxFuncTrigger &trigger)
break;
#endif

#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
case AUX_FUNC::AHRS_AUTO_TRIM:
copter.g2.rc_channels.do_aux_function_ahrs_auto_trim(ch_flag);
break;
#endif // AP_COPTER_AHRS_AUTO_TRIM_ENABLED

case AUX_FUNC::SIMPLE_HEADING_RESET:
if (ch_flag == AuxSwitchPos::HIGH) {
copter.init_simple_bearing();
Expand Down Expand Up @@ -706,68 +712,78 @@ void RC_Channel_Copter::do_aux_function_change_force_flying(const AuxSwitchPos c
}
}

// note that this is a method on the RC_Channels object, not the
// individual channel
// save_trim - adds roll and pitch trims from the radio to ahrs
void Copter::save_trim()
void RC_Channels_Copter::save_trim()
{
// save roll and pitch trim
float roll_trim = ToRad((float)channel_roll->get_control_in()*0.01f);
float pitch_trim = ToRad((float)channel_pitch->get_control_in()*0.01f);
ahrs.add_trim(roll_trim, pitch_trim);
float roll_trim = ToRad((float)get_roll_channel().get_control_in()*0.01f);
float pitch_trim = ToRad((float)get_pitch_channel().get_control_in()*0.01f);
AP::ahrs().add_trim(roll_trim, pitch_trim);
LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM);
gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
}

#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
// start/stop ahrs auto trim
void RC_Channels_Copter::do_aux_function_ahrs_auto_trim(const RC_Channel::AuxSwitchPos ch_flag)
{
switch (ch_flag) {
case RC_Channel::AuxSwitchPos::HIGH:
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim running");
// flash the leds
AP_Notify::flags.save_trim = true;
auto_trim.running = true;
break;
case RC_Channel::AuxSwitchPos::MIDDLE:
break;
case RC_Channel::AuxSwitchPos::LOW:
if (auto_trim.running) {
AP_Notify::flags.save_trim = false;
save_trim();
}
break;
}
}

// auto_trim - slightly adjusts the ahrs.roll_trim and ahrs.pitch_trim towards the current stick positions
// meant to be called continuously while the pilot attempts to keep the copter level
void Copter::auto_trim_cancel()
void RC_Channels_Copter::auto_trim_cancel()
{
auto_trim_counter = 0;
auto_trim.running = false;
AP_Notify::flags.save_trim = false;
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim cancelled");
// restore original trims
}

void Copter::auto_trim()
void RC_Channels_Copter::auto_trim_run()
{
if (auto_trim_counter > 0) {
if (copter.flightmode != &copter.mode_stabilize ||
!copter.motors->armed()) {
auto_trim_cancel();
if (!auto_trim.running) {
return;
}

// flash the leds
AP_Notify::flags.save_trim = true;

if (!auto_trim_started) {
if (ap.land_complete) {
// haven't taken off yet
return;
}
auto_trim_started = true;
// only trim in certain modes:
if (copter.flightmode != &copter.mode_stabilize &&
copter.flightmode != &copter.mode_althold) {
auto_trim_cancel();
return;
}

if (ap.land_complete) {
// landed again.
// must be started and stopped mid-air:
if (copter.ap.land_complete_maybe) {
auto_trim_cancel();
return;
}

auto_trim_counter--;

// calculate roll trim adjustment
float roll_trim_adjustment = ToRad((float)channel_roll->get_control_in() / 4000.0f);
float roll_trim_adjustment = ToRad((float)get_roll_channel().get_control_in() / 4000.0f);

// calculate pitch trim adjustment
float pitch_trim_adjustment = ToRad((float)channel_pitch->get_control_in() / 4000.0f);

// add trim to ahrs object
// save to eeprom on last iteration
ahrs.add_trim(roll_trim_adjustment, pitch_trim_adjustment, (auto_trim_counter == 0));
float pitch_trim_adjustment = ToRad((float)get_pitch_channel().get_control_in() / 4000.0f);

// on last iteration restore leds and accel gains to normal
if (auto_trim_counter == 0) {
AP_Notify::flags.save_trim = false;
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim: Trims saved");
}
}
// add trim to ahrs object, but do not save to permanent storage:
AP::ahrs().add_trim(roll_trim_adjustment, pitch_trim_adjustment, false);
}

#endif // AP_COPTER_AHRS_AUTO_TRIM_ENABLED
12 changes: 12 additions & 0 deletions ArduCopter/RC_Channel_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,18 @@ class RC_Channels_Copter : public RC_Channels
// returns true if throttle arming checks should be run
bool arming_check_throttle() const override;

// support for trimming AHRS using RC stick inputs, enabled via an
// aux function
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
void do_aux_function_ahrs_auto_trim(const RC_Channel::AuxSwitchPos ch_flag);
struct {
bool running;
} auto_trim;
void auto_trim_run();
void auto_trim_cancel();
#endif // AP_COPTER_AHRS_AUTO_TRIM_ENABLED
void save_trim();

protected:

int8_t flight_mode_channel_number() const override;
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -578,6 +578,10 @@
# define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 0
#endif

#ifndef AP_COPTER_AHRS_AUTO_TRIM_ENABLED
# define AP_COPTER_AHRS_AUTO_TRIM_ENABLED 1
#endif

#ifndef CH_MODE_DEFAULT
# define CH_MODE_DEFAULT 5
#endif
Expand Down
12 changes: 1 addition & 11 deletions ArduCopter/motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

#define ARM_DELAY 20 // called at 10hz so 2 seconds
#define DISARM_DELAY 20 // called at 10hz so 2 seconds
#define AUTO_TRIM_DELAY 100 // called at 10hz so 10 seconds
#define LOST_VEHICLE_DELAY 10 // called at 10hz so 1 second

static uint32_t auto_disarm_begin;
Expand Down Expand Up @@ -39,7 +38,7 @@ void Copter::arm_motors_check()
if (yaw_in > 4000) {

// increase the arming counter to a maximum of 1 beyond the auto trim counter
if (arming_counter <= AUTO_TRIM_DELAY) {
if (arming_counter < ARM_DELAY) {
arming_counter++;
}

Expand All @@ -51,15 +50,6 @@ void Copter::arm_motors_check()
}
}

// arm the motors and configure for flight
if (arming_counter == AUTO_TRIM_DELAY && motors->armed() && flightmode->mode_number() == Mode::Number::STABILIZE) {
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim start");
auto_trim_counter = 250;
auto_trim_started = false;
// ensure auto-disarm doesn't trigger immediately
auto_disarm_begin = millis();
}

// full left and rudder disarming is enabled
} else if ((yaw_in < -4000) && (arming_rudder == AP_Arming::RudderArming::ARMDISARM)) {
if (!flightmode->has_manual_throttle() && !ap.land_complete) {
Expand Down
9 changes: 0 additions & 9 deletions Blimp/Blimp.h
Original file line number Diff line number Diff line change
Expand Up @@ -239,10 +239,6 @@ class Blimp : public AP_Vehicle
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
uint32_t arm_time_ms;

// Used to exit the roll and pitch auto trim function
uint8_t auto_trim_counter;
bool auto_trim_started = false;

// last valid RC input time
uint32_t last_radio_update_ms;

Expand Down Expand Up @@ -412,11 +408,6 @@ class Blimp : public AP_Vehicle
bool rangefinder_alt_ok();
bool rangefinder_up_ok();

// RC_Channel.cpp
void save_trim();
void auto_trim();
void auto_trim_cancel();

// system.cpp
void init_ardupilot() override;
void startup_INS_ground();
Expand Down
74 changes: 0 additions & 74 deletions Blimp/RC_Channel_Blimp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,14 +106,6 @@ bool RC_Channel_Blimp::do_aux_function(const AuxFuncTrigger &trigger)

switch (ch_option) {

case AUX_FUNC::SAVE_TRIM:
if ((ch_flag == AuxSwitchPos::HIGH) &&
(blimp.control_mode <= Mode::Number::MANUAL) &&
(blimp.channel_up->get_control_in() == 0)) {
blimp.save_trim();
}
break;

case AUX_FUNC::LOITER:
do_aux_function_change_mode(Mode::Number::LOITER, ch_flag);
break;
Expand All @@ -127,69 +119,3 @@ bool RC_Channel_Blimp::do_aux_function(const AuxFuncTrigger &trigger)
}
return true;
}

// save_trim - adds roll and pitch trims from the radio to ahrs
void Blimp::save_trim()
{
// save roll and pitch trim
float roll_trim = ToRad((float)channel_right->get_control_in()*0.01f);
float pitch_trim = ToRad((float)channel_front->get_control_in()*0.01f);
ahrs.add_trim(roll_trim, pitch_trim);
LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM);
gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
}

// auto_trim - slightly adjusts the ahrs.roll_trim and ahrs.pitch_trim towards the current stick positions
// meant to be called continuously while the pilot attempts to keep the blimp level
void Blimp::auto_trim_cancel()
{
auto_trim_counter = 0;
AP_Notify::flags.save_trim = false;
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim cancelled");
}

void Blimp::auto_trim()
{
if (auto_trim_counter > 0) {
if (blimp.flightmode != &blimp.mode_manual ||
!blimp.motors->armed()) {
auto_trim_cancel();
return;
}

// flash the leds
AP_Notify::flags.save_trim = true;

if (!auto_trim_started) {
if (ap.land_complete) {
// haven't taken off yet
return;
}
auto_trim_started = true;
}

if (ap.land_complete) {
// landed again.
auto_trim_cancel();
return;
}

auto_trim_counter--;

// calculate roll trim adjustment
float roll_trim_adjustment = ToRad((float)channel_right->get_control_in() / 4000.0f);

// calculate pitch trim adjustment
float pitch_trim_adjustment = ToRad((float)channel_front->get_control_in() / 4000.0f);

// add trim to ahrs object
// save to eeprom on last iteration
ahrs.add_trim(roll_trim_adjustment, pitch_trim_adjustment, (auto_trim_counter == 0));

// on last iteration restore leds and accel gains to normal
if (auto_trim_counter == 0) {
AP_Notify::flags.save_trim = false;
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim: Trims saved");
}
}
}
10 changes: 1 addition & 9 deletions Blimp/motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

#define ARM_DELAY 20 // called at 10hz so 2 seconds
#define DISARM_DELAY 20 // called at 10hz so 2 seconds
#define AUTO_TRIM_DELAY 100 // called at 10hz so 10 seconds
#define LOST_VEHICLE_DELAY 10 // called at 10hz so 1 second

// arm_motors_check - checks for pilot input to arm or disarm the blimp
Expand All @@ -29,7 +28,7 @@ void Blimp::arm_motors_check()
if (yaw_in > 900) {

// increase the arming counter to a maximum of 1 beyond the auto trim counter
if (arming_counter <= AUTO_TRIM_DELAY) {
if (arming_counter < ARM_DELAY) {
arming_counter++;
}

Expand All @@ -41,13 +40,6 @@ void Blimp::arm_motors_check()
}
}

// arm the motors and configure for flight
if (arming_counter == AUTO_TRIM_DELAY && motors->armed() && control_mode == Mode::Number::MANUAL) {
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim start");
auto_trim_counter = 250;
auto_trim_started = false;
}

// full left and rudder disarming is enabled
} else if ((yaw_in < -900) && (arming_rudder == AP_Arming::RudderArming::ARMDISARM)) {
if (!flightmode->has_manual_throttle() && !ap.land_complete) {
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 @@ -300,6 +300,7 @@ AP_HW_FlywooF405HD_AIOv2 1180
AP_HW_FlywooH743Pro 1181
AP_HW_CBU_StampH743_LC 1182
AP_HW_NarinH7 1183
AP_HW_BrahmaF4 1184

AP_HW_JFB200 1200

Expand Down
4 changes: 2 additions & 2 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ def configure_env(self, cfg, env):
'-Wno-gnu-variable-sized-type-not-at-end',
'-Werror=implicit-fallthrough',
'-cl-single-precision-constant',
'-Wno-vla-cxx-extension',
'-Wno-vla-extension',
]
else:
env.CFLAGS += [
Expand Down Expand Up @@ -420,7 +420,7 @@ def configure_env(self, cfg, env):

'-Wno-gnu-designator',
'-Wno-mismatched-tags',
'-Wno-vla-cxx-extension',
'-Wno-vla-extension',
'-Wno-gnu-variable-sized-type-not-at-end',
'-Werror=implicit-fallthrough',
'-cl-single-precision-constant',
Expand Down
Loading

0 comments on commit f53bd9a

Please sign in to comment.