[tests] Fix unneeded warnings for test build (#2403)

This commit is contained in:
Freek van Tienen
2019-03-15 19:34:50 +01:00
committed by Michal Podhradsky
parent 61f1d24478
commit 22be04faf9
6 changed files with 142 additions and 140 deletions
+92 -91
View File
@@ -11,114 +11,115 @@
<firmware name="rotorcraft">
<target name="ap" board="px4fmu_2.4" />
<!-- Main autopilot MCU -->
<target name="ap" board="px4fmu_2.4">
<configure name="PERIODIC_FREQUENCY" value="200"/>
<configure name="TELEMETRY_FREQUENCY" value="60"/>
<comment>
amount of time it take for the bat to check
to avoid bat low spike detection when strong pullup withch draws short sudden power
</comment>
<define name="BAT_CHECKER_DELAY" value="80" /><!-- in seconds-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" /><!-- in seconds-->
<module name="telemetry" type="transparent_gec">
<configure name="MODEM_PORT" value="UART2"/>
<configure name="MODEM_BAUD" value="B57600"/>
</module>
<module name="imu" type="px4fmu_v2.4"/>
<!--module name="stabilization" type="indi_simple"/-->
<module name="stabilization" type="float_euler"/>
<!--module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
</module-->
<!--module name="ahrs" type="int_cmpl_quat">
<define name="AHRS_ICQ_IMU_ID" value="IMU_PX4_ID" />
<define name="AHRS_ICQ_MAG_ID" value="MAG_HMC58XX_SENDER_ID" />
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</module-->
<module name="ahrs" type="float_mlkf">
<configure name="SECONDARY_AHRS" value="float_mlkf"/>
<define name="AHRS_MLKF_IMU_ID" value="IMU_PX4_ID"/>
<comment>
use external mag
amount of time it take for the bat to check
to avoid bat low spike detection when strong pullup withch draws short sudden power
</comment>
<define name="AHRS_MLKF_MAG_ID" value="MAG_HMC58XX_SENDER_ID" />
<configure name="USE_MAGNETOMETER" value="TRUE"/>
</module>
<define name="BAT_CHECKER_DELAY" value="80" /><!-- in seconds-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" /><!-- in seconds-->
<module name="telemetry" type="transparent_gec">
<configure name="MODEM_PORT" value="UART2"/>
<configure name="MODEM_BAUD" value="B57600"/>
</module>
<module name="imu" type="px4fmu_v2.4"/>
<!--module name="stabilization" type="indi_simple"/-->
<module name="stabilization" type="float_euler"/>
<!--module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
</module-->
<module name="ahrs" type="vectornav">
<configure name="VN_PORT" value="UART3"/>
<configure name="VN_BAUD" value="B921600"/>
<!--configure name="SECONDARY_AHRS" value="vectornav"/-->
</module>
<!--module name="ahrs" type="int_cmpl_quat">
<define name="AHRS_ICQ_IMU_ID" value="IMU_PX4_ID" />
<define name="AHRS_ICQ_MAG_ID" value="MAG_HMC58XX_SENDER_ID" />
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</module-->
<!--module name="ins" type="float_invariant">
<define name="INS_FINV_IMU_ID" value="IMU_PX4_ID" />
<define name="INS_FINV_MAG_ID" value="MAG_HMC58XX_SENDER_ID" />
<define name="INS_FINV_GPS_ID" value="GPS_UBX_ID" />
<define name="SEND_INVARIANT_FILTER"/>
</module-->
<module name="ahrs" type="float_mlkf">
<configure name="SECONDARY_AHRS" value="float_mlkf"/>
<define name="AHRS_MLKF_IMU_ID" value="IMU_PX4_ID"/>
<comment>
use external mag
</comment>
<define name="AHRS_MLKF_MAG_ID" value="MAG_HMC58XX_SENDER_ID" />
<configure name="USE_MAGNETOMETER" value="TRUE"/>
</module>
<!-- extended INS uses sonar for vertical estimates -->
<module name="ins" type="extended"/>
<!-- Horizontal Filter Float (HFF) INS uses simple Kalman filters to horizontal estimate,
No sonar/lidar updates though -->
<!--module name="ins" type="hff"/-->
<module name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_3" />
</module>
<module name="intermcu" type="uart">
<configure name="INTERMCU_PORT" value="UART6" />
<configure name="INTERMCU_BAUD" value="B1500000" /> <!-- This is only during first 10s start up, afterwards it is set to 230400-->
</module>
<module name="ahrs" type="vectornav">
<configure name="VN_PORT" value="UART3"/>
<configure name="VN_BAUD" value="B921600"/>
<!--configure name="SECONDARY_AHRS" value="vectornav"/-->
</module>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="200" />
</module>
<!--module name="ins" type="float_invariant">
<define name="INS_FINV_IMU_ID" value="IMU_PX4_ID" />
<define name="INS_FINV_MAG_ID" value="MAG_HMC58XX_SENDER_ID" />
<define name="INS_FINV_GPS_ID" value="GPS_UBX_ID" />
<define name="SEND_INVARIANT_FILTER"/>
</module-->
<!-- extended INS uses sonar for vertical estimates -->
<module name="ins" type="extended"/>
<!-- Horizontal Filter Float (HFF) INS uses simple Kalman filters to horizontal estimate,
No sonar/lidar updates though -->
<!--module name="ins" type="hff"/-->
<module name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_3" />
</module>
<module name="intermcu" type="uart">
<configure name="INTERMCU_PORT" value="UART6" />
<configure name="INTERMCU_BAUD" value="B1500000" /> <!-- This is only during first 10s start up, afterwards it is set to 230400-->
</module>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="200" />
</module>
<!--
<module name="tlsf"/>
<module name="pprzlog"/>
<module name="logger" type="sd_chibios"/>
<module name="flight_recorder"/>
<module name="tlsf"/>
<module name="pprzlog"/>
<module name="logger" type="sd_chibios"/>
<module name="flight_recorder"/>
-->
</firmware>
</target>
<firmware name="rotorcraft">
<target name="fbw" board="px4io_2.4" />
<configure name="PERIODIC_FREQUENCY" value="200"/>
<module name="motor_mixing" />
<module name="radio_control" type="ppm">
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1" />
<define name="RADIO_KILL_SWITCH" value="RADIO_KILL" />
</module>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="200" />
</module>
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
<!-- Switch to Failsafe or to Autopilot on RC loss? -->
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO" />
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
<!-- Switch to Failsafe or to Manual on AP loss? -->
<define name="INTERMCU_LOST_CNT" value="100" />
<module name="intermcu" type="uart">
<configure name="INTERMCU_PORT" value="UART2" />
<configure name="INTERMCU_BAUD" value="B1500000" />
</module>
<!-- IO board / FBW MCU -->
<target name="fbw" board="px4io_2.4">
<configure name="PERIODIC_FREQUENCY" value="200"/>
<module name="motor_mixing" />
<module name="radio_control" type="ppm">
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1" />
<define name="RADIO_KILL_SWITCH" value="RADIO_KILL" />
</module>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="200" />
</module>
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
<!-- Switch to Failsafe or to Autopilot on RC loss? -->
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO" />
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
<!-- Switch to Failsafe or to Manual on AP loss? -->
<define name="INTERMCU_LOST_CNT" value="100" />
<module name="intermcu" type="uart">
<configure name="INTERMCU_PORT" value="UART2" />
<configure name="INTERMCU_BAUD" value="B1500000" />
</module>
</target>
</firmware>
<modules main_freq="PERIODIC_FREQUENCY">
+2 -1
View File
@@ -4,9 +4,9 @@
<firmware name="fixedwing">
<define name="USE_I2C1"/>
<configure name="PERIODIC_FREQUENCY" value="125"/>
<target name="ap" board="apogee_1.0_chibios">
<configure name="PERIODIC_FREQUENCY" value="125"/>
<module name="ins" type="float_invariant">
<configure name="AHRS_PROPAGATE_FREQUENCY" value="125"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="125"/>
@@ -19,6 +19,7 @@
<module name="ins" type="alt_float"/>
</target>
<target name="nps" board="pc">
<configure name="PERIODIC_FREQUENCY" value="125"/>
<!-- Note NPS needs the ppm type radio_control module -->
<module name="fdm" type="jsbsim"/>
<module name="ins" type="float_invariant">
@@ -30,9 +30,7 @@
<module name="imu" type="navstik"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="indi_simple"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="FALSE"/>
</module>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins" type="hff"/>
</firmware>
+41 -39
View File
@@ -22,51 +22,53 @@ The xml in master currently configures the LOGO600 as a pure model aircraft: mea
</description>
<firmware name="rotorcraft">
<target name="ap" board="lisa_mx_2.1"/>
<!-- Autopilot main MCU -->
<target name="ap" board="lisa_mx_2.1">
<module name="telemetry" type="xbee_api"/>
<module name="imu" type="lisa_mx_v2.1"/>
<module name="gps" type="ublox">
<configure name="GPS_PORT" value="UART4"/>
<configure name="GPS_BAUD" value="B115200"/>
</module>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins" type="hff"/>
<module name="guidance" type="indi"/>
<module name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_3"/>
</module>
<module name="intermcu" type="uart">
<define name="REMAP_UART3" value="TRUE"/>
</module>
<module name="heli" type="throttle_curve"/>
<module name="telemetry" type="xbee_api"/>
<module name="imu" type="lisa_mx_v2.1"/>
<module name="gps" type="ublox">
<configure name="GPS_PORT" value="UART4"/>
<configure name="GPS_BAUD" value="B115200"/>
</module>
<module name="gps" type="ubx_ucenter"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins" type="hff"/>
<module name="guidance" type="indi"/>
<module name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_3"/>
</module>
<module name="intermcu" type="uart">
<define name="REMAP_UART3" value="TRUE"/>
</module>
<module name="heli" type="throttle_curve"/>
<module name="geo_mag"/>
<module name="air_data"/>
<module name="logger_spi_link"/>
</firmware>
<module name="geo_mag"/>
<module name="air_data"/>
<module name="logger_spi_link"/>
</target>
<firmware name="rotorcraft">
<target name="fbw" board="lisa_mx_2.1"/>
<!-- Flight-by-wire MCU -->
<target name="fbw" board="lisa_mx_2.1">
<module name="radio_control" type="spektrum">
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
<define name="RADIO_CONTROL_SPEKTRUM_NO_SIGN" value="1"/>
</module>
<module name="radio_control" type="spektrum">
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
<define name="RADIO_CONTROL_SPEKTRUM_NO_SIGN" value="1"/>
</module>
<module name="actuators" type="spektrum">
<configure name="ACTUATORS_SPEKTRUM_DEV2" value="UART6"/>
</module>
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE"/><!-- Switch to Failsafe or to Autopilot on RC loss? -->
<!--define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO"/--><!-- Switch to AUTO2 with a working autopilot on RC loss? Warning: beware of fly-away: program a GeoFence. beware: AP can ARM the FBW: airframe is dangerous at all times.-->
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_FAILSAFE"/><!-- Behave as a model aircraft: failsafe on RC lost. -->
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_MANUAL"/><!-- Switch to Failsafe or to Manual on AP loss? -->
<module name="actuators" type="spektrum">
<configure name="ACTUATORS_SPEKTRUM_DEV2" value="UART6"/>
</module>
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE"/><!-- Switch to Failsafe or to Autopilot on RC loss? -->
<!--define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO"/--><!-- Switch to AUTO2 with a working autopilot on RC loss? Warning: beware of fly-away: program a GeoFence. beware: AP can ARM the FBW: airframe is dangerous at all times.-->
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_FAILSAFE"/><!-- Behave as a model aircraft: failsafe on RC lost. -->
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_MANUAL"/><!-- Switch to Failsafe or to Manual on AP loss? -->
<module name="intermcu" type="uart">
<define name="REMAP_UART3" value="TRUE"/>
</module>
<module name="intermcu" type="uart">
<define name="REMAP_UART3" value="TRUE"/>
</module>
</target>
</firmware>
<servos driver="Spektrum">
+1 -1
View File
@@ -650,7 +650,7 @@ void fit_linear_model_prior(float *targets, int D, float (*samples)[D], uint16_t
MAKE_MATRIX_PTR(AATAA, _AATAA, D_1);
float _PRIOR[D_1][D_1];
MAKE_MATRIX_PTR(PRIOR, _PRIOR, D_1);
for(int d = 0; d < D; d++) {
for(d = 0; d < D; d++) {
PRIOR[d][d] = priors[d];
}
if(use_bias) {
@@ -121,11 +121,11 @@ static const struct can_instance can2 = {&CAND2, 12};
* from abort mode.
* See section 22.7.7 on the STM32 reference manual.
*/
static const CANConfig cancfg_lb = {
CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP,
CAN_BTR_LBKM | CAN_BTR_SJW(0) | CAN_BTR_TS2(1) |
CAN_BTR_TS1(8) | CAN_BTR_BRP(6)
};
// static const CANConfig cancfg_lb = {
// CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP,
// CAN_BTR_LBKM | CAN_BTR_SJW(0) | CAN_BTR_TS2(1) |
// CAN_BTR_TS1(8) | CAN_BTR_BRP(6)
// };
/*
* Normal mode, see if we can ping each other