paparazzi-commits
[Top][All Lists]
Advanced

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

[paparazzi-commits] [paparazzi/paparazzi] 9d0639: [autopilot] reorganize


From: Gautier Hattenberger
Subject: [paparazzi-commits] [paparazzi/paparazzi] 9d0639: [autopilot] reorganize autopilot code
Date: Tue, 27 Jul 2021 05:01:41 -0700

  Branch: refs/heads/autopilot_reorg
  Home:   https://github.com/paparazzi/paparazzi
  Commit: 9d06398c562b2a7e61a01e4877061cfdc0d461d2
      
https://github.com/paparazzi/paparazzi/commit/9d06398c562b2a7e61a01e4877061cfdc0d461d2
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M sw/airborne/arch/chibios/mcu_arch.h
    M sw/airborne/arch/linux/mcu_arch.h
    M sw/airborne/arch/sim/mcu_arch.h
    M sw/airborne/arch/stm32/mcu_arch.h
    M sw/airborne/firmwares/demo/demo_ahrs_actuators.c
    M sw/airborne/firmwares/fixedwing/main_ap.c
    M sw/airborne/firmwares/fixedwing/main_fbw.c
    M sw/airborne/firmwares/rotorcraft/main_ap.c
    M sw/airborne/firmwares/rotorcraft/main_fbw.c
    M sw/airborne/firmwares/rover/main_ap.c
    M sw/airborne/firmwares/setup/setup_actuators.c
    M sw/airborne/firmwares/setup/usb_tunnel.c
    M sw/airborne/firmwares/tutorial/main_demo3.c
    M sw/airborne/firmwares/tutorial/main_demo4.c
    M sw/airborne/firmwares/tutorial/main_demo5.c
    M sw/airborne/firmwares/tutorial/main_demo6.c
    M sw/airborne/mcu_periph/sys_time.c
    M sw/airborne/mcu_periph/sys_time.h
    M sw/airborne/test/mcu_periph/test_adc.c
    M sw/airborne/test/mcu_periph/test_gpio.c
    M sw/airborne/test/mcu_periph/test_sys_time_timer.c
    M sw/airborne/test/mcu_periph/test_sys_time_usleep.c
    M sw/airborne/test/peripherals/test_ami601.c
    M sw/airborne/test/peripherals/test_lis302dl_spi.c
    M sw/airborne/test/peripherals/test_ms2100.c
    M sw/airborne/test/subsystems/test_ahrs.c
    M sw/airborne/test/subsystems/test_imu.c
    M sw/airborne/test/subsystems/test_radio_control.c
    M sw/airborne/test/subsystems/test_settings.c
    M sw/airborne/test/test_manual.c
    M sw/airborne/test/test_math_trig_compressed.c
    M sw/airborne/test/test_telemetry.c
    M sw/lib/ocaml/aircraft.ml
    M sw/lib/ocaml/module.ml
    M sw/tools/generators/gen_makefile.ml
    M sw/tools/generators/gen_modules.ml

  Log Message:
  -----------
  [autopilot] reorganize autopilot code

- better structure for the autopilot tasks
- convergence between firmwares
- remove unused int_enable functions
- update generators


  Commit: 10d59311a2ea4d3a94ef00708a72312b85976ed3
      
https://github.com/paparazzi/paparazzi/commit/10d59311a2ea4d3a94ef00708a72312b85976ed3
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    A sw/airborne/arch/linux/subsystems/actuators/actuators_pwm_arch.c
    A sw/airborne/arch/linux/subsystems/actuators/actuators_pwm_arch.h
    M sw/airborne/arch/sim/led_hw.c
    M sw/airborne/arch/sim/led_hw.h
    A sw/airborne/arch/sim/mcu_periph/gpio_arch.c
    M sw/airborne/arch/sim/sim_ap.c
    M sw/airborne/boards/ardrone/navdata.c
    M sw/airborne/inter_mcu.h
    M sw/airborne/math/pprz_trig_int.c
    M sw/airborne/math/pprz_trig_int.h
    M sw/airborne/modules/datalink/mavlink.c
    M sw/airborne/modules/datalink/missionlib/mission_manager.c
    M sw/airborne/modules/datalink/missionlib/waypoints.c
    M sw/airborne/modules/digital_cam/dc.c
    M sw/airborne/modules/display/max7456.c
    A sw/airborne/modules/sensors/baro_board_common.c
    A sw/airborne/modules/sensors/baro_board_common.h
    M sw/airborne/modules/sensors/baro_ms5611_i2c.c
    M sw/airborne/modules/sensors/baro_ms5611_i2c.h
    M sw/airborne/subsystems/datalink/downlink.h
    M sw/simulator/nps/nps_main_hitl.c
    M tests/modules/generated/modules.h
    M tests/modules/generated/periodic_telemetry.h
    M tests/modules/generated/settings.h

  Log Message:
  -----------
  update various code for errors and warnings or fit reorg


  Commit: d32a1584eb1db84df79050e90a3129d25671e6eb
      
https://github.com/paparazzi/paparazzi/commit/d32a1584eb1db84df79050e90a3129d25671e6eb
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M conf/firmwares/fixedwing.makefile
    M conf/firmwares/rotorcraft.makefile
    M conf/firmwares/rover.makefile
    M conf/firmwares/subsystems/fixedwing/autopilot.makefile
    R conf/firmwares/subsystems/shared/hitl.makefile
    R conf/firmwares/subsystems/shared/nps.makefile
    R conf/firmwares/subsystems/shared/nps_common.makefile
    A conf/modules/boards/apogee_1.0.xml
    A conf/modules/boards/apogee_1.0_chibios.xml
    A conf/modules/boards/ardrone2.xml
    A conf/modules/boards/bebop.xml
    A conf/modules/boards/bebop2.xml
    A conf/modules/boards/booz_1.0.xml
    A conf/modules/boards/chimera_1.0.xml
    A conf/modules/boards/disco.xml
    A conf/modules/boards/elle0_1.0.xml
    A conf/modules/boards/elle0_1.2.xml
    A conf/modules/boards/krooz_sd.xml
    A conf/modules/boards/lisa_l_1.0.xml
    A conf/modules/boards/lisa_l_1.1.xml
    A conf/modules/boards/lisa_m_1.0.xml
    A conf/modules/boards/lisa_m_2.0.xml
    A conf/modules/boards/lisa_m_2.0_chibios.xml
    A conf/modules/boards/lisa_m_2.1.xml
    A conf/modules/boards/lisa_m_2.1_chibios.xml
    A conf/modules/boards/lisa_mx_2.0.xml
    A conf/modules/boards/lisa_mx_2.1.xml
    A conf/modules/boards/lisa_mx_2.1_chibios.xml
    A conf/modules/boards/lisa_mxs_1.0.xml
    A conf/modules/boards/lisa_mxs_1.0_nimble.xml
    A conf/modules/boards/lisa_s_1.0.xml
    A conf/modules/boards/navstik_1.0.xml
    A conf/modules/boards/naze32_rev4.xml
    A conf/modules/boards/naze32_rev5.xml
    A conf/modules/boards/opa_ap_1.0.xml
    A conf/modules/boards/openpilot_revo_1.0.xml
    A conf/modules/boards/openpilot_revo_nano.xml
    A conf/modules/boards/px4fmu_1.7.xml
    A conf/modules/boards/px4fmu_2.4.xml
    A conf/modules/boards/px4fmu_2.4_chibios.xml
    A conf/modules/boards/px4fmu_4.0.xml
    A conf/modules/boards/px4fmu_4.0_chibios.xml
    A conf/modules/boards/px4fmu_5.0_chibios.xml
    A conf/modules/boards/swing.xml
    A conf/modules/firmwares/fixedwing.xml
    A conf/modules/firmwares/rotorcraft.xml
    A conf/modules/firmwares/rover.xml
    R conf/modules/nps.xml
    R conf/modules/sim.xml
    A conf/modules/targets/ap.xml
    A conf/modules/targets/fbw.xml
    A conf/modules/targets/hitl.xml
    A conf/modules/targets/nps.xml
    A conf/modules/targets/sim.xml
    M sw/airborne/boards/bebop.h

  Log Message:
  -----------
  [firmware] split firmware makefile into modules

these modules are automatically loaded according to the target, board
and firmware


  Commit: 11ac07d3851fbd3c05efdbca031c8010200c91e0
      
https://github.com/paparazzi/paparazzi/commit/11ac07d3851fbd3c05efdbca031c8010200c91e0
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M conf/airframes/ENAC/fixed-wing/apogee.xml
    M conf/airframes/ENAC/fixed-wing/tawaki.xml
    M conf/airframes/ENAC/quadrotor/crazyflie_2.1.xml
    M conf/airframes/ESDEN/esden_cocto_lm2a2.xml
    M conf/airframes/ESDEN/esden_gain_scheduling_example.xml
    M conf/airframes/ESDEN/esden_hexy_ll11a2pwm.xml
    M conf/airframes/ESDEN/esden_hexy_lm2a2pwm.xml
    M conf/airframes/ESDEN/esden_lisa2_hex.xml
    M conf/airframes/ESDEN/esden_qs_asp22.xml
    M conf/airframes/ESDEN/esden_quady_ll11a2pwm.xml
    M conf/airframes/ESDEN/esden_quady_lm1a1pwm.xml
    M conf/airframes/ESDEN/esden_quady_lm2a2pwm.xml
    M conf/airframes/ESDEN/esden_quady_lm2a2pwmppm.xml
    M conf/airframes/ESDEN/esden_quady_ls10pwm.xml
    M conf/airframes/MM/bebop.xml
    M conf/airframes/MM/bebop2_lum1_xbee.xml
    M conf/airframes/OPENUAS/openuas_itsybitsy.xml
    M conf/airframes/OPENUAS/openuas_own_mavtec.xml
    M conf/airframes/examples/microjet_lisa_m_xsens.xml
    M conf/airframes/max/microjet_lisa_m.xml

  Log Message:
  -----------
  [conf] update airframe files

minimal changes, mostly to move the 'modules' node inside firmware
section


  Commit: d02ec5ba98ea46fb06f11830ce0a3c14d15bc743
      
https://github.com/paparazzi/paparazzi/commit/d02ec5ba98ea46fb06f11830ce0a3c14d15bc743
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M conf/modules/AOA_adc.xml
    M conf/modules/AOA_pwm.xml
    A conf/modules/actuators.xml
    M conf/modules/actuators_ardrone2.xml
    M conf/modules/actuators_asctec_v2.xml
    M conf/modules/actuators_bebop.xml
    M conf/modules/actuators_disco.xml
    M conf/modules/actuators_dshot.xml
    M conf/modules/actuators_dualpwm.xml
    M conf/modules/actuators_dummy.xml
    M conf/modules/actuators_esc32.xml
    M conf/modules/actuators_md25.xml
    M conf/modules/actuators_nps.xml
    M conf/modules/actuators_ostrich.xml
    M conf/modules/actuators_ppm.xml
    M conf/modules/actuators_pwm.xml
    M conf/modules/actuators_sbus.xml
    M conf/modules/actuators_spektrum.xml
    M conf/modules/actuators_swing.xml
    M conf/modules/actuators_uavcan.xml
    M conf/modules/adc.xml
    M conf/modules/ahrs_chimu_spi.xml
    M conf/modules/ahrs_chimu_uart.xml
    A conf/modules/ahrs_common.xml
    M conf/modules/ahrs_float_cmpl_quat.xml
    M conf/modules/ahrs_float_cmpl_rmat.xml
    M conf/modules/ahrs_float_dcm.xml
    M conf/modules/ahrs_float_invariant.xml
    M conf/modules/ahrs_float_mlkf.xml
    M conf/modules/ahrs_gx3.xml
    M conf/modules/ahrs_int_cmpl_quat.xml
    M conf/modules/ahrs_madgwick.xml
    M conf/modules/ahrs_sim.xml
    M conf/modules/ahrs_vectornav.xml
    M conf/modules/air_data.xml
    M conf/modules/airspeed_adc.xml
    M conf/modules/airspeed_ads1114.xml
    M conf/modules/airspeed_amsys.xml
    M conf/modules/airspeed_ets.xml
    M conf/modules/airspeed_ms45xx_i2c.xml
    M conf/modules/airspeed_otf.xml
    M conf/modules/airspeed_sdp3x.xml
    M conf/modules/airspeed_uADC.xml
    A conf/modules/autopilot_gnc.xml
    M conf/modules/baro_MS5534A.xml
    M conf/modules/baro_amsys.xml
    M conf/modules/baro_bmp.xml
    M conf/modules/baro_bmp280_i2c.xml
    M conf/modules/baro_bmp3.xml
    A conf/modules/baro_board.xml
    A conf/modules/baro_board_common.xml
    M conf/modules/baro_ets.xml
    M conf/modules/baro_hca.xml
    M conf/modules/baro_mpl3115.xml
    M conf/modules/baro_ms5611_i2c.xml
    M conf/modules/baro_ms5611_spi.xml
    M conf/modules/baro_scp_i2c.xml
    M conf/modules/baro_sim.xml
    M conf/modules/battery_monitor.xml
    M conf/modules/bebop_cam.xml
    M conf/modules/control.xml
    M conf/modules/control_adaptive.xml
    M conf/modules/control_energy.xml
    M conf/modules/control_energyadaptive.xml
    M conf/modules/control_new.xml
    M conf/modules/dac.xml
    A conf/modules/datalink_common.xml
    A conf/modules/electrical.xml
    M conf/modules/fdm_jsbsim.xml
    M conf/modules/filter_1euro_imu.xml
    M conf/modules/flight_recorder.xml
    M conf/modules/gpio_ext_common.xml
    M conf/modules/gps.xml
    M conf/modules/gps_datalink.xml
    M conf/modules/gps_furuno.xml
    M conf/modules/gps_mediatek_diy.xml
    M conf/modules/gps_nmea.xml
    M conf/modules/gps_nps.xml
    M conf/modules/gps_optitrack.xml
    M conf/modules/gps_piksi.xml
    M conf/modules/gps_sim.xml
    M conf/modules/gps_sim_hitl.xml
    M conf/modules/gps_sirf.xml
    M conf/modules/gps_skytraq.xml
    M conf/modules/gps_ublox.xml
    M conf/modules/gps_ubx_i2c.xml
    M conf/modules/gps_ubx_ucenter.xml
    M conf/modules/gps_udp.xml
    M conf/modules/guidance_basic_fw.xml
    M conf/modules/guidance_energy.xml
    M conf/modules/guidance_full_pid_fw.xml
    M conf/modules/guidance_hybrid.xml
    M conf/modules/guidance_indi.xml
    M conf/modules/guidance_indi_hybrid.xml
    M conf/modules/guidance_rotorcraft.xml
    M conf/modules/guidance_rover.xml
    M conf/modules/guidance_rover_holonomic.xml
    M conf/modules/imu_apogee.xml
    M conf/modules/imu_apogee_mpu9150.xml
    M conf/modules/imu_ardrone2.xml
    M conf/modules/imu_aspirin_common.xml
    M conf/modules/imu_aspirin_i2c_common.xml
    M conf/modules/imu_aspirin_i2c_v1.0.xml
    M conf/modules/imu_aspirin_i2c_v1.5.xml
    M conf/modules/imu_aspirin_v1.0.xml
    M conf/modules/imu_aspirin_v1.5.xml
    M conf/modules/imu_aspirin_v2.1.xml
    M conf/modules/imu_aspirin_v2.2.xml
    M conf/modules/imu_aspirin_v2_common.xml
    M conf/modules/imu_bebop.xml
    M conf/modules/imu_bmi088_i2c.xml
    M conf/modules/imu_chimera.xml
    M conf/modules/imu_common.xml
    M conf/modules/imu_disco.xml
    M conf/modules/imu_drotek_10dof_v2.xml
    M conf/modules/imu_elle0.xml
    M conf/modules/imu_gl1.xml
    M conf/modules/imu_krooz_sd.xml
    M conf/modules/imu_krooz_sd_memsic.xml
    M conf/modules/imu_lisa_m_v2.1.xml
    M conf/modules/imu_lisa_mx_v2.1.xml
    M conf/modules/imu_lisa_s_v1.0.xml
    M conf/modules/imu_mpu6000.xml
    M conf/modules/imu_mpu6000_hmc5883.xml
    M conf/modules/imu_mpu60x0_i2c.xml
    M conf/modules/imu_mpu9250.xml
    M conf/modules/imu_mpu9250_i2c.xml
    M conf/modules/imu_mpu9250_spi.xml
    M conf/modules/imu_navstik.xml
    M conf/modules/imu_nps.xml
    M conf/modules/imu_openpilot_revo.xml
    M conf/modules/imu_openpilot_revo_nano.xml
    M conf/modules/imu_pprzuav.xml
    M conf/modules/imu_px4fmu_v1.7.xml
    M conf/modules/imu_px4fmu_v2.4.xml
    M conf/modules/imu_quality_assessment.xml
    A conf/modules/imu_sim.xml
    M conf/modules/imu_swing.xml
    M conf/modules/imu_temp_ctrl.xml
    M conf/modules/imu_um6.xml
    M conf/modules/imu_vectornav.xml
    M conf/modules/imu_xsens.xml
    M conf/modules/ins.xml
    M conf/modules/ins_alt_float.xml
    M conf/modules/ins_arduimu.xml
    M conf/modules/ins_arduimu_basic.xml
    M conf/modules/ins_ekf2.xml
    M conf/modules/ins_extended.xml
    M conf/modules/ins_float_invariant.xml
    M conf/modules/ins_gps_passthrough.xml
    M conf/modules/ins_hff.xml
    M conf/modules/ins_hff_extended.xml
    M conf/modules/ins_mekf_wind.xml
    M conf/modules/ins_nps.xml
    M conf/modules/ins_sim.xml
    M conf/modules/ins_skeleton.xml
    M conf/modules/ins_vectornav.xml
    M conf/modules/ins_vn100.xml
    M conf/modules/ins_xsens.xml
    M conf/modules/ins_xsens700.xml
    M conf/modules/intermcu_can.xml
    M conf/modules/intermcu_spi.xml
    M conf/modules/intermcu_uart.xml
    M conf/modules/jevois.xml
    M conf/modules/lidar_lite.xml
    M conf/modules/lidar_sf11.xml
    M conf/modules/lidar_tfmini.xml
    M conf/modules/lidar_tfmini_i2c.xml
    M conf/modules/logger_control_effectiveness.xml
    M conf/modules/logger_dataflash.xml
    M conf/modules/logger_file.xml
    M conf/modules/logger_sd_chibios.xml
    M conf/modules/logger_sd_spi_direct.xml
    M conf/modules/logger_spi_link.xml
    M conf/modules/logger_uart.xml
    M conf/modules/mag_calib_ukf.xml
    M conf/modules/mag_hmc5843.xml
    M conf/modules/mag_hmc58xx.xml
    M conf/modules/mag_ist8310.xml
    M conf/modules/mag_lis3mdl.xml
    M conf/modules/mag_pitot_uart.xml
    A conf/modules/math.xml
    M conf/modules/mcu.xml
    M conf/modules/mission_fw.xml
    M conf/modules/mission_rotorcraft.xml
    M conf/modules/module.dtd
    M conf/modules/motor_mixing.xml
    M conf/modules/nav_basic_fw.xml
    M conf/modules/nav_basic_rotorcraft.xml
    M conf/modules/nav_bungee_takeoff.xml
    M conf/modules/nav_catapult.xml
    M conf/modules/nav_cube.xml
    M conf/modules/nav_drop.xml
    M conf/modules/nav_fish.xml
    M conf/modules/nav_flower.xml
    M conf/modules/nav_gls.xml
    M conf/modules/nav_heli_spinup.xml
    M conf/modules/nav_launcher.xml
    M conf/modules/nav_line.xml
    M conf/modules/nav_line_border.xml
    M conf/modules/nav_line_osam.xml
    M conf/modules/nav_poles.xml
    M conf/modules/nav_rover_base.xml
    M conf/modules/nav_skid_landing.xml
    M conf/modules/nav_smooth.xml
    M conf/modules/nav_spiral.xml
    M conf/modules/nav_survey_disc.xml
    M conf/modules/nav_survey_poly_osam.xml
    M conf/modules/nav_survey_poly_rotorcraft.xml
    M conf/modules/nav_survey_polygon.xml
    M conf/modules/nav_survey_rectangle_rotorcraft.xml
    M conf/modules/nav_survey_zamboni.xml
    M conf/modules/nav_vertical_raster.xml
    M conf/modules/navigation.xml
    M conf/modules/photogrammetry_calculator.xml
    M conf/modules/pipe.xml
    M conf/modules/radio_control_cc2500_frsky.xml
    M conf/modules/radio_control_datalink.xml
    M conf/modules/radio_control_hott.xml
    M conf/modules/radio_control_ppm.xml
    M conf/modules/radio_control_sbus.xml
    M conf/modules/radio_control_sbus_dual.xml
    M conf/modules/radio_control_spektrum.xml
    M conf/modules/radio_control_superbitrf_rc.xml
    M conf/modules/rng.xml
    A conf/modules/settings.xml
    M conf/modules/shell.xml
    M conf/modules/sonar_adc.xml
    M conf/modules/sonar_bebop.xml
    M conf/modules/sonar_pwm.xml
    M conf/modules/sonar_vl53l1x.xml
    M conf/modules/spi_master.xml
    M conf/modules/stabilization_adaptive_fw.xml
    M conf/modules/stabilization_attitude_fw.xml
    M conf/modules/stabilization_float_euler.xml
    M conf/modules/stabilization_float_quat.xml
    M conf/modules/stabilization_heli_indi.xml
    M conf/modules/stabilization_indi.xml
    M conf/modules/stabilization_indi_simple.xml
    M conf/modules/stabilization_int_euler.xml
    M conf/modules/stabilization_int_quat.xml
    M conf/modules/stabilization_passthrough.xml
    M conf/modules/stabilization_rate.xml
    M conf/modules/stabilization_rate_indi.xml
    M conf/modules/stabilization_rotorcraft.xml
    A conf/modules/state_interface.xml
    M conf/modules/stereocam.xml
    M conf/modules/sys_mon.xml
    A conf/modules/system_core.xml
    M conf/modules/telemetry_bluegiga.xml
    M conf/modules/telemetry_intermcu.xml
    M conf/modules/telemetry_ivy.xml
    M conf/modules/telemetry_nps.xml
    M conf/modules/telemetry_nps_secure.xml
    M conf/modules/telemetry_secure_common.xml
    M conf/modules/telemetry_sim.xml
    M conf/modules/telemetry_superbitrf.xml
    M conf/modules/telemetry_transparent.xml
    M conf/modules/telemetry_transparent_frsky_x.xml
    M conf/modules/telemetry_transparent_gec.xml
    M conf/modules/telemetry_transparent_udp.xml
    M conf/modules/telemetry_transparent_usb.xml
    M conf/modules/telemetry_w5100.xml
    M conf/modules/telemetry_xbee_api.xml
    M conf/modules/tlsf.xml
    M conf/modules/traffic_info.xml
    M conf/modules/tune_airspeed.xml
    M conf/modules/uart.xml
    M conf/modules/udp.xml

  Log Message:
  -----------
  [modules] update modules XML for proper dependcies and tasks


  Commit: d37b7903d2896b6338e6a645f29d86a125a052a6
      
https://github.com/paparazzi/paparazzi/commit/d37b7903d2896b6338e6a645f29d86a125a052a6
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    A conf/modules/autopilot_gnc_fw.xml
    M conf/modules/baro_board.xml
    M conf/modules/baro_board_common.xml
    M conf/modules/firmwares/fixedwing.xml
    M conf/modules/intermcu_uart.xml
    M conf/modules/targets/ap.xml
    M sw/airborne/arch/sim/sim_ap.c
    M sw/airborne/firmwares/fixedwing/autopilot_static.c
    M sw/airborne/firmwares/fixedwing/main_ap.c
    M sw/airborne/firmwares/fixedwing/main_ap.h
    M sw/airborne/firmwares/rotorcraft/main_ap.c
    M sw/airborne/modules/sensors/baro_board_common.c
    M sw/simulator/sitl.ml

  Log Message:
  -----------
  [autopilot] convert fixedwing firmware to new AP modules

also load baro_board with ap target as a workaround until relevant
modules are loaded from board XML modules


  Commit: e4fd6a8524a7fef85c9030169234b5a9a236e28e
      
https://github.com/paparazzi/paparazzi/commit/e4fd6a8524a7fef85c9030169234b5a9a236e28e
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M conf/modules/autopilot_gnc_fw.xml
    M sw/tools/generators/gen_modules.ml

  Log Message:
  -----------
  [gen_modules] use parse on cond attribute

It will check for valid C expression and allow to use alias for some
keywords not allowed in XML


  Commit: 2ed729731a8c4b3fe18f3e6d6c3e9625645568f3
      
https://github.com/paparazzi/paparazzi/commit/2ed729731a8c4b3fe18f3e6d6c3e9625645568f3
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M sw/airborne/firmwares/fixedwing/main_ap.c

  Log Message:
  -----------
  [fix] add missing task monitoring

this should be included in a core module


  Commit: 869adb279480539a3bb8106bf4e2a4b63d23c33a
      
https://github.com/paparazzi/paparazzi/commit/869adb279480539a3bb8106bf4e2a4b63d23c33a
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c
    M sw/airborne/mcu_periph/sys_time.h

  Log Message:
  -----------
  [sys_time] make time thread work at SYS_TIME_FREQ for ChibiOS

This is making the ChibiOS implementation behave the same way than the
other arch.
The get_sys_time functions for milli and micor seconds are also more
accurate.


  Commit: 81a695e55063c3f5a706bd7b27637814ae65af4c
      
https://github.com/paparazzi/paparazzi/commit/81a695e55063c3f5a706bd7b27637814ae65af4c
  Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
  Date:   2021-07-27 (Tue, 27 Jul 2021)

  Changed paths:
    M conf/modules/autopilot_gnc_fw.xml
    M sw/airborne/firmwares/fixedwing/autopilot_firmware.c
    M sw/airborne/firmwares/fixedwing/autopilot_firmware.h
    M sw/airborne/firmwares/fixedwing/main_ap.c
    M sw/airborne/firmwares/fixedwing/main_chibios.c
    M sw/airborne/firmwares/rotorcraft/main_ap.c
    M sw/airborne/firmwares/rotorcraft/main_chibios.c
    M sw/airborne/firmwares/rover/main_ap.c
    M sw/airborne/firmwares/rover/main_chibios.c

  Log Message:
  -----------
  [autopilot] group tasks and improve timing

- some tasks are grouped in a gnc group as they should be called
in sequence: estimation, control, default, actuators
- the timing between the sensors and gnc is half of the main period, it
correspond to the default resolution of the sys_time virtual timers
- the timing of AP threads is improved with a calculated wakeup time
instead of a fixed sleep time
- the monitor task for fixedwing is moved in the firmware specific
autopilot part and called by a module
- all timings have been accurately tested with high speed log and a
dedicated profiler for ChibiOS


Compare: 
https://github.com/paparazzi/paparazzi/compare/9381fe2c594d...81a695e55063



reply via email to

[Prev in Thread] Current Thread [Next in Thread]