mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-21 20:04:09 +08:00
[conf] Fix build warnings and small bugfixes
This commit is contained in:
+13
-13
@@ -7,7 +7,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -18,7 +18,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -29,7 +29,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/superbitrf.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -40,7 +40,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
|
||||
flight_plan="flight_plans/versatile_airspeed.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/estimation/ac_char.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#ffffffffffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -51,7 +51,7 @@
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/electrical.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -62,7 +62,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -73,7 +73,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -84,7 +84,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -95,7 +95,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -106,7 +106,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
|
||||
settings_modules="modules/air_data.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
settings_modules="modules/air_data.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -117,7 +117,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_optitrack.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/bebop_cam.xml modules/cv_opticflow.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
settings_modules="modules/bebop_cam.xml modules/cv_opticflow.xml modules/cv_textons.xml modules/electrical.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_flow.xml modules/nav_rotorcraft.xml modules/optical_flow_landing.xml modules/stabilization_indi_simple.xml modules/video_capture.xml modules/video_rtp_stream.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -128,7 +128,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/competitions/IMAV2022_falcon.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_rotorcraft.xml modules/stabilization_indi.xml"
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/stabilization_indi.xml"
|
||||
gui_color="#5eb6d9dd4484"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -139,7 +139,7 @@
|
||||
telemetry="telemetry/default_rotorcraft_slow.xml"
|
||||
flight_plan="flight_plans/dummy.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="[modules/ahrs_float_cmpl_quat.xml] [modules/gps.xml] [modules/guidance_rotorcraft.xml] [modules/imu_common.xml] [modules/ins_extended.xml] [modules/nav_basic_rotorcraft.xml] modules/radio_control_cc2500_frsky.xml [modules/stabilization_int_quat.xml]"
|
||||
settings_modules="[modules/ahrs_float_cmpl_quat.xml] modules/electrical.xml [modules/gps.xml] modules/guidance_pid_rotorcraft.xml [modules/guidance_rotorcraft.xml] [modules/imu_common.xml] [modules/ins_extended.xml] modules/nav_rotorcraft.xml modules/radio_control_cc2500_frsky.xml [modules/stabilization_int_quat.xml]"
|
||||
gui_color="blue"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
+1
-1
@@ -84,7 +84,7 @@
|
||||
telemetry="telemetry/default_rotorcraft_mavlink.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/electrical.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="#ffff954c0000"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -18,7 +18,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -29,7 +29,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -40,7 +40,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/stabilization_adaptive_fw.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/power_switch.xml modules/stabilization_adaptive_fw.xml"
|
||||
gui_color="#ffff7d7d0000"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -51,7 +51,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/superbitrf.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -62,7 +62,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -73,7 +73,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
|
||||
flight_plan="flight_plans/versatile_airspeed.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/estimation/ac_char.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#ffffffffffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -84,7 +84,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/nav_modules.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_dash_loiter_trim.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -95,7 +95,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -106,7 +106,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_dash_loiter_trim.xml"
|
||||
settings_modules="modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/electrical.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -117,7 +117,7 @@
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/electrical.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -128,7 +128,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -139,7 +139,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -150,7 +150,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -161,7 +161,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -172,7 +172,7 @@
|
||||
telemetry="telemetry/fixedwing_flight_recorder.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/logger_sd_chibios.xml modules/nav_basic_fw.xml modules/power_switch.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -183,7 +183,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -194,7 +194,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/cv_opticflow.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/opticflow_hover.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/cv_opticflow.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/opticflow_hover.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -205,7 +205,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/bebop_ae_awb.xml modules/bebop_cam.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/bebop_ae_awb.xml modules/bebop_cam.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
@@ -167,7 +167,7 @@ static int imin(int num1, int num2) {
|
||||
int pprz_svd_float(float **a, float *w, float **v, int m, int n)
|
||||
{
|
||||
/* Householder reduction to bidiagonal form. */
|
||||
int flag, i, its, j, jj, k, l, NM;
|
||||
int flag, i, its, j, jj, k, l, NM = 0;
|
||||
float C, F, H, S, X, Y, Z, tmp;
|
||||
float G = 0.0;
|
||||
float Scale = 0.0;
|
||||
|
||||
@@ -396,8 +396,8 @@ void extract_information_from_parameters(float *parameters_u, float *parameters_
|
||||
* @param[in] focal_length Focal length in pixels
|
||||
* @param[out] info Contains all info extracted from the linear flow fit.
|
||||
*/
|
||||
bool analyze_flow_field(struct flow_t *vectors, int count, float error_threshold, int n_iterations, int n_samples,
|
||||
int im_width, int im_height, float focal_length, struct linear_flow_fit_info *info)
|
||||
bool analyze_flow_field(struct flow_t *vectors __attribute__((unused)), int count, float error_threshold __attribute__((unused)), int n_iterations __attribute__((unused)), int n_samples __attribute__((unused)),
|
||||
int im_width __attribute__((unused)), int im_height __attribute__((unused)), float focal_length __attribute__((unused)), struct linear_flow_fit_info *info __attribute__((unused)))
|
||||
{
|
||||
// Are there enough flow vectors to perform a fit?
|
||||
if (count < N_PAR_TR_FIT) {
|
||||
|
||||
@@ -63,14 +63,14 @@ void imu_mpu9250_report(void)
|
||||
(int32_t)(mpu9250.data_accel.vect.y),
|
||||
(int32_t)(mpu9250.data_accel.vect.z)
|
||||
};
|
||||
DOWNLINK_SEND_IMU_ACCEL_RAW(DefaultChannel, DefaultDevice, &id, &accel.x, &accel.y, &accel.z, &temp);
|
||||
DOWNLINK_SEND_IMU_ACCEL_RAW(DefaultChannel, DefaultDevice, &id, &temp, &accel.x, &accel.y, &accel.z);
|
||||
|
||||
struct Int32Rates rates = {
|
||||
(int32_t)(mpu9250.data_rates.rates.p),
|
||||
(int32_t)(mpu9250.data_rates.rates.q),
|
||||
(int32_t)(mpu9250.data_rates.rates.r)
|
||||
};
|
||||
DOWNLINK_SEND_IMU_GYRO_RAW(DefaultChannel, DefaultDevice, &id, &rates.p, &rates.q, &rates.r, &temp);
|
||||
DOWNLINK_SEND_IMU_GYRO_RAW(DefaultChannel, DefaultDevice, &id, &temp, &rates.p, &rates.q, &rates.r);
|
||||
|
||||
struct Int32Vect3 mag = {
|
||||
(int32_t)(mpu9250.akm.data.vect.x),
|
||||
|
||||
@@ -29,6 +29,7 @@
|
||||
#include "modules/nav/nav_survey_hybrid.h"
|
||||
|
||||
#include "firmwares/rotorcraft/navigation.h"
|
||||
#include "modules/nav/nav_rotorcraft_base.h"
|
||||
#include "math/pprz_algebra_float.h"
|
||||
#include "state.h"
|
||||
#include "autopilot.h"
|
||||
|
||||
@@ -30,7 +30,7 @@
|
||||
static inline void main_init(void);
|
||||
static inline void main_periodic_task(void);
|
||||
static inline void main_event_task(void);
|
||||
static void main_on_radio_control_frame(void);
|
||||
//static void main_on_radio_control_frame(void);
|
||||
|
||||
int main(void)
|
||||
{
|
||||
@@ -91,9 +91,9 @@ static inline void main_event_task(void)
|
||||
//RadioControlEvent(main_on_radio_control_frame); FIXME
|
||||
}
|
||||
|
||||
static void main_on_radio_control_frame(void)
|
||||
/*static void main_on_radio_control_frame(void)
|
||||
{
|
||||
|
||||
// RunOnceEvery(10, {DOWNLINK_SEND_RC(RADIO_CONTROL_NB_CHANNEL, radio_control.values);});
|
||||
RunOnceEvery(10, {DOWNLINK_SEND_RC(RADIO_CONTROL_NB_CHANNEL, radio_control.values);});
|
||||
|
||||
}
|
||||
}*/
|
||||
|
||||
Reference in New Issue
Block a user