Skip to content

Commit

Permalink
Merge pull request #3015 from paparazzi/fix-chibios
Browse files Browse the repository at this point in the history
[chibios] Small fixes
  • Loading branch information
gautierhattenberger committed Mar 28, 2023
2 parents eba266a + f0a8ed3 commit b855de5
Show file tree
Hide file tree
Showing 6 changed files with 117 additions and 117 deletions.
2 changes: 1 addition & 1 deletion conf/Makefile.chibios
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ ifeq ($(USE_OPT),)
ifeq (,$(findstring $(RTOS_DEBUG),0 FALSE))
CH_OPT ?= 0 -g -ggdb3 -fno-inline
else
CH_OPT ?= 2 -ggdb
CH_OPT ?= 2
endif
USE_OPT = -O$(CH_OPT) \
-falign-functions=16 -fomit-frame-pointer \
Expand Down
6 changes: 3 additions & 3 deletions sw/airborne/mcu_periph/usb_serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@
#endif

#ifdef USB_MAX_ENDPOINTS
#if USB_MAX_ENDPOINTS < 4
#define USBD_NUMBER 1
#else
#if USB_MAX_ENDPOINTS >= 4 && USE_USB_SERIAL_DEBUG
#define USBD_NUMBER 2
#else
#define USBD_NUMBER 1
#endif
#else
#define USBD_NUMBER 1
Expand Down
18 changes: 10 additions & 8 deletions sw/airborne/modules/loggers/sdlog_chibios.c
Original file line number Diff line number Diff line change
Expand Up @@ -196,10 +196,6 @@ void sdlog_chibios_init(void)
void sdlog_chibios_finish(const bool flush)
{
if (pprzLogFile != -1) {
// disable all required periph to save energy and maximize chance to flush files
// to mass storage and avoid infamous dirty bit on filesystem
mcu_energy_save();

// if a FF_FS_REENTRANT is true, we can umount fs without closing
// file, fatfs lock will assure that umount is done after a write,
// and umount will close all open files cleanly. Thats the fatest
Expand All @@ -214,9 +210,9 @@ void sdlog_chibios_finish(const bool flush)
#endif

sdLogFinish();
pprzLogFile = 0;
pprzLogFile = -1;
#if FLIGHTRECORDER_SDLOG
flightRecorderLogFile = 0;
flightRecorderLogFile = -1;
#endif
}
chibios_sdlog_status = SDLOG_STOPPED;
Expand Down Expand Up @@ -321,15 +317,21 @@ static void thd_bat_survey(void *arg)
register_adc_watchdog(&SDLOG_BAT_ADC, SDLOG_BAT_CHAN, V_ALERT, &powerOutageIsr);

chEvtWaitOne(EVENT_MASK(1));
// Only try to energy save is it is really a problem and not powered through USB
if (palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) {
// disable all required periph to save energy and maximize chance to flush files
// to mass storage and avoid infamous dirty bit on filesystem
mcu_energy_save();
}

// in case of powerloss, we should go fast and avoid to flush ram buffer
sdlog_chibios_finish(false);
chThdExit(0);

// Only put to deep sleep in case there is no power on the USB
if (palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) {
mcu_reboot(MCU_REBOOT_POWEROFF);
}
chThdSleep(TIME_INFINITE);
chThdExit(0);
while (true); // never goes here, only to avoid compiler warning: 'noreturn' function does return
}

Expand Down
1 change: 1 addition & 0 deletions sw/airborne/modules/loggers/sdlog_chibios/sdLog.c
Original file line number Diff line number Diff line change
Expand Up @@ -293,6 +293,7 @@ SdioError sdLogOpenLog(FileDes *fd, const char *directoryName, const char *prefi
sde = getFileName(prefix, directoryName, fileName, nameLength, +1);
if (sde != SDLOG_OK) {
// sd card is not inserted, so logging task can be deleted
fileDes[ldf].inUse = false;
return storageStatus = SDLOG_FATFS_ERROR;
}

Expand Down
186 changes: 102 additions & 84 deletions sw/tools/px4/px_uploader.py
Original file line number Diff line number Diff line change
Expand Up @@ -582,7 +582,35 @@ def identify(self):
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)

# upload the firmware
def upload(self, fw, force=False, boot_delay=None):
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False):
# select correct binary
found_suitable_firmware = False
for file in fw_list:
fw = firmware(file)
if self.board_type == fw.property('board_id'):
if len(fw_list) > 1: print("using firmware binary {}".format(file))
found_suitable_firmware = True
break

if not found_suitable_firmware:
msg = "Firmware not suitable for this board (Firmware board_type=%u board_id=%u)" % (
self.board_type, fw.property('board_id'))
print("WARNING: %s" % msg)
if force:
if len(fw_list) > 1:
raise FirmwareNotSuitableException("force flashing failed, more than one file provided, none suitable")
print("FORCED WRITE, FLASHING ANYWAY!")
else:
raise FirmwareNotSuitableException(msg)

percent = fw.property('image_size') / fw.property('image_maxsize')
binary_size = float(fw.property('image_size'))
binary_max_size = float(fw.property('image_maxsize'))
percent = (binary_size / binary_max_size) * 100

print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%) " % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent))
print()

# Make sure we are doing the right thing
start = _time()
if self.board_type != fw.property('board_id'):
Expand All @@ -598,74 +626,74 @@ def upload(self, fw, force=False, boot_delay=None):
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")

# # OTP added in v4:
# if self.bl_rev >= 4:
# for byte in range(0, 32*6, 4):
# x = self.__getOTP(byte)
# self.otp = self.otp + x
# # print(binascii.hexlify(x).decode('Latin-1') + ' ', end='')
# # see src/modules/systemlib/otp.h in px4 code:
# self.otp_id = self.otp[0:4]
# self.otp_idtype = self.otp[4:5]
# self.otp_vid = self.otp[8:4:-1]
# self.otp_pid = self.otp[12:8:-1]
# self.otp_coa = self.otp[32:160]
# # show user:
# try:
# print("sn: ", end='')
# for byte in range(0, 12, 4):
# x = self.__getSN(byte)
# x = x[::-1] # reverse the bytes
# self.sn = self.sn + x
# print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
# print('')
# print("chip: %08x" % self.__getCHIP())

# otp_id = self.otp_id.decode('Latin-1')
# if ("PX4" in otp_id):
# print("OTP id: " + otp_id)
# print("OTP idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
# print("OTP vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
# print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1'))
# print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1'))

# except Exception:
# # ignore bad character encodings
# pass

# # Silicon errata check was added in v5
# if (self.bl_rev >= 5):
# des = self.__getCHIPDes()
# if (len(des) == 2):
# print("family: %s" % des[0])
# print("revision: %s" % des[1])
# print("flash: %d bytes" % self.fw_maxsize)

# # Prevent uploads where the maximum image size of the board config is smaller than the flash
# # of the board. This is a hint the user chose the wrong config and will lack features
# # for this particular board.

# # This check should also check if the revision is an unaffected revision
# # and thus can support the full flash, see
# # https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144

# if self.fw_maxsize > fw.property('image_maxsize') and not force:
# raise RuntimeError("Board can accept larger flash images (%u bytes) than board config (%u bytes). Please use the correct board configuration to avoid lacking critical functionality."
# % (self.fw_maxsize, fw.property('image_maxsize')))
# else:
# # If we're still on bootloader v4 on a Pixhawk, we don't know if we
# # have the silicon errata and therefore need to flash px4_fmu-v2
# # with 1MB flash or if it supports px4_fmu-v3 with 2MB flash.
# if fw.property('board_id') == 9 \
# and fw.property('image_size') > 1032192 \
# and not force:
# raise RuntimeError("\nThe Board uses bootloader revision 4 and can therefore not determine\n"
# "if flashing more than 1 MB (px4_fmu-v3_default) is safe, chances are\n"
# "high that it is not safe! If unsure, use px4_fmu-v2_default.\n"
# "\n"
# "If you know you that the board does not have the silicon errata, use\n"
# "this script with --force, or update the bootloader. If you are invoking\n"
# "upload using make, you can use force-upload target to force the upload.\n")
# OTP added in v4:
if self.bl_rev >= 4:
for byte in range(0, 32*6, 4):
x = self.__getOTP(byte)
self.otp = self.otp + x
# print(binascii.hexlify(x).decode('Latin-1') + ' ', end='')
# see src/modules/systemlib/otp.h in px4 code:
self.otp_id = self.otp[0:4]
self.otp_idtype = self.otp[4:5]
self.otp_vid = self.otp[8:4:-1]
self.otp_pid = self.otp[12:8:-1]
self.otp_coa = self.otp[32:160]
# show user:
try:
print("sn: ", end='')
for byte in range(0, 12, 4):
x = self.__getSN(byte)
x = x[::-1] # reverse the bytes
self.sn = self.sn + x
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
print('')
print("chip: %08x" % self.__getCHIP())

otp_id = self.otp_id.decode('Latin-1')
if ("PX4" in otp_id):
print("OTP id: " + otp_id)
print("OTP idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
print("OTP vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1'))
print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1'))

except Exception:
# ignore bad character encodings
pass

# Silicon errata check was added in v5
if (self.bl_rev >= 5):
des = self.__getCHIPDes()
if (len(des) == 2):
print("family: %s" % des[0])
print("revision: %s" % des[1])
print("flash: %d bytes" % self.fw_maxsize)

# Prevent uploads where the maximum image size of the board config is smaller than the flash
# of the board. This is a hint the user chose the wrong config and will lack features
# for this particular board.

# This check should also check if the revision is an unaffected revision
# and thus can support the full flash, see
# https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144

if self.fw_maxsize > fw.property('image_maxsize') and not force:
raise RuntimeError("Board can accept larger flash images (%u bytes) than board config (%u bytes). Please use the correct board configuration to avoid lacking critical functionality."
% (self.fw_maxsize, fw.property('image_maxsize')))
else:
# If we're still on bootloader v4 on a Pixhawk, we don't know if we
# have the silicon errata and therefore need to flash px4_fmu-v2
# with 1MB flash or if it supports px4_fmu-v3 with 2MB flash.
if fw.property('board_id') == 9 \
and fw.property('image_size') > 1032192 \
and not force:
raise RuntimeError("\nThe Board uses bootloader revision 4 and can therefore not determine\n"
"if flashing more than 1 MB (px4_fmu-v3_default) is safe, chances are\n"
"high that it is not safe! If unsure, use px4_fmu-v2_default.\n"
"\n"
"If you know you that the board does not have the silicon errata, use\n"
"this script with --force, or update the bootloader. If you are invoking\n"
"upload using make, you can use force-upload target to force the upload.\n")
self.__erase("Erase ")
self.__program("Program", fw)

Expand Down Expand Up @@ -764,7 +792,7 @@ def main():
parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading')
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot')
parser.add_argument('firmware', action="store", help="Firmware file to be uploaded")
parser.add_argument('firmware', action="store", nargs='+', help="Firmware file(s)")
args = parser.parse_args()

if args.use_protocol_splitter_format:
Expand All @@ -776,17 +804,7 @@ def main():
print("WARNING: You should uninstall ModemManager as it conflicts with any non-modem serial device (like Pixhawk)")
print("==========================================================================================================")

# Load the firmware file
fw = firmware(args.firmware)

percent = fw.property('image_size') / fw.property('image_maxsize')
binary_size = float(fw.property('image_size'))
binary_max_size = float(fw.property('image_maxsize'))
percent = (binary_size / binary_max_size) * 100

print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%), waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent))
print()

print("Waiting for bootloader...")
# tell any GCS that might be connected to the autopilot to give up
# control of the serial port

Expand Down Expand Up @@ -835,7 +853,7 @@ def main():
try:
if "linux" in _platform:
# Linux, don't open Mac OS and Win ports
if "tty.usb" not in port:
if "COM" not in port and "tty.usb" not in port:
up = uploader(port, args.baud_bootloader, baud_flightstack)
elif "darwin" in _platform:
# OS X, don't open Windows and Linux ports
Expand Down Expand Up @@ -889,7 +907,7 @@ def main():

try:
# ok, we have a bootloader, try flashing it
up.upload(fw, force=args.force, boot_delay=args.boot_delay)
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay)

# if we made this far without raising exceptions, the upload was successful
successful = True
Expand Down Expand Up @@ -935,4 +953,4 @@ def main():
if __name__ == '__main__':
main()

# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4
# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4
21 changes: 0 additions & 21 deletions sw/tools/px4/set_target.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,27 +63,6 @@
# sys.exit(0)

if mode == -1: # no pprz cdc was found, look for PX4
ports = glob.glob("/dev/serial/by-id/usb-3D_Robotics*")
ports.append(glob.glob("/dev/serial/by-id/pci-3D_Robotics*"))
ports.append(glob.glob("/dev/serial/by-id/usb-Hex_ProfiCNC_Cube*"))
ports.append(glob.glob("/dev/serial/by-id/usb-ArduPilot*"))
for p in ports:
port = p
if isinstance(p, list) and len(port) > 0:
port = p[0]
if len(port) > 0:
try:
ser = serial.Serial(port, timeout=0.5)
mode = 2
print("Original PX4 firmware CDC device found at port: " + port)
except serial.serialutil.SerialException:
print("Non working PX4 port found, continuing...")

if mode == -1:
print("No original PX4 CDC firmware found either.")
print("Error: no compatible usb device found...")
sys.exit(1)

if target == "fbw":
print("Error: original firmware cannot be used to upload the fbw code. Wait for the PX4 bootloader to exit (takes 5 seconds), or in case this is the first upload; first upload the Paparazzi ap target.")
sys.exit(1)
Expand Down

0 comments on commit b855de5

Please sign in to comment.