Skip to content

Commit

Permalink
AP_Common: add get_alt - 100 times better than get_alt_cm
Browse files Browse the repository at this point in the history
Copter: emit system time during compassmot on SITL

the autotest framework heavily relies on system_time being emitted -
because we're not running the main loop during compassmot it gets stuck
if we don't do this

Copter: send RC_CHANNELS in SITL in compassmot loop

When setting an RC value in autotest, we require the change to appear in this message

autotest: add test for Copter compassmot

Added mag and dataflash logging support to AnyLeaf H7

Added mag and dataflash logging support to AnyLeaf H7

autotest: add test for Copter compassmot

Added mag and dataflash logging support to AnyLeaf H7

Added mag and dataflash logging support to AnyLeaf H7
  • Loading branch information
peterbarker authored and David O'Connor committed May 22, 2024
1 parent 423198c commit 9dff355
Show file tree
Hide file tree
Showing 5 changed files with 88 additions and 0 deletions.
6 changes: 6 additions & 0 deletions ArduCopter/compassmot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,12 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
#if HAL_WITH_ESC_TELEM
// send ESC telemetry to monitor ESC and motor temperatures
AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan());
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// a lot of autotest timeouts are based on receiving system time
gcs_chan.send_system_time();
// autotesting of compassmot wants to see RC channels message
gcs_chan.send_rc_channels();
#endif
}
}
Expand Down
63 changes: 63 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -2055,6 +2055,67 @@ def ModeCircle(self, holdtime=36):

self.do_RTL()

def CompassMot(self):
'''test code that adjust mag field for motor interference'''
self.run_cmd(
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
0, # p1
0, # p2
0, # p3
0, # p4
0, # p5
1, # p6
0 # p7
)
self.context_collect("STATUSTEXT")
self.wait_statustext("Starting calibration", check_context=True)
self.wait_statustext("Current", check_context=True)
rc3_min = self.get_parameter('RC3_MIN')
rc3_max = self.get_parameter('RC3_MAX')
rc3_dz = self.get_parameter('RC3_DZ')

def set_rc3_for_throttle_pct(thr_pct):
value = int((rc3_min+rc3_dz) + (thr_pct/100.0) * (rc3_max-(rc3_min+rc3_dz)))
self.progress("Setting rc3 to %u" % value)
self.set_rc(3, value)

throttle_in_pct = 0
set_rc3_for_throttle_pct(throttle_in_pct)
self.assert_received_message_field_values("COMPASSMOT_STATUS", {
"interference": 0,
"throttle": throttle_in_pct
}, verbose=True, very_verbose=True)
tstart = self.get_sim_time()
delta = 5
while True:
if self.get_sim_time_cached() - tstart > 60:
raise NotAchievedException("did not run through entire range")
throttle_in_pct += delta
self.progress("Using throttle %f%%" % throttle_in_pct)
set_rc3_for_throttle_pct(throttle_in_pct)
self.wait_message_field_values("COMPASSMOT_STATUS", {
"throttle": throttle_in_pct * 10.0,
}, verbose=True, very_verbose=True, epsilon=1)
if throttle_in_pct == 0:
# finished counting down
break
if throttle_in_pct == 100:
# start counting down
delta = -delta

m = self.wait_message_field_values("COMPASSMOT_STATUS", {
"throttle": 0,
}, verbose=True)
for axis in "X", "Y", "Z":
fieldname = "Compensation" + axis
if getattr(m, fieldname) <= 0:
raise NotAchievedException("Expected non-zero %s" % fieldname)

# it's kind of crap - but any command-ack will stop the
# calibration
self.mav.mav.command_ack_send(0, 1)
self.wait_statustext("Calibration successful")

def MagFail(self):
'''test failover of compass in EKF'''
# we want both EK2 and EK3
Expand Down Expand Up @@ -10944,6 +11005,7 @@ def tests2b(self): # this block currently around 9.5mins here
self.CameraLogMessages,
self.LoiterToGuidedHomeVSOrigin,
self.GuidedModeThrust,
self.CompassMot,
])
return ret

Expand Down Expand Up @@ -10975,6 +11037,7 @@ def disabled_tests(self):
"FlyMissionTwice": "See https://github.com/ArduPilot/ardupilot/pull/18561",
"GPSForYawCompassLearn": "Vehicle currently crashed in spectacular fashion",
"GuidedModeThrust": "land detector raises internal error as we're not saying we're about to take off but just did",
"CompassMot": "Cuases an arithmetic exception in the EKF",
}


Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_Common/Location.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,15 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
}
return false; // LCOV_EXCL_LINE - not reachable
}
bool Location::get_alt_m(AltFrame desired_frame, float &ret_alt) const
{
int32_t ret_alt_cm;
if (!get_alt_cm(desired_frame, ret_alt_cm)) {
return false;
}
ret_alt = ret_alt_cm * 0.01;
return true;
}

#if AP_AHRS_ENABLED
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Common/Location.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ class Location
// - above-home and home is not set
// - above-origin and origin is not set
bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const WARN_IF_UNUSED;
// same as get_alt_cm but in metres:
bool get_alt_m(AltFrame desired_frame, float &ret_alt) const WARN_IF_UNUSED;

// get altitude frame
AltFrame get_alt_frame() const;
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/AnyleafH7/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,14 @@ define HAL_DEFAULT_INS_FAST_SAMPLE 1
# DPS310 integrated on I2C2 bus, multiple possible choices for external barometer
BARO DPS310 I2C:0:0x77

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

# setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 5 # MSP Displayport
define HAL_LOGGING_DATAFLASH_ENABLED 1

0 comments on commit 9dff355

Please sign in to comment.