In phases add all OUAS flyable airframes (#2629)

* In phases add all OUAS flyable airframes

* on requaest added separate ac file without conf in name

Co-authored-by: Open UAS <noreply@openuas.org>
This commit is contained in:
OpenUAS
2020-12-17 17:20:02 +01:00
committed by GitHub
parent f98a7ffdd4
commit f1ca529e78
31 changed files with 12581 additions and 1163 deletions
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,354 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Crazyflie_2_1">
<description>
+ Airframe a Bitcraze crazyflie 2.1
+ Model: Crazyfly v2.1 in original configuration
+ Autopilot: Defailt FMU 2.1
+ GNSS uBlox CAM M8Q
+ MAG External HMC5983 on GNSS device
+ ESC: Default ESC
+ RCRX: Via datalink
+ TELEMETRY: Via default chip
+ CURRENT: None
+ RANGER: Combined on Flowdeck
+ MOTOR: Default brushed
+ PROP: Default
NOTES:
Has Flowdeck with ranger and GPS and Magneto all on I2C
</description>
<firmware name="rotorcraft">
<configure name="PERIODIC_FREQUENCY" value="1000"/>
<configure name="RTOS_DEBUG" value="0"/>
<target name="ap" board="crazyflie_2.1">
<module name="geo_mag"/>
<!-- <module name="gps" type="datalink"/>--> <!-- for motive system -->
<module name="gps" type="ubx_i2c">
<configure name="GPS_UBX_I2C_DEV" value="i2c1"/>
</module>
<module name="syslink_dl"/>
<module name="opticflow" type="pmw3901">
<configure name="OPTICFLOW_PMW3901_SPI_DEV" value="spi1"/>
<define name="SENSOR_SYNC_SEND_OPTICFLOW_PMW3901"/>
<define name="PMW3901_SPI_CDIV" value="SPIDiv32"/>
</module>
</target>
<target name="nps" board="pc">
<module name="gps" type="ublox"/>
<module name="fdm" type="jsbsim"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm"/>
<module name="radio_control" type="datalink">
</module>
<module name="telemetry" type="transparent"/>
<module name="imu" type="bmi088_i2c">
<configure name="IMU_BMI088_I2C_DEV" value="i2c3"/>
<define name="IMU_BMI088_GYRO_I2C_ADDR" value="BMI088_GYRO_ADDR_ALT"/>
<define name="IMU_BMI088_Y_SIGN" value="-1"/>
<define name="IMU_BMI088_Z_SIGN" value="-1"/>
</module>
<module name="stabilization" type="int_quat"/>
<!--module name="stabilization" type="indi_simple"/-->
<module name="ahrs" type="madgwick">
<configure name="AHRS_PROPAGATE_FREQUENCY" value="1000"/>
<!--configure name="USE_MAGNETOMETER" value="FALSE"/-->
<define name="AHRS_FC_MAG_ID" value="MAG_HMC58XX_SENDER_ID"/>
</module>
<module name="ins" type="extended"/>
<!--<module name="sys_mon"/>-->
<module name="air_data"/>
<module name="baro_bmp3">
<configure name="BMP3_I2C_DEV" value="i2c3"/>
<define name="AIR_DATA_BARO_ABS_ID" value="BARO_BMP3_SENDER_ID"/>
<define name="BMP3_SLAVE_ADDR" value="BMP3_I2C_ADDR_ALT"/>
</module>
<module name="mag" type="hmc58xx">
<!-- <define name="MAG_TO_IMU_THETA" value="2" unit="deg"/>-->
<configure name="MAG_HMC58XX_I2C_DEV" value="i2c1"/>
<!--<define name="MODULE_HMC58XX_SYNC_SEND" value="TRUE"/>--><!-- temporary for debugging external magneto and setup orientation sign and Body to Magneto angles-->
<define name="MODULE_HMC58XX_UPDATE_AHRS" value="TRUE"/> <!-- When all calib and works to TRUE -->
<define name="HMC58XX_CHAN_X" value="1"/>
<define name="HMC58XX_CHAN_Y" value="0"/>
<define name="HMC58XX_CHAN_Z" value="2"/>
<define name="HMC58XX_CHAN_X_SIGN" value="-"/>
<define name="HMC58XX_CHAN_Y_SIGN" value="+"/>
<define name="HMC58XX_CHAN_Z_SIGN" value="+"/>
</module>
<module name="cf_deck" type="multi_ranger"/>
<module name="sonar" type="vl53l1x">
<define name="SENSOR_SYNC_SEND_SONAR"/><!-- debug only TODO: disable if all validated -->
</module>
<define name="NO_GPS_NEEDED_FOR_NAV" value="FALSE"/> <!-- set to false later -->
<module name="traffic_info"/>
</firmware>
<!-- Rotation between sensor frame and IMU frame of this airframe external magnetometer -->
<!--If you build in your GPS where the MAGNETOMETER resides on the board
not alligned with the Accelo/Gyro axis or the main IMU on flight controller then set these values-->
<!--<section name="MAG_HMC" prefix="HMC58XX_">
<define name="MAG_TO_IMU_PHI" value="0.0"/>
<define name="MAG_TO_IMU_THETA" value="0.0"/>
<define name="MAG_TO_IMU_PSI" value="0.0"/>
</section>-->
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<servos driver="Pwm">
<servo name="FRONT_LEFT" no="4" min="0" neutral="20" max="255"/>
<servo name="FRONT_RIGHT" no="1" min="0" neutral="20" max="255"/>
<servo name="BACK_RIGHT" no="2" min="0" neutral="20" max="255"/>
<servo name="BACK_LEFT" no="3" min="0" neutral="20" max="255"/>
</servos>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot.motors_on,FALSE,values)"/>
<set servo="FRONT_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="FRONT_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BACK_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BACK_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_">
<!--TODO: calibrate-->
<define name="ACCEL_X_NEUTRAL" value="-19"/>
<define name="ACCEL_Y_NEUTRAL" value="-12"/>
<define name="ACCEL_Z_NEUTRAL" value="58"/>
<define name="ACCEL_X_SENS" value="1.83754430011" integer="16"/>
<define name="ACCEL_Y_SENS" value="1.8445793586" integer="16"/>
<define name="ACCEL_Z_SENS" value="1.84794644385" integer="16"/>
<!-- TODO: The external HMC5883 mag calib on 2021xxxx -->
<define name="MAG_X_NEUTRAL" value="-179"/>
<define name="MAG_Y_NEUTRAL" value="-21"/>
<define name="MAG_Z_NEUTRAL" value="79"/>
<define name="MAG_X_SENS" value="4.17334785618" integer="16"/>
<define name="MAG_Y_SENS" value="3.98885954135" integer="16"/>
<define name="MAG_Z_SENS" value="4.40442339014" integer="16"/>
<!-- If using the external magnetometer on GPS -->
<!--<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="-1"/>
<define name="MAG_Z_SIGN" value="-1"/>-->
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<section name="AHRS" prefix="AHRS_">
<!-- Use GPS heading instead of magneto for time being -->
<define name="USE_GPS_HEADING" value="1"/>
<!-- Values used if no GNSS fix, on 3D fix is updated by geo_mag module -->
<!-- Better use the geo_mag module if you have a GNSS, else replace the values with your local magnetic field -->
<!--North, East and Vertical Components do: Normalize[{19738.7, 899.5, 44845.6}] -->
<!-- Local Magnetic field DE2020 -->
<define name="H_X" value="0.402784"/>
<define name="H_Y" value="0.018355"/>
<define name="H_Z" value="0.915111"/>
<define name="BIAS_UPDATE_HEADING_THRESHOLD" value="15.0"/> <!-- don't update gyro bias if heading deviation is above this threshold in degrees"-->
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0.0"/> <!-- unit m/s thus Don't update heading from GPS course if GPS ground speed is below is this threshold in m/s" -->
<!-- Some insights https://lists.nongnu.org/archive/html/paparazzi-devel/2013-10/msg00126.html -->
<define name="GRAVITY_HEURISTIC_FACTOR" value="0.0"/> <!-- Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. Set to 0 in case of vibrations -->
<define name="MAG_UPDATE_ALL_AXES" value="FALSE"/><!-- Since ot much pitch and roll angle at all -->
</section>
<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="1.5"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="DEADBAND_P" value="20"/>
<define name="DEADBAND_Q" value="20"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>
<define name="IGAIN_P" value="75"/>
<define name="IGAIN_Q" value="75"/>
<define name="IGAIN_R" value="50"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="25." unit="deg"/>
<define name="SP_MAX_THETA" value="25." unit="deg"/>
<define name="SP_MAX_R" value="70." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="250" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="300"/>
<define name="PHI_DGAIN" value="200"/>
<define name="PHI_IGAIN" value="100"/>
<define name="THETA_PGAIN" value="300"/>
<define name="THETA_DGAIN" value="200"/>
<define name="THETA_IGAIN" value="100"/>
<define name="PSI_PGAIN" value="400"/>
<define name="PSI_DGAIN" value="200"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="300"/>
<define name="THETA_DDGAIN" value="300"/>
<define name="PSI_DDGAIN" value="300"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.0034724f"/>
<define name="G1_Q" value="0.0052575f"/>
<define name="G1_R" value="-0.0015942f"/>
<define name="G2_R" value="-0.11281f"/>
<define name="FILTER_ROLL_RATE" value="FALSE"/>
<define name="FILTER_PITCH_RATE" value="FALSE"/>
<define name="FILTER_YAW_RATE" value="FALSE"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="3.57f"/>
<define name="REF_ERR_Q" value="3.57f"/>
<define name="REF_ERR_R" value="3.57f"/>
<define name="REF_RATE_P" value="14.0"/>
<define name="REF_RATE_Q" value="14.0"/>
<define name="REF_RATE_R" value="14.0"/>
<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="8.0f"/>
<define name="FILT_CUTOFF_R" value="8.0f"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.03149f"/>
<define name="ACT_DYN_Q" value="0.03149f"/>
<define name="ACT_DYN_R" value="0.03149f"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<!-- NOMINAL_HOVER_THROTTLE sets a fixed value instead of the adaptive estimation -->
<define name="NOMINAL_HOVER_THROTTLE" value="0.75"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="100"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MAX_BAT_CAPACITY" value="240" unit="mAh"/><!-- Default battery-->
<!-- <define name="MAX_BAT_CAPACITY" value="350" unit="mAh"/>--> <!-- 3rd party battery -->
<define name="MILLIAMP_AT_FULL_THROTTLE" value="300" unit="mA"/>
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="40" unit="mA"/>
<define name="CURRENT_ESTIMATION_NONLINEARITY" value="1.0"/>
<define name="MAX_BAT_LEVEL" value="4.2" unit="V"/> <!-- 1S lipo -->
<define name="LOW_BAT_LEVEL" value="3.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="3.3" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="3.0" unit="V"/>
<define name="MIN_BAT_LEVEL" value="2.9" unit="V"/>
</section>
<section name="MISC">
<define name="ARRIVED_AT_WAYPOINT" value="0.2" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="MAX_DIST_FROM_HOME*1.1+HOME_RADIUS" unit="m"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="5." unit="m"/>
<define name="CARROT" value="4." unit="s"/>
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="1.5"/>
<define name="DESCEND_VSPEED" value="-1.0"/>
</section>
<section name="GCS">
<define name="SPEECH_NAME" value="Crazy fly"/><!-- written differently on purpose for better spoken AC name -->
<define name="ALT_SHIFT_PLUS_PLUS" value="5"/>
<define name="ALT_SHIFT_PLUS" value="1"/>
<define name="ALT_SHIFT_MINUS" value="-1"/>
<define name="AC_ICON" value="quadrotor_xi"/>
</section>
</airframe>
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,496 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Goblin">
<description>
+ Airframe with the PX4 Pixracer flightcontroller hardware
+ Model: Durafly Goblin in original configuration
+ Autopilot: PX4FMU 4.0 in the form of a Pixracer v1.0 R15
+ Actuators: Regular metal gear servos
+ GNSS Ublox M8N GNSS
+ MAG External QMC Magnetometer on GNSS device
+ ESC: Default
+ RCRX: OpenRXSR Receiver
+ AIRSPEED: No airspeed
+ TELEMETRY: Si10xx Chip based with firmware allowing PPRZ RSSI
+ CURRENT: A standard 3DR PowerBrick clone sensor on the default analog ports
+ RANGER: MAXBOTICS MB1010, LV-MaxSonar-EZ1 Ultrasonic sensor analog, or via CTS PWM pin
+ MOTOR: Default
+ PROP: Default
NOTES:
+ Servo pins point to FRONT of airframe
+ AP is rotated sideways 90 degrees counterclockwise, so SDcard and USB to top
+ Engine battery voltage and current values via separate sensor
+ Servos and Sonar powered via BEC of ESC
+ AP via additional BEC
+ Telemetry via BEC on powerbrick
+ Flashing the firmware can be done via original PX4 bootloader...
Simple, USB cable in, upload.. voila PPRZ aircraft on a Pixracer...
+ A GNSS device with ANOTHER magneto on it is used, external...
+ Separate Aileron servo outputs pin for more differential options
</description>
<firmware name="fixedwing">
<target name="ap" board="px4fmu_4.0">
<configure name="CPU_LED" value="1"/>
<configure name="PERIODIC_FREQUENCY" value="512"/>
<!-- Not enabled ATM default should be good -->
<!--<define name="MPU9250_GYRO_RANGE" value="MPU60X0_GYRO_RANGE_2000"/>
<define name="MPU9250_ACCEL_RANGE" value="MPU60X0_ACCEL_RANGE_16G"/>
<define name="MPU9250_LOWPASS_FILTER" value="MPU60X0_DLPF_256HZ"/>
<define name="MPU9250_SMPLRT_DIV" value="3"/>-->
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="500"/>
<configure name="AHRS_MAG_CORRECT_FREQUENCY" value="50"/>
<configure name="NAVIGATION_FREQUENCY" value="16"/>
<configure name="CONTROL_FREQUENCY" value="120"/>
<configure name="TELEMETRY_FREQUENCY" value="60"/>
<configure name="MODULES_FREQUENCY" value="512"/>
<module name="imu" type="mpu9250_spi">
<configure name="IMU_MPU9250_SPI_DEV" value="spi1"/>
<configure name="IMU_MPU9250_SPI_SLAVE_IDX" value="SPI_SLAVE2"/>
<define name="IMU_MPU9250_READ_MAG" value="FALSE"/>
<!-- To be able to set AP IMU orientaion when AP is mounted rotated, body to IMU should also work -->
<define name="IMU_MPU9250_CHAN_X" value="0"/>
<define name="IMU_MPU9250_CHAN_Y" value="2"/>
<define name="IMU_MPU9250_CHAN_Z" value="1"/>
<define name="IMU_MPU9250_X_SIGN" value="-1"/>
<define name="IMU_MPU9250_Y_SIGN" value="+1"/>
<define name="IMU_MPU9250_Z_SIGN" value="+1"/>
</module>
<configure name="USE_ADC_2" value="TRUE"/>
<define name="ADC_CHANNEL_VSUPPLY" value="ADC_2"/>
<module name="current_sensor">
<configure name="USE_ADC_3" value="TRUE"/>
<configure name="ADC_CURRENT_SENSOR" value="ADC_3"/>
<define name="CURRENT_ESTIMATION_NONLINEARITY" value="1.1"/>
</module>
<module name="sonar_adc">
<configure name="USE_ADC_4" value="TRUE"/>
<configure name="ADC_SONAR" value="ADC_4"/>
<define name="SENSOR_SYNC_SEND_SONAR"/>
</module>
<module name="radio_control" type="sbus">
<define name="RADIO_CONTROL_NB_CHANNEL" value="16"/>
<define name="RADIO_GEAR" value="RADIO_AUX2"/>
<define name="RADIO_FLAP" value="RADIO_AUX3"/>
</module>
<!--<module name="telemetry" type="transparent_usb"/>-->
<module name="telemetry" type="transparent">
<configure name="MODEM_PORT" value="UART3"/><!-- Telem2 on pixracer -->
<configure name="MODEM_BAUD" value="B57600"/>
</module>
</target>
<target name="sim" board="pc">
<define name="INS_BARO_ID" value="BARO_SIM_SENDER_ID"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<module name="radio_control" type="ppm"/>
<define name="RADIO_GEAR" value="RADIO_AUX2"/>
<define name="RADIO_FLAP" value="RADIO_AUX3"/>
<!--<define name="RADIO_CONTROL_NB_CHANNEL" value="8"/>-->
<module name="telemetry" type="transparent"/>
<!--<module name="imu" type="aspirin_v2.2"/>-->
<!--<module name="ahrs" type="float_dcm"/>
<module name="ins" type="alt_float"/>-->
<module name="baro_sim"/>
</target>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="autopilot_motors_on" value="TRUE"/>
<configure name="USE_BARO_BOARD" value="TRUE"/>
<define name="USE_BARO_MEDIAN_FILTER"/>
<define name="BAT_CHECKER_DELAY" value="80"/>
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="410"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
<define name="USE_AHRS_GPS_ACCELERATIONS" value="TRUE"/>
<!--<define name="USE_MAGNETOMETER_ONGROUND" value="FALSE"/>-->
<!--<configure name="USE_MAGNETOMETER" value="TRUE"/>-->
<module name="gps" type="ublox">
<configure name="GPS_BAUD" value="B460800"/>
</module>
<module name="ahrs" type="float_cmpl_quat">
<configure name="AHRS_ALIGNER_LED" value="2"/>
<define name="AHRS_GPS_SPEED_IN_NEGATIVE_Z_DIRECTION" value="FALSE"/>
<define name="AHRS_HEADING_UPDATE_GPS_MIN_SPEED" value="3.0"/>
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="0.0"/>
</module>
<module name="ins" type="alt_float">
<define name="SONAR_COMPENSATE_ROTATION" value="TRUE"/>
</module>
<module name="control" type="new"/>
<module name="navigation"/>
<module name="send_imu_mag_current"/>
<module name="baro_ms5611_spi">
<configure name="MS5611_SPI_DEV" value="spi1"/>
<configure name="MS5611_SLAVE_IDX" value="SPI_SLAVE3"/>
</module>
<module name="geo_mag"/>
<module name="nav" type="line"/>
<module name="nav" type="line_border"/>
<module name="nav" type="line_osam"/>
<module name="nav" type="survey_polygon">
<define name="POLYSURVEY_DEFAULT_DISTANCE" value="40"/>
</module>
<module name="nav" type="survey_poly_osam"/>
<module name="nav" type="smooth"/>
<module name="nav" type="vertical_raster"/>
<module name="nav" type="flower"/>
<!-- module name="nav" type="catapult"/> -->
<module name="mag" type="hmc58xx">
<configure name="MAG_HMC58XX_I2C_DEV" value="i2c1"/>
<define name="MODULE_HMC58XX_SYNC_SEND" value="TRUE"/>
<define name="MODULE_HMC58XX_UPDATE_AHRS" value="TRUE"/>
<define name="HMC58XX_CHAN_X" value="1"/>
<define name="HMC58XX_CHAN_Y" value="0"/>
<define name="HMC58XX_CHAN_Z" value="2"/>
<define name="HMC58XX_CHAN_X_SIGN" value="-"/>
<define name="HMC58XX_CHAN_Y_SIGN" value="+"/>
<define name="HMC58XX_CHAN_Z_SIGN" value="+"/>
</module>
<module name="photogrammetry_calculator">
</module>
<module name="traffic_info">
</module>
<module name="tcas">
</module>
</firmware>
<servos>
<servo name="S_THROTTLE" no="0" min="1100" neutral="1110" max="1900"/>
<servo name="S_AILERON_LEFT" no="1" min="1900" neutral="1500" max="1100"/>
<servo name="S_ELEVATOR" no="2" min="1900" neutral="1500" max="1100"/>
<servo name="S_AILERON_RIGHT" no="4" min="1900" neutral="1500" max="1100"/>
</servos>
<section name="ServoPositions">
<!-- Just name a few, value can be used in e.g. flightplan -->
<define name="LANDINGGEAR_EXTEND" value="-MAX_PPRZ"/>
<define name="LANDINGGEAR_RETRACT" value="MAX_PPRZ"/>
<define name="FLAP_FULL" value="-MAX_PPRZ"/>
<define name="FLAP_HALF" value="-MAX_PPRZ/2"/>
<define name="FLAP_NONE" value="0"/>
<define name="BEACON_ROTATE" value="MAX_PPRZ"/>
<define name="BEACON_FLASH" value="0"/>
<define name="BEACON_OFF" value="-MAX_PPRZ"/>
<define name="SERVO_BRAKE_FULL" value="-MAX_PPRZ"/>
<define name="SERVO_HATCH_OPEN" value="0"/>
<define name="SERVO_HATCH_CLOSED" value="-9600"/>
<define name="AirbrakesOff()" value="(ap_state->commands[COMMAND_BRAKE]=0)"/>
<define name="AirbrakesOn()" value="(ap_state->commands[COMMAND_BRAKE]=SERVO_BRAKE_FULL)"/>
<!--<define name="Fly()" value="(ap_state->commands[COMMAND_FORCECRASH]=0)" />-->
<!--<define name="ForceCrash()" value="(ap_state->commands[COMMAND_FORCECRASH]=9600)" />-->
<define name="ThrottleHigh()" value="(ap_state->commands[COMMAND_THROTTLE]>9600/2)"/>
<define name="SPOILERON_BRAKE_FULL" value="-MAX_PPRZ"/>
<define name="FLAPERON_BRAKE_FULL" value="MAX_PPRZ"/>
</section>
<section name="MIXER">
<define name="ASSIST_ROLL_WITH_RUDDER" value="0.0"/>
<define name="AILERON_DIFF" value="0.3"/>
<define name="BRAKE" value="0.3"/>
</section>
<command_laws>
<set servo="S_THROTTLE" value="@THROTTLE"/>
<set servo="S_AILERON_LEFT" value="@ROLL+(0.1*SPOILERON_BRAKE_FULL)"/>
<set servo="S_AILERON_RIGHT" value="@ROLL+(0.1*SPOILERON_BRAKE_FULL)"/>
<set servo="S_ELEVATOR" value="@PITCH+(0.0*SPOILERON_BRAKE_FULL)"/>
</command_laws>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
<set command="GEAR" value="@AUX1"/>
<set command="FLAP" value="@AUX2"/>
</rc_commands>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="5"/>
<axis name="PITCH" failsafe_value="-6"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="GEAR" failsafe_value="0"/>
<axis name="FLAP" failsafe_value="0"/>
</commands>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="60" unit="deg"/>
<define name="MAX_PITCH" value="55" unit="deg"/>
</section>
<section name="TRIM" prefix="COMMAND_">
<define name="ROLL_TRIM" value="0.0"/>
<define name="PITCH_TRIM" value="0.0"/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.0" unit="%"/>
<define name="DEFAULT_GEAR" value="1100"/>
<define name="DEFAULT_ROLL" value="8.0" unit="deg"/>
<define name="DEFAULT_PITCH" value="-4.0" unit="deg"/>
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="MAX_DIST_FROM_HOME*1.3+HOME_RADIUS" unit="m"/>
<define name="DELAY_WITHOUT_GPS" value="4" unit="s"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- <define name="GYRO_P_SENS" value=" 1.01" integer="16"/> -->
<!-- <define name="GYRO_Q_SENS" value=" 1.01" integer="16"/> -->
<!-- <define name="GYRO_R_SENS" value=" 1.01" integer="16"/> -->
<!-- <define name="GYRO_P_NEUTRAL" value="0"/> -->
<!-- <define name="GYRO_Q_NEUTRAL" value="0"/> -->
<!-- <define name="GYRO_R_NEUTRAL" value="0"/> -->
<!-- TODO: calibrate ASAP -->
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<define name="ACCEL_X_SENS" value="2.44717990354" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.41787653186" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.4425224747" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="0" unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0" unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0.0" unit="deg"/>
<define name="MAG_X_NEUTRAL" value="7"/>
<define name="MAG_Y_NEUTRAL" value="76"/>
<define name="MAG_Z_NEUTRAL" value="133"/>
<define name="MAG_X_SENS" value="3.82579687604" integer="16"/>
<define name="MAG_Y_SENS" value="3.6213651898" integer="16"/>
<define name="MAG_Z_SENS" value="4.01635370187" integer="16"/>
<!-- TODO: Calibrate -->
<define name="MAG_X_CURRENT_COEF" value="-0.677655963532"/>
<define name="MAG_Y_CURRENT_COEF" value="-7.38678178538"/>
<define name="MAG_Z_CURRENT_COEF" value="-5.02116042576"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.402784"/>
<define name="H_Y" value="0.018355"/>
<define name="H_Z" value="0.915111"/>
</section>
<section name="INS">
<define name="INS_BODY_TO_GPS_X" value="0.20" unit="m"/>
<define name="INS_BODY_TO_GPS_Y" value="0.0" unit="m"/>
<define name="INS_BODY_TO_GPS_Z" value="0.10" unit="m"/>
<define name="ROLL_NEUTRAL_DEFAULT" value="0." unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="0." unit="deg"/>
<define name="USE_GPS_ALT" value="TRUE"/>
<!--<define name="USE_GPS_ALT_SPEED" value="FALSE"/>-->
<define name="VFF_R_GPS" value="0.01"/>
<!--<define name="VFF_VZ_R_GPS" value="0.2"/>-->
<define name="INS_SONAR_MAX_RANGE" value="6.0"/>
<define name="INS_SONAR_MIN_RANGE" value="0.15"/>
</section>
<section name="SONAR" prefix="SONAR_">
<define name="MEDIAN_SIZE" value="15"/>
<!--<define name="USE_ADC_FILTER" value="TRUE"/>-->
<define name="SCALE" value="0.0025375" integer="16"/>
<define name="OFFSET" value="90.0"/>
<define name="MAX_RANGE" value="6.0" unit="m"/>
<define name="MIN_RANGE" value="0.15" unit="m"/>
</section>
<section name="AGL" prefix="AGL_DIST_SONAR_">
<define name="ID" value="ABI_BROADCAST"/>
<define name="MAX_RANGE" value="6." unit="m"/>
<define name="MIN_RANGE" value="0.20" unit="m"/>
<!--<define name="FILTER" value="0.5"/>-->
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.8"/>
<define name="COURSE_DGAIN" value="0.02"/>
<define name="COURSE_TAU" value="0.7"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="0.99"/>
<define name="ROLL_MAX_SETPOINT" value="35" unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="40" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-40" unit="deg"/>
<define name="PITCH_PGAIN" value="6000"/>
<define name="PITCH_DGAIN" value="80"/>
<define name="PITCH_IGAIN" value="2"/>
<define name="PITCH_KFFA" value="20."/>
<define name="PITCH_KFFD" value="4."/>
<define name="ELEVATOR_OF_ROLL" value="1550" unit="PPRZ_MAX"/>
<define name="ROLL_SLEW" value="0.1"/>
<define name="ROLL_ATTITUDE_GAIN" value="9000."/>
<define name="ROLL_RATE_GAIN" value="400."/>
<define name="ROLL_IGAIN" value="100."/>
<define name="ROLL_KFFA" value="100"/>
<define name="ROLL_KFFD" value="10"/>
<define name="AILERON_OF_THROTTLE" value="0.0"/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<define name="POWER_CTL_BAT_NOMINAL" value="11.7" unit="volt"/>
<define name="ALTITUDE_PGAIN" value="0.1"/>
<define name="AUTO_CLIMB_LIMIT" value="1.5*V_CTL_ALTITUDE_MAX_CLIMB"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.45" unit="%"/>
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.6" unit="%"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85" unit="%"/>
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1000" unit="pprz_t"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="-2000" unit="pprz_t"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.10" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.01" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.001"/>
<define name="AUTO_THROTTLE_DGAIN" value="0.001"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.01" unit="rad/(m/s)"/>
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_PITCH" value="0." unit="rad"/>
<define name="THROTTLE_SLEW_LIMITER" value="0.7" unit="m/s/s"/>
<define name="AUTO_AIRSPEED_SETPOINT" value="12.0" unit="m/s"/>
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0.07" unit="%/(m/s)"/>
<define name="AUTO_AIRSPEED_THROTTLE_DGAIN" value="0.06"/>
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0.002"/>
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.12" unit="degree/(m/s)"/>
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.001"/>
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.02"/>
<define name="AIRSPEED_MAX" value="18.0" unit="m/s"/>
<define name="AIRSPEED_MIN" value="7.0" unit="m/s"/>
<define name="PITCH_LOITER_TRIM" value="1.0" unit="deg"/>
<define name="PITCH_DASH_TRIM" value="0." unit="deg"/>
<define name="AUTO_GROUNDSPEED_SETPOINT" value="8.0" unit="m/s"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="0.7"/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0.3"/>
<define name="AIRSPEED_PGAIN" value="0.15"/>
<define name="AUTO_AIRSPEED_PGAIN" value="0.18" unit="%/(m/s)"/>
<define name="AUTO_AIRSPEED_IGAIN" value="0.2"/>
<define name="ALTITUDE_MAX_CLIMB" value="4.0" unit="m/s"/>
<define name="MAX_ACCELERATION" value="3.0" unit="G"/>
<define name="AUTO_PITCH_PGAIN" value="0.015"/>
<define name="AUTO_PITCH_DGAIN" value="0.01"/>
<define name="AUTO_PITCH_IGAIN" value="0.001"/>
<!-- <define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.14"/> -->
<define name="AUTO_PITCH_MAX_PITCH" value="30" unit="deg"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-30" unit="deg"/>
<define name="GLIDE_RATIO" value="6."/>
</section>
<section name="BAT">
<define name="MAX_BAT_CAPACITY" value="1300" unit="mAh"/>
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="300" unit="mA"/>
<define name="MILLIAMP_AT_FULL_THROTTLE" value="30000" unit="mA"/>
<define name="MAX_BAT_LEVEL" value="16.8" unit="V"/>
<define name="LOW_BAT_LEVEL" value="14.0" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="13.2" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="12.0" unit="V"/>
</section>
<section name="MISC">
<!-- All for use with default motor and propeller -->
<define name="MINIMUM_AIRSPEED" value="13." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="20." unit="m/s"/>
<define name="MAXIMUM_AIRSPEED" value="54." unit="m/s"/>
<define name="CLIMB_AIRSPEED" value="14." unit="m/s"/>
<define name="TRACKING_AIRSPEED" value="35." unit="m/s"/>
<define name="GLIDE_AIRSPEED" value="13" unit="m/s"/>
<define name="STALL_AIRSPEED" value="11." unit="m/s"/>
<define name="RACE_AIRSPEED" value="50." unit="m/s"/>
<define name="MIN_SPEED_FOR_TAKEOFF" value="12." unit="m/s"/>
<define name="AIRSPEED_SETPOINT_SLEW" value="0.3" unit="m/s/s"/>
<define name="TAKEOFF_PITCH_ANGLE" value="35" unit="deg"/>
<define name="FLARE_PITCH_ANGLE" value="6" unit="deg"/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0.0" unit="deg"/>
<define name="KILL_MODE_DISTANCE" value="MAX_DIST_FROM_HOME*1.3+HOME_RADIUS" unit="m"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="120." unit="m"/>
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="LANDING_CIRCLE_RADIUS" value="100." unit="m"/>
<define name="MIN_CIRCLE_RADIUS" value="100." unit="m"/>
<define name="CARROT" value="6." unit="s"/>
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
<define name="RC_LOST_MODE" value="AP_MODE_AUTO2"/>
</section>
<section name="PHOTOGRAMMETRY" prefix="PHOTOGRAMMETRY_">
<define name="FOCAL_LENGTH" value="2.5" unit="mm"/>
<define name="SENSOR_WIDTH" value="2.304" unit="mm"/>
<define name="SENSOR_HEIGHT" value="1.728" unit="mm"/>
<define name="PIXELS_WIDTH" value="320"/>
<!-- Photogrammetry Parameters. Can also be defined in a flightplan instead
<define name="OVERLAP" value="0.3" unit="%"/>
<define name="SIDELAP" value="0.2" unit="%"/>
<define name="RESOLUTION" value="50" unit="mm pixel projection"/>
-->
<!-- note: only for PHOTOGRAMMETRY-->
<define name="HEIGHT_MIN" value="50." unit="m"/>
<define name="HEIGHT_MAX" value="120." unit="m"/>
<define name="RADIUS_MIN" value="70." unit="m"/>
</section>
<!-- Can as well be your handlaunch, a.k.a. the human catapult ;) -->
<section name="CATAPULT" prefix="NAV_CATAPULT_">
<define name="MOTOR_DELAY" value="0." unit="s"/>
<define name="HEADING_DELAY" value="3.0" unit="s"/>
<define name="ACCELERATION_THRESHOLD" value="1.1"/>
<define name="INITIAL_PITCH" value="20.0" unit="deg"/>
<define name="INITIAL_THROTTLE" value="1.0"/>
</section>
<section name="GLS_APPROACH" prefix="APP_">
<define name="DISTANCE_AF_SD" value="30" unit="m"/>
<define name="ANGLE" value="2" unit="deg"/>
<define name="INTERCEPT_AF_SD" value="80" unit="m"/>
<!--<define name="INTERCEPT_RATE" value="0.624" unit="m/s/s"/>-->
<define name="TARGET_SPEED" value="11.0" unit="m/s"/>
</section>
<section name="GCS">
<define name="SPEECH_NAME" value="Goblin"/>
<define name="AC_ICON" value="fixedwing"/>
<define name="ALT_SHIFT_PLUS_PLUS" value="50"/>
<define name="ALT_SHIFT_PLUS" value="10"/>
<define name="ALT_SHIFT_MINUS" value="-10"/>
</section>
<section name="SIMU">
<define name="JSBSIM_LAUNCHSPEED" value="10.0"/>
<define name="WEIGHT" value="1."/>
<define name="JSBSIM_IR_ROLL_NEUTRAL" value="RadOfDeg(0.)"/>
<define name="JSBSIM_IR_PITCH_NEUTRAL" value="RadOfDeg(0.)"/>
<define name="YAW_RESPONSE_FACTOR" value=".9"/>
<define name="PITCH_RESPONSE_FACTOR" value="1."/>
<define name="ROLL_RESPONSE_FACTOR" value="20."/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="JSBSIM_MODEL" value="Malolo1" type="string"/>
<define name="COMMANDS_NB" value="4"/>
<define name="ACTUATOR_NAMES" value="throttle-cmd-norm, aileron-cmd-norm, elevator-cmd-norm, rudder-cmd-norm" type="string[]"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<define name="JS_AXIS_MODE" value="4"/>
<define name="BYPASS_AHRS" value="TRUE"/>
<define name="BYPASS_INS" value="TRUE"/>
<define name="JSBSIM_LAUNCHSPEED" value="10"/>
</section>
</airframe>
@@ -0,0 +1,495 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Trashcan">
<description>
* Airframe for the regular "Trashcan" Quadrotor frame equipped with to validate all onboard functionally.
+ Autopilot: Default Crazybee F4 Pro STM32F4 and all that comes with it
+ Actuators: Default onboard Blheli S ESCs see http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM
+ Telemetry: Default WiFi Via ESP8266 see
+ RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out on LED pin
NOTES:
+ All set to expect flying on 2s LiPo battery, 1s LiPo battery possible but no gains set or autocompensation (yet..)
+ Removed Camera and Video TX to be replaced by a JeVois (www.jevois.org) camera on Uart1
+ RC control also possible via wifi telemetry module
+ Vison: added a JeVois on UART1 TX/RX
+ RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out,
+ Wifi telemetry module also allows RC
WIP:
+ GPS: uBlox SAM M8Q with Magneto n Baro GNSS
+ FPV RC only target to learn to recover your Drone in case of AP mishap
</description>
<firmware name="rotorcraft">
<target name="ap" board="crazybee_f4_1.0">
<configure name="NO_LUFTBOOT" value="1"/>
<configure name="USE_BARO_BOARD" value="FALSE"/>
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/> <!-- Starts in KILL, but can now switch to NAV -->
<define name="AHRS_ALIGNER_SAMPLES_NB" value="1200"/> <!--When fidly plugging in a battery, aircraft kind of wobbly, now avoid messing up the aligner this way -->
<!-- <define name="LOW_NOISE_THRESHOLD" value="30000"/>-->
<!-- <define name="LOW_NOISE_TIME" value="10"/>-->
<!-- 2 kHz periodic -->
<configure name="PERIODIC_FREQUENCY" value="2048"/>
<define name="HFF_PRESCALER" value="40"/><!-- FIXME: determine fully correct one-->
<define name="AHRS_PROPAGATE_FREQUENCY" value="2000"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="2000"/>
<configure name="AHRS_MAG_CORRECT_FREQUENCY" value="50"/> <!-- 75 or 160 max -->
<!-- set Gyro/Accel output rate to 2kHz at 8kHz internal sampling -->
<define name="IMU_MPU_LOWPASS_FILTER" value="MPU60X0_DLPF_256HZ"/><!--This sets the internal sample rate to 8KHz. -->
<define name="IMU_MPU_ACCEL_LOWPASS_FILTER" value="MPU60X0_DLPF_ACC_44HZ"/><!-- FIXME check value -->
<define name="IMU_MPU_SMPLRT_DIV" value="3"/> <!-- for 1khz periodic IMU_MPU_SMPLRT_DIV=7 sr = gr(8) /1+IMU_MPU_SMPLRT_DIV (1+7/8=1khz-->
<configure name="NAVIGATION_FREQUENCY" value="16"/>
<configure name="CONTROL_FREQUENCY" value="2000"/>
<configure name="TELEMETRY_FREQUENCY" value="120"/>
<configure name="MODULES_FREQUENCY" value="2048"/>
<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/><!-- handy with the short flight time between tuning sets, not tested if it works yet, this board we have 16kb reserved -->
<define name="BAT_CHECKER_DELAY" value="70"/> <!-- to avoid bat low spike detection when strong up movement withch draws short sudden power-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="90"/> <!-- in 10/s seconds-->
</target>
<module name="radio_control" type="cc2500_frsky">
<define name="CC2500_RX_LED" value="LED_2"/>
<define name="CC2500_BIND_BUTTON" value="BIND_BUTTON"/>
<!--<define name="CC2500_AUTOBIND" value="TRUE"/>-->
<define name="CC2500_TELEMETRY_SENSORS" value="SENSOR_NONE"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_AUX1"/>
</module>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="480"/>
</module>
<module name="dfu_command"/>
<!-- <module name="telemetry" type="transparent_usb"/> -->
<module name="telemetry" type="transparent_frsky_x"/>
<module name="imu" type="mpu6000">
<configure name="IMU_MPU_SPI_DEV" value="spi1"/>
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE0"/>
<!-- define name="ICM20608"/> --> <!-- Not used atm -->
<!-- To be able (for now) to set AP IMU orientaion -->
<define name="IMU_GYRO_P_SIGN" value="1"/>
<define name="IMU_GYRO_Q_SIGN" value="-1"/>
<define name="IMU_GYRO_R_SIGN" value="-1"/>
<define name="IMU_ACCEL_X_SIGN" value="1"/>
<define name="IMU_ACCEL_Y_SIGN" value="-1"/>
<define name="IMU_ACCEL_Z_SIGN" value="-1"/>
</module>
<!-- not all are tested or tuned -->
<!-- <module name="stabilization" type="rate"/>--><!-- not working yet..)-->
<!-- <module name="stabilization" type="rate_indi"/> -->
<module name="stabilization" type="int_quat"/>
<!--<module name="stabilization" type="float_quat"/>-->
<!-- <module name="stabilization" type="indi_simple" /> -->
<!-- <module name="stabilization" type="indi" /> -->
<module name="ins" type="extended"/>
<module name="osd_max7456">
<configure name="MAX7456_SPI_DEV" value="SPI2"/>
<configure name="MAX7456_SLAVE_IDX" value="SPI_SLAVE1"/>
<!--<define name="OSD_USE_EXTERNAL_SPRINTF" value="0" />-->
<define name="USE_MATEK_TYPE_OSD_CHIP" value="FALSE" />
<!--<define name="USE_PAL_FOR_OSD_VIDEO" value="TRUE" />-->
<!--<define name="BARO_ALTITUDE_VAR" value="baro_alt" />-->
</module>
<!-- <module name="filter_1euro_imu"> -->
<!--<define name="IMU_F1E_ID" value="30"/>-->
<!--<define name="AHRS_ICQ_IMU_ID" value="F1E_IMU_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="F1E_IMU_ID"/>-->
<!-- </module> -->
<!--module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
</module-->
<module name="ahrs" type="float_cmpl_quat">
<!--<define name="AHRS_ICQ_IMU_ID" value="IMU_F1E_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="IMU_F1E_ID"/>-->
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/> <!-- True for Optitrack false for real magneto-->
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="TRUE"/> <!-- for dronerace -->
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="0"/> <!-- TODO: determine best... Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. -->
<define name="AHRS_PROPAGATE_LOW_PASS_RATES" value="FALSE"/> <!-- apply a low pass filter on rotational velocity"-->
</module>
<!-- WIP for setting values e.g. P/D roll tune via RC Tranmitter, need a new setting file WIP -->
<!--<module name="settings" type="rc"/>-->
<!-- only for... dronerace... -->
<!--
<module name="dronerace"/>
-->
<!-- Not yet used ATM
<module name="jevois_mavlink">
<configure name="JEVOIS_UART" value="UART1"/>
<configure name="JEVOIS_BAUD" value="B115200"/>
</module>
-->
<module name="gps" type="datalink"/> <!-- using optitrack and natnet2ivy -->
<!-- No I2C bus yet... still need to find some good spot for I2C pins... except straigt on MCU solder blobs -->
<!--
<module name="gps" type="ublox">
<configure name="GPS_PORT" value="I2C"/>
</module>
-->
<!--<module name="geo_mag"/>
<<module name="air_data"/>-->
<!-- below temporary until measuerd and values set then disable it -->
<!-- <module name="send_imu_mag_current"/> -->
<!--
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm">
<define name="RADIO_CONTROL_NB_CHANNEL" value="8"/>
</module>
</target>
-->
<!-- <target name="FPV Racing" board="crazybee_f4_1.0">
WIP
For FPV setup only
No GPS
No Baro
No Magneto
Highest loop rate possible for board
Flip module
Module for OSD
Tuned for Race and ACRO
Try INDI full
</target>
-->
</firmware>
<servos driver="Pwm">
<servo name="FL" no="3" min="1000" neutral="1030" max="2000"/> <!-- maybe shorter on the cost of resolution... but low high differcnce MUST be bigger than 140-->
<servo name="FR" no="1" min="1000" neutral="1030" max="2000"/>
<servo name="BR" no="0" min="1000" neutral="1030" max="2000"/>
<servo name="BL" no="2" min="1000" neutral="1030" max="2000"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="REVERSE" value="TRUE"/>
<define name="TYPE" value="QUAD_X"/>
</section>
<!-- in case we need much more precise mixing use the table here instead of motor_mixing_run -->
<!-- section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section-->
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="FL" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="FR" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BR" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BL" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="FILTER_1EURO" prefix="FILTER_1EURO_">
<define name="ENABLED" value="FALSE"/> <!-- activate or not the filter by default -->
<define name="GYRO_MINCUTOFF" value="10."/> <!-- minimum cutoff freq for gyro signal -->
<define name="GYRO_BETA" value="0.1"/> <!-- adaptation coefficient for gyro signal -->
<define name="ACCEL_MINCUTOFF" value="0.1"/> <!-- minimum cutoff freq for accel signal -->
<define name="ACCEL_BETA" value="0.01"/> <!-- adaptation coefficient for accel signal -->
<!--<define name="FREQ" value="512"set fixed frequency, if not defined but INS/AHRS_PROPAGATE_FREQUENCY is defined it is used, otherwise autofreq is used-->
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
<!-- Tere is no MAG per default, but in case one adds one , make it correct -->
<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>
<!-- replace this with your own calibration -->
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="8.0" integer="16"/>
<define name="MAG_Y_SENS" value="8.0" integer="16"/>
<define name="MAG_Z_SENS" value="8.0" integer="16"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="2400." unit="deg/s"/>
<define name="SP_MAX_Q" value="2400." unit="deg/s"/>
<define name="SP_MAX_R" value="2400" unit="deg/s"/>
<define name="DEADBAND_P" value="10"/>
<define name="DEADBAND_Q" value="10"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="800"/>
<define name="GAIN_Q" value="800"/>
<define name="GAIN_R" value="700"/>
<define name="IGAIN_P" value="140"/>
<define name="IGAIN_Q" value="140"/>
<define name="IGAIN_R" value="90"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<define name="SP_MAX_PHI" value="30." unit="deg"/>
<define name="SP_MAX_THETA" value="30." unit="deg"/>
<define name="SP_MAX_R" value="120." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="80"/>
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<define name="PHI_PGAIN" value="185"/>
<define name="PHI_DGAIN" value="70"/>
<define name="PHI_IGAIN" value="1"/>
<define name="THETA_PGAIN" value="185"/>
<define name="THETA_DGAIN" value="70"/>
<define name="THETA_IGAIN" value="1"/>
<define name="PSI_PGAIN" value="350"/>
<define name="PSI_DGAIN" value="100"/>
<define name="PSI_IGAIN" value="3"/>
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</section>
<!-- when using stabilization type float_quat use ones below, not tuned yet! -->
<!--
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<define name="REF_OMEGA_P" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_P" value="{0.85}"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_Q" value="{0.85}"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="{RadOfDeg(250)}"/>
<define name="REF_ZETA_R" value="{0.85}"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<define name="PHI_PGAIN" value="{1000}"/>
<define name="PHI_DGAIN" value="{1000}"/>
<define name="PHI_IGAIN" value="{200}"/>
<define name="THETA_PGAIN" value="{1000}"/>
<define name="THETA_DGAIN" value="{1000}"/>
<define name="THETA_IGAIN" value="{200}"/>
<define name="PSI_PGAIN" value="{500}"/>
<define name="PSI_DGAIN" value="{500}"/>
<define name="PSI_IGAIN" value="{10}"/>
<define name="PHI_DGAIN_D" value="{100}"/>
<define name="THETA_DGAIN_D" value="{100}"/>
<define name="PSI_DGAIN_D" value="{100}"/>
<define name="PHI_DDGAIN" value="{300}"/>
<define name="THETA_DDGAIN" value="{300}"/>
<define name="PSI_DDGAIN" value="{300}"/>
</section>
-->
<!-- when using stabilization type indi use ones below, not tuned yet! -->
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.05"/>
<define name="G1_Q" value="0.025"/>
<define name="G1_R" value="0.0022"/>
<define name="G2_R" value="0.20"/>
<!-- For some airframes, e.g. Bebop2 we need to filter the roll rate due to the dampers -->
<define name="FILTER_ROLL_RATE" value="FALSE"/>
<define name="FILTER_PITCH_RATE" value="FALSE"/>
<define name="FILTER_YAW_RATE" value="FALSE"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="170.0"/>
<define name="REF_ERR_Q" value="600.0"/>
<define name="REF_ERR_R" value="600.0"/>
<define name="REF_RATE_P" value="14.3"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>
<!-- second order filter parameters -->
<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>
<define name="FILT_CUTOFF" value="5.0"/>
<define name="FILT_CUTOFF_P" value="5.0"/>
<!-- first order actuator dynamics (indi_simple) -->
<define name="ACT_DYN_P" value="0.06"/>
<define name="ACT_DYN_Q" value="0.06"/>
<define name="ACT_DYN_R" value="0.06"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="TRUE"/>
<define name="ADAPTIVE_MU" value="0.0003"/>
<!--Maxium yaw rate, to avoid instability -->
<define name="MAX_R" value="180" unit="deg/s"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.33"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="INS" prefix="INS_">
<!-- Use GPS altitude measurments and set the R gain -->
<define name="USE_GPS_ALT" value="1"/>
<define name="VFF_R_GPS" value="0.01"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value=" 0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value=" 0.85490967783446"/>
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="60." unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="650"/>
<define name="DGAIN" value="350"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="1.0" unit="m/s"/>
<define name="DESCEND_VSPEED" value="-0.7" unit="m/s"/>
</section>
<section name="MISC">
<define name="ARRIVED_AT_WAYPOINT" value="0.2" unit="m"/>
</section>
<!-- ********************** AP ************************** -->
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_ATTITUDE_DIRECT"/><!-- if GNSS use AP_MODE_NAV ...-->
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_RATE_DIRECT"/><!-- for now...-->
<define name="MODE_AUTO2" value="AP_MODE_GUIDED"/> <!-- for dronerrace -->
<!-- <define name="MODE_AUTO2" value="AP_MODE_NAV"/>--> <!-- If GNSS device is added for autonomous flight -->
<!--<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>-->
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="TRUE"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<!-- If flying on a 2S1P 300mAh 40/80C LiPo -->
<section name="BAT">
<define name="MAX_BAT_CAPACITY" value="300" unit="mAh"/>
<define name="BAT_CAPACITY" value="MAX_BAT_CAPACITY"/><!--temp fix until OSD module is fixed-->
<!-- tested at V 7.6 the avg --> <!-- idle RPM then ?A half throttle ?A-->
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="10" unit="mA"/> <!-- TODO ??mA, with additional RC receiver and wifi and jevois cam ~??mA -->
<define name="MILLIAMP_AT_FULL_THROTTLE" value="240" unit="mA"/> <!-- TODO At 7.2 ?? A at 8.2v ??A rounded then to ?? to be at safe side-->
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/> <!-- TODO: test when AP board switches off -->
<define name="CRITIC_BAT_LEVEL" value="6.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="7.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="8.7" unit="V"/> <!-- 2s LiPo HV 2x4.35 = 8.7 -->
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="FL, FR, BR, BL" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<!-- <define name="JS_AXIS_MODE" value="4"/>-->
</section>
<section name="GCS">
<define name="SPEECH_NAME" value="Trashcan"/>
<define name="AC_ICON" value="quadrotor_x"/>
<define name="ALT_SHIFT_PLUS_PLUS" value="2"/> <!-- 2m low diff for e.g. optitrack, use e.g 10m for outside-->
<define name="ALT_SHIFT_PLUS" value="1" unit="m"/>
<define name="ALT_SHIFT_MINUS" value="-1" unit="m"/>
</section>
</airframe>
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,251 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="xvert">
<description>
* E-flite X-VERT VTOL (https://www.openuas.org/airframes/)
+ Autopilot: Default STM32F3 based
+ Actuators: Default servos, 2 PWM servo's, 2 escs through some proprietary atmega uart protocol
+ GPS: Ublox M8N GNSS over I2C
+ IMU: MPU6500 on mainboard and external HMC58XX on GNSS module
+ TELEMETRY: Si10xx Chip based with full fledged multifreq firmware
+ CURRENT: A standard Volt and Current sensor on the analog ports
+ RANGER: {none yet}
+ RC: RC over Datalink
NOTES:
+ Hey, calibrate your magneto! Yes, you too ;), unit UKF auto works...
+ Yeah.. and you Accelometer also... EKF2 will like you :)
+ Flashing the firmware is done (For now..) via tiny SWD wires solderd on Main PCB, for Hardcore builder only ;)...
WIP:
+ Many thing to improve, e.g. RC and the Flashing method
</description>
<firmware name="rotorcraft">
<target name="ap" board="xvert_1.0"/>
<define name="BAT_CHECKER_DELAY" value="80" />
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" />
<!-- To fix the 32k ram limit issue:-->
<!--<define name="PPRZ_TRIG_INT_USE_FLOAT"/>-->
<define name="PPRZ_TRIG_CONST" value="const"/>
<define name="THD_WORKING_AREA_MAIN" value="802"/>
<define name="UART_THREAD_STACK_SIZE" value="190"/>
<define name="I2C_THREAD_STACK_SIZE" value="190"/>
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<module name="telemetry" type="transparent" >
<define name="MODEM_BAUD" value="B57600"/>
</module>
<module name="guidance" type="hybrid"/>
<module name="motor_mixing"/>
<!--<module name="sys_mon"/>-->
<!--<module name="gps" type="ubx_ucenter"/>-->
<module name="send_imu_mag_current"/>
<module name="air_data"/>
<module name="imu" type="mpu9250_i2c">
<configure name="IMU_MPU9250_I2C_DEV" value="i2c1"/>
<define name="IMU_MPU9250_READ_MAG" value="FALSE"/>
<define name="IMU_MPU9250_I2C_ADDR" value="MPU9250_ADDR"/>
<define name="AHRS_ICQ_MAG_ID" value="MAG_HMC58XX_SENDER_ID" /> <!-- Meaning the external hmc-->
</module>
<module name="stabilization" type="indi_simple" />
<module name="ahrs" type="float_cmpl_quat" >
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</module>
<module name="ins" type="float_invariant">
<define name="INS_PROPAGATE_FREQUENCY" value="500"/>
<define name="INS_FINV_MAG_ID" value="MAG_HMC58XX_SENDER_ID"/>
</module>
<module name="actuators" type="xvert">
<define name="SERVO_HZ" value="400" />
</module>
<module name="radio_control" type="datalink"/>
<module name="gps" type="ubx_i2c">
<configure name="GPS_UBX_I2C_DEV" value="i2c2"/>
</module>
<module name="mag" type="hmc58xx">
<configure name="MAG_HMC58XX_I2C_DEV" value="i2c2"/>
<define name="MODULE_HMC58XX_UPDATE_AHRS" value="TRUE"/>
<define name="HMC58XX_CHAN_X" value="1"/>
<define name="HMC58XX_CHAN_Y" value="0"/>
<define name="HMC58XX_CHAN_Z" value="2"/>
<define name="HMC58XX_CHAN_X_SIGN" value="-"/>
<define name="HMC58XX_CHAN_Y_SIGN" value="+"/>
<define name="HMC58XX_CHAN_Z_SIGN" value="+"/>
</module>
</firmware>
<section name="INS" prefix="INS_">
<define name="H_X" value="0.5138"/>
<define name="H_Y" value="0.00019"/>
<define name="H_Z" value="0.8578"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="30"/>
<define name="MAG_Y_NEUTRAL" value="127"/>
<define name="MAG_Z_NEUTRAL" value="140"/>
<define name="MAG_X_SENS" value="7.11726808648" integer="16"/>
<define name="MAG_Y_SENS" value="7.09366475279" integer="16"/>
<define name="MAG_Z_SENS" value="6.84467824688" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="-52"/>
<define name="ACCEL_Y_NEUTRAL" value="-4"/>
<define name="ACCEL_Z_NEUTRAL" value="-7"/>
<define name="ACCEL_X_SENS" value="2.45056441681" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.44991708802" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.44199722843" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="90." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
</section>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<servos driver="Xvert">
<servo name="RM" no="0" min="1160" neutral="1200" max="1880"/>
<servo name="LM" no="1" min="1160" neutral="1200" max="1880"/>
<servo name="ELEVON_RIGHT" no="2" min="1000" neutral="1500" max="2000"/>
<servo name="ELEVON_LEFT" no="3" min="1000" neutral="1500" max="2000"/>
</servos>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="RM" value="motor_mixing.commands[0]"/>
<set servo="LM" value="motor_mixing.commands[1]"/>
<!-- Mode dependent actuator laws for the elevons. The elevons act different in rc attitude flight mode-->
<!-- First the correct feedback is stored in variables -->
<let var="aileron_feedback_left" value="@YAW"/>
<let var="aileron_feedback_right" value="@YAW"/>
<let var="elevator_feedback_left" value="-@PITCH"/>
<let var="elevator_feedback_right" value="+@PITCH"/>
<!-- if using PID with gain scheduling -->
<let var="forward_left" value="$aileron_feedback_left + $elevator_feedback_left"/>
<let var="forward_right" value="$aileron_feedback_right + $elevator_feedback_right"/>
<!-- This statement tells the autopilot to use the hover feedback if in mode attitude direct and to use the forward feedback in all other cases-->
<set servo="ELEVON_LEFT" value="$forward_left" />
<set servo="ELEVON_RIGHT" value="$forward_right" />
</command_laws>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="2"/>
<define name="SCALE" value="256"/>
<define name="PITCH_COEF" value="{ 0, 0}"/>
<define name="ROLL_COEF" value="{ -256, 256 }"/>
<define name="YAW_COEF" value="{ 0, 0 }"/>
<define name="THRUST_COEF" value="{ 256, 256 }"/>
</section>
<section name="AIR_DATA" prefix="AIR_DATA_">
<define name="CALC_AIRSPEED" value="FALSE" />
<define name="CALC_TAS_FACTOR" value="FALSE" />
<define name="CALC_AMSL_BARO" value="TRUE" />
</section>
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg" />
<define name="SP_MAX_THETA" value="45" unit="deg" />
<define name="SP_MAX_R" value="300" unit="deg/s" />
<define name="DEADBAND_A" value="0" />
<define name="DEADBAND_E" value="0" />
<define name="DEADBAND_R" value="50" />
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.01292" />
<define name="G1_Q" value="0.014867" />
<define name="G1_R" value="0.012055" />
<define name="G2_R" value="0.0" />
<!-- For the bebop2 we need to filter the roll rate due to the dampers -->
<define name="FILTER_ROLL_RATE" value="FALSE" />
<define name="FILTER_PITCH_RATE" value="FALSE" />
<define name="FILTER_YAW_RATE" value="FALSE" />
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="100.0" />
<define name="REF_ERR_Q" value="100.0" />
<define name="REF_ERR_R" value="100.0" />
<define name="REF_RATE_P" value="14.0" />
<define name="REF_RATE_Q" value="14.0" />
<define name="REF_RATE_R" value="14.0" />
<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="3.2"/>
<define name="FILT_CUTOFF_R" value="3.2"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.04" />
<define name="ACT_DYN_Q" value="0.04" />
<define name="ACT_DYN_R" value="0.04" />
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE" />
<define name="ADAPTIVE_MU" value="0.0001" />
<!-- max rates (conservative) -->
<define name="STABILIZATION_INDI_MAX_RATE" value="343.77" unit="deg/s"/>
<define name="STABILIZATION_INDI_MAX_R" value="200" unit="deg/s"/> <!--Does not seem to be applied-->
<define name="FULL_AUTHORITY" value="TRUE"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="350" />
<define name="HOVER_KD" value="85" />
<define name="HOVER_KI" value="20" />
<define name="NOMINAL_HOVER_THROTTLE" value="0.6" />
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE" />
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="30" unit="deg" />
<define name="REF_MAX_SPEED" value="3" unit="m/s" />
<define name="PGAIN" value="50" />
<define name="DGAIN" value="100" />
<define name="IGAIN" value="30" />
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="4.5" />
<define name="DESCEND_VSPEED" value="-1.0" />
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_ATTITUDE_DIRECT" />
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT" />
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD" />
<define name="MODE_AUTO2" value="AP_MODE_RC_DIRECT" />
<define name="NO_RC_THRUST_LIMIT" value="TRUE" />
</section>
<section name="BAT">
<!-- 2S LiPo with 950mAh -->
<define name="LOW_BAT_LEVEL" value="7.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="7.3" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="7.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="8.4" unit="V"/>
</section>
</airframe>
@@ -0,0 +1,425 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Tinyhawk_II">
<description>
* Airframe for the regular "EMAX Tinyhawk II" Quadrotor frame
+ Autopilot: Default Matek f411RX v0 STM32F4 CrazeeBee Pro F4 compatible
+ Actuators: Default onboard Blheli S ESCs see http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM
+ Telemetry: Default via FrSky to TX to USB out to GCS PC
+ RC RX: CC2500 via SPI software FrSky compatible over air 2.4Ghz
NOTES:
+ All set to expect flying on 2s LiPo battery, 1s LiPo battery possible but needs other gain set
+ For FPV racing control tests only
+ No GPS
+ No Baro
+ No Magneto
+ Test Highest loop rate possible for this board
+ Flip module
+ Module for OSD
+ Tuned for Race and ACRO
+ Try out INDI full with rpm feedback
</description>
<firmware name="rotorcraft">
<target name="ap" board="crazybee_f4_1.0">
<configure name="NO_LUFTBOOT" value="1"/>
<configure name="USE_BARO_BOARD" value="FALSE"/>
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/> <!-- Starts in KILL, but can now switch to NAV -->
<!--<define name="AHRS_ALIGNER_SAMPLES_NB" value="1200"/>--> <!--When fidly plugging in a battery, aircraft kind of wobbly, now avoid messing up the aligner this way -->
<!-- <define name="LOW_NOISE_THRESHOLD" value="30000"/>-->
<!-- <define name="LOW_NOISE_TIME" value="10"/>-->
<!-- 2 kHz periodic -->
<configure name="PERIODIC_FREQUENCY" value="2048"/>
<define name="HFF_PRESCALER" value="40"/><!-- FIXME: determine fully correct one-->
<define name="AHRS_PROPAGATE_FREQUENCY" value="2000"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="2000"/>
<!--<configure name="AHRS_MAG_CORRECT_FREQUENCY" value="50"/>-->
<!-- set Gyro/Accel output rate to 2kHz at 8kHz internal sampling -->
<define name="IMU_MPU_LOWPASS_FILTER" value="MPU60X0_DLPF_256HZ"/><!--This sets the internal sample rate to 8KHz. -->
<define name="IMU_MPU_ACCEL_LOWPASS_FILTER" value="MPU60X0_DLPF_ACC_44HZ"/><!-- FIXME check value -->
<define name="IMU_MPU_SMPLRT_DIV" value="3"/> <!--Note that for 1khz periodic IMU_MPU_SMPLRT_DIV=7 sr = gr(8) /1+IMU_MPU_SMPLRT_DIV (1+7/8=1khz-->
<configure name="NAVIGATION_FREQUENCY" value="16"/>
<configure name="CONTROL_FREQUENCY" value="2000"/>
<!--<configure name="TELEMETRY_FREQUENCY" value="120"/>-->
<configure name="MODULES_FREQUENCY" value="2048"/>
<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/>
<define name="BAT_CHECKER_DELAY" value="20"/> <!-- to avoid bat low spike detection when strong up movement withch draws short sudden power-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="50"/> <!-- in 10/s seconds-->
</target>
<module name="radio_control" type="cc2500_frsky">
<define name="CC2500_RX_LED" value="LED_2"/>
<define name="CC2500_BIND_BUTTON" value="BIND_BUTTON"/>
<!--<define name="CC2500_AUTOBIND" value="TRUE"/>-->
<define name="CC2500_TELEMETRY_SENSORS" value="SENSOR_NONE"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_AUX1"/>
</module>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="480"/><!-- DShot also possible-->
</module>
<!-- For flashing -->
<module name="dfu_command"/>
<module name="gps" type="ublox"><!-- hes no GPS but it is a temp fixfor OSD module expecting GPS-->
<configure name="GPS_BAUD" value="B460800"/>
<configure name="GPS_PORT" value="UART2"/>
</module>
<module name="telemetry" type="transparent_usb"/>
<!--<module name="telemetry" type="transparent_frsky_x"/>-->
<module name="imu" type="mpu6000">
<configure name="IMU_MPU_SPI_DEV" value="spi1"/>
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE0"/>
<!-- define name="ICM20608"/> --><!-- Not used atm -->
<!-- <define name="IMU_GYRO_P_CHAN" value="1"/>
<define name="IMU_GYRO_Q_CHAN" value="0"/>
<define name="IMU_GYRO_R_CHAN" value="2"/>
<define name="IMU_ACCEL_X_CHAN" value="1"/>
<define name="IMU_ACCEL_Y_CHAN" value="0"/>
<define name="IMU_ACCEL_Z_CHAN" value="2"/>-->
<!-- To be able (for now) to set AP IMU orientaion -->
<define name="IMU_GYRO_P_SIGN" value="-1"/>
<define name="IMU_GYRO_Q_SIGN" value="1"/>
<define name="IMU_GYRO_R_SIGN" value="-1"/>
<define name="IMU_ACCEL_X_SIGN" value="-1"/>
<define name="IMU_ACCEL_Y_SIGN" value="1"/>
<define name="IMU_ACCEL_Z_SIGN" value="-1"/>
</module>
<!-- BEWARE not all are tested nor tuned -->
<!-- <module name="stabilization" type="rate"/>--><!-- not working yet -->
<!-- <module name="stabilization" type="rate_indi"/> -->
<module name="stabilization" type="int_quat"/>
<!-- <module name="stabilization" type="float_quat"/>-->
<!-- <module name="stabilization" type="indi_simple" /> -->
<!-- <module name="stabilization" type="indi" /> -->
<module name="ins" type="extended"/>
<module name="osd_max7456">
<configure name="MAX7456_SPI_DEV" value="SPI2"/>
<configure name="MAX7456_SLAVE_IDX" value="SPI_SLAVE1"/>
</module>
<!-- <module name="filter_1euro_imu"> -->
<!--<define name="IMU_F1E_ID" value="30"/>-->
<!--<define name="AHRS_ICQ_IMU_ID" value="F1E_IMU_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="F1E_IMU_ID"/>-->
<!-- </module> -->
<!--module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
</module-->
<module name="ahrs" type="float_cmpl_quat">
<!--<define name="AHRS_ICQ_IMU_ID" value="IMU_F1E_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="IMU_F1E_ID"/>-->
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="0"/> <!-- TODO: determine best... Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. -->
<define name="AHRS_PROPAGATE_LOW_PASS_RATES" value="FALSE"/> <!-- apply a low pass filter on rotational velocity"-->
</module>
<!-- WIP for setting values e.g. P/D roll tune via RC Tranmitter, need a new setting file WIP -->
<!--<module name="settings" type="rc"/>-->
</firmware>
<servos driver="Pwm"><!-- OK -->
<servo name="FL" no="3" min="1000" neutral="1130" max="2000"/> <!-- maybe shorter on the cost of resolution... but low high differcnce MUST be bigger than 140-->
<servo name="FR" no="1" min="1000" neutral="1130" max="2000"/>
<servo name="BR" no="0" min="1000" neutral="1130" max="2000"/>
<servo name="BL" no="2" min="1000" neutral="1130" max="2000"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="REVERSE" value="FALSE"/>
<define name="TYPE" value="QUAD_X"/>
</section>
<!-- in case we need much more precise mixing use the table here instead of motor_mixing_run-->
<!-- section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
-->
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="FL" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="FR" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BR" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BL" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="FILTER_1EURO" prefix="FILTER_1EURO_">
<define name="ENABLED" value="FALSE"/> <!-- activate or not the filter by default -->
<define name="GYRO_MINCUTOFF" value="10."/> <!-- minimum cutoff freq for gyro signal -->
<define name="GYRO_BETA" value="0.1"/> <!-- adaptation coefficient for gyro signal -->
<define name="ACCEL_MINCUTOFF" value="0.1"/> <!-- minimum cutoff freq for accel signal -->
<define name="ACCEL_BETA" value="0.01"/> <!-- adaptation coefficient for accel signal -->
<!--<define name="FREQ" value="512"set fixed frequency, if not defined but INS/AHRS_PROPAGATE_FREQUENCY is defined it is used, otherwise autofreq is used-->
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
<!-- replace this with your own calibration -->
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="2400." unit="deg/s"/>
<define name="SP_MAX_Q" value="2400." unit="deg/s"/>
<define name="SP_MAX_R" value="2400" unit="deg/s"/>
<define name="DEADBAND_P" value="10"/>
<define name="DEADBAND_Q" value="10"/>
<define name="DEADBAND_R" value="20"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="800"/>
<define name="GAIN_Q" value="800"/>
<define name="GAIN_R" value="700"/>
<define name="IGAIN_P" value="140"/>
<define name="IGAIN_Q" value="140"/>
<define name="IGAIN_R" value="90"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="200"/>
<define name="DDGAIN_Q" value="200"/>
<define name="DDGAIN_R" value="200"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<define name="SP_MAX_PHI" value="25." unit="deg"/>
<define name="SP_MAX_THETA" value="25." unit="deg"/>
<define name="SP_MAX_R" value="120." unit="deg/s"/>
<define name="DEADBAND_A" value="2"/>
<define name="DEADBAND_E" value="2"/>
<define name="DEADBAND_R" value="50"/>
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<define name="PHI_PGAIN" value="185"/>
<define name="PHI_DGAIN" value="70"/>
<define name="PHI_IGAIN" value="1"/>
<define name="THETA_PGAIN" value="185"/>
<define name="THETA_DGAIN" value="70"/>
<define name="THETA_IGAIN" value="1"/>
<define name="PSI_PGAIN" value="450"/>
<define name="PSI_DGAIN" value="100"/>
<define name="PSI_IGAIN" value="0"/>
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</section>
<!-- when using stabilization type float_quat use ones below, not tuned yet! -->
<!--
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<define name="REF_OMEGA_P" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_P" value="{0.85}"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_Q" value="{0.85}"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="{RadOfDeg(250)}"/>
<define name="REF_ZETA_R" value="{0.85}"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<define name="PHI_PGAIN" value="{1000}"/>
<define name="PHI_DGAIN" value="{1000}"/>
<define name="PHI_IGAIN" value="{200}"/>
<define name="THETA_PGAIN" value="{1000}"/>
<define name="THETA_DGAIN" value="{1000}"/>
<define name="THETA_IGAIN" value="{200}"/>
<define name="PSI_PGAIN" value="{500}"/>
<define name="PSI_DGAIN" value="{500}"/>
<define name="PSI_IGAIN" value="{10}"/>
<define name="PHI_DGAIN_D" value="{100}"/>
<define name="THETA_DGAIN_D" value="{100}"/>
<define name="PSI_DGAIN_D" value="{100}"/>
<define name="PHI_DDGAIN" value="{300}"/>
<define name="THETA_DDGAIN" value="{300}"/>
<define name="PSI_DDGAIN" value="{300}"/>
</section>
-->
<!-- when using stabilization type indi use ones below, not tuned yet! -->
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.05"/>
<define name="G1_Q" value="0.025"/>
<define name="G1_R" value="0.0022"/>
<define name="G2_R" value="0.20"/>
<!-- For some airframes, e.g. Bebop2 we need to filter the roll rate due to the dampers -->
<define name="FILTER_ROLL_RATE" value="FALSE"/>
<define name="FILTER_PITCH_RATE" value="FALSE"/>
<define name="FILTER_YAW_RATE" value="FALSE"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="170.0"/>
<define name="REF_ERR_Q" value="600.0"/>
<define name="REF_ERR_R" value="600.0"/>
<define name="REF_RATE_P" value="14.3"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>
<!-- second order filter parameters -->
<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>
<define name="FILT_CUTOFF" value="5.0"/>
<define name="FILT_CUTOFF_P" value="5.0"/>
<!-- first order actuator dynamics (indi_simple) -->
<define name="ACT_DYN_P" value="0.06"/>
<define name="ACT_DYN_Q" value="0.06"/>
<define name="ACT_DYN_R" value="0.06"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="TRUE"/>
<define name="ADAPTIVE_MU" value="0.0003"/>
<!--Maxium yaw rate, to avoid instability -->
<define name="MAX_R" value="120" unit="deg/s"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.33"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="INS" prefix="INS_">
<!-- Use GPS altitude measurments and set the R gain -->
<!--<define name="USE_GPS_ALT" value="1"/>
<define name="VFF_R_GPS" value="0.01"/>-->
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value=" 0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value=" 0.85490967783446"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="60." unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="650"/>
<define name="DGAIN" value="350"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="1.0" unit="m/s"/>
<define name="DESCEND_VSPEED" value="-0.7" unit="m/s"/>
</section>
<!-- ********************** AP ************************** -->
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_RATE_DIRECT"/>
<define name="MODE_AUTO2" value="AP_MODE_RATE_DIRECT"/>
<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>
<!--<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="TRUE"/>-->
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<!-- If flying on a 2S1P 300mAh 50/100C HV LiPo -->
<section name="BAT">
<define name="MAX_BAT_CAPACITY" value="300" unit="mAh"/>
<!-- tested at V 7.6 the avg --> <!-- idle RPM then ?A half throttle ?A-->
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="10" unit="mA"/> <!-- TODO ??mA, with additional RC receiver and wifi and jevois cam ~??mA -->
<define name="MILLIAMP_AT_FULL_THROTTLE" value="240" unit="mA"/> <!-- TODO At 7.2 ?? A at 8.2v ??A rounded then to ?? to be at safe side-->
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/> <!-- TODO: test when AP board switches off -->
<define name="CRITIC_BAT_LEVEL" value="6.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="7.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="8.7" unit="V"/> <!-- 2s LiPo HV 2x4.35 = 8.7 -->
</section>
<section name="GCS">
<define name="SPEECH_NAME" value="Tinyhawk 2"/>
<define name="AC_ICON" value="quadrotor_x"/>
</section>
</airframe>
@@ -14,26 +14,25 @@
<airframe name="TaxiIII">
<firmware name="fixedwing">
<target name="sim" board="pc"/>
<target name="sim" board="pc"/>
<target name="ap" board="tiny_2.11"/>
<target name="ap" board="tiny_2.11"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="AGR_CLIMB"/>
<define name="TUNE_AGRESSIVE_CLIMB"/>
<define name="USE_I2C0"/>
<define name="PITCH_TRIM"/>
<define name="USE_I2C0"/>
<module name="radio_control" type="ppm">
<!-- for debugging PPM value the one below -->
<!-- <define name="TELEMETRY_MODE_FBW" value="1"/> -->
</module>
<module name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B9600"/>
<configure name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_PORT" value="UART1"/>
</module>
@@ -49,12 +48,12 @@
<modules>
<module name="gps" type="ubx_ucenter"/>
<module name="infrared_adc"/>
<module name="ahrs_infrared"/>
<module name="ahrs_infrared"/>
<module name="digital_cam">
<!-- <define name="DC_SHUTTER_GPIO" value="CAM_SWITCH_GPIO"/>--><!-- Not compiling ATM -->
<define name="DC_SHUTTER_GPIO" value="GPIOB,GPIO22"/>
</module>
</module>
<!--
<module name="sys_mon"/>
-->
@@ -85,7 +84,7 @@
<module name="nav" type="flower"/>
<module name="nav" type="bungee_takeoff"/>
<module name="nav" type="catapult"/>
</modules>
<!-- Define here to which CONNECTOR NUMBER the servo is connected to, on the autopilot cicuit board -->
@@ -99,14 +98,14 @@
<!-- commands section -->
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<!-- for tuning via RC these ones below -->
<!--
<axis name="GAIN1" failsafe_value="0"/>
<axis name="CALIB" failsafe_value="0"/>
<axis name="GAIN1" failsafe_value="0"/>
<axis name="CALIB" failsafe_value="0"/>
-->
</commands>
@@ -382,7 +381,7 @@ If not set before when you would enter home mode you had to flip a bit via the G
<define name="DEVICE_TYPE" value="PPRZ"/>
<define name="DEVICE_ADDRESS" value="...."/>
</section>
<section name="DIGITAL_CAMERA" prefix="DC_">
<define name="AUTOSHOOT_PERIOD" value="3" unit="sec"/>
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="70" unit="meter"/>
@@ -394,4 +393,3 @@ If not set before when you would enter home mode you had to flip a bit via the G
</section>
</airframe>
@@ -1,239 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="leapfrogeye">
<firmware name="rotorcraft">
<target name="ap" board="bebop"/>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="udp"/>
</target>
<!--define name="USE_SONAR" value="TRUE"/-->
<!-- Subsystem section -->
<module name="telemetry" type="transparent_udp"/>
<module name="radio_control" type="datalink"/>
<module name="motor_mixing"/>
<module name="actuators" type="bebop"/>
<module name="imu" type="bebop"/>
<module name="gps" type="furuno"/>
<module name="stabilization" type="indi_simple"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</module>
<module name="ins" type="extended"/>
<module name="guidance" type="indi"/>
</firmware>
<modules main_freq="512">
<module name="geo_mag"/>
<module name="air_data"/>
<!-- only for calibration once-->
<module name="send_imu_mag_current"/>
<!--module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</module-->
<module name="bebop_cam"/>
<module name="cv_blob_locator">
<define name="BLOB_LOCATOR_CAMERA" value="bottom_camera"/>
</module>
<module name="video_rtp_stream">
<define name="VIEWVIDEO_CAMERA" value="bottom_camera"/>
<define name="VIEWVIDEO_QUALITY_FACTOR" value="80"/>
<define name="VIEWVIDEO_DOWNSIZE_FACTOR" value="1"/>
</module>
<module name="nav" type="survey_rectangle_rotorcraft">
<define name="RECTANGLE_SURVEY_DEFAULT_SWEEP" value="10"/>
</module>
<module name="nav" type="survey_poly_rotorcraft">
<define name="POLYSURVEY_DEFAULT_DISTANCE" value="10"/>
</module>
<module name="video_capture">
<define name="VIDEO_CAPTURE_CAMERA" value="bottom_camera"/>
</module>
<module name="digital_cam_video">
<define name="DC_AUTOSHOOT_DISTANCE_INTERVAL" value="5"/>
</module>
<module name="video_exif"/>
</modules>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="6000"/>
</commands>
<servos driver="Default">
<servo name="TOP_RIGHT" no="0" min="3000" neutral="3000" max="12000"/>
<servo name="TOP_LEFT" no="1" min="3000" neutral="3000" max="12000"/>
<servo name="BOTTOM_LEFT" no="2" min="3000" neutral="3000" max="12000"/>
<servo name="BOTTOM_RIGHT" no="3" min="3000" neutral="3000" max="12000"/>
</servos>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="AIR_DATA" prefix="AIR_DATA_">
<define name="CALC_AIRSPEED" value="FALSE"/>
<define name="CALC_TAS_FACTOR" value="FALSE"/>
<define name="CALC_AMSL_BARO" value="TRUE"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- Magneto calibration spesific for this airframe -->
<define name="MAG_X_NEUTRAL" value="-54"/>
<define name="MAG_Y_NEUTRAL" value="-1"/>
<define name="MAG_Z_NEUTRAL" value="134"/>
<define name="MAG_X_SENS" value="7.55622140532" integer="16"/>
<define name="MAG_Y_SENS" value="7.72221931874" integer="16"/>
<define name="MAG_Z_SENS" value="7.84828034818" integer="16"/>
<!-- Magneto current compensation factor calibration -->
<define name="MAG_X_CURRENT_COEF" value="0.0"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0"/>
<define name="MAG_Z_CURRENT_COEF" value="0.0"/>
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<!-- NL -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
<!-- DE -->
</section>
<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="2.2"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="300" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="50"/>
</section>
<section name="ATTITUDE_REFERENCE" prefix="STABILIZATION_ATTITUDE_">
<!-- attitude reference generation model -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="600." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="450" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="600." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.0639"/>
<define name="G1_Q" value="0.0361"/>
<define name="G1_R" value="0.0022"/>
<define name="G2_R" value="0.1450"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="600.0"/>
<define name="REF_ERR_Q" value="600.0"/>
<define name="REF_ERR_R" value="600.0"/>
<define name="REF_RATE_P" value="28.0"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>
<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="8.0"/>
<define name="FILT_CUTOFF_R" value="8.0"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.1"/>
<define name="ACT_DYN_Q" value="0.1"/>
<define name="ACT_DYN_R" value="0.1"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="283"/>
<define name="HOVER_KD" value="82"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="REF_MAX_SPEED" value="2" unit="m/s"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="79"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="30"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="2.5"/>
<define name="DESCEND_VSPEED" value="-1.0"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.9" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="11.0" unit="V"/>
<define name="LOW_BAT_LEVEL" value="11.1" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
-260
View File
@@ -1,260 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
Lisa + Aspirin v2 using SPI only
-->
<airframe name="LisaAspirin2">
<!-- ************************* FIRMWARE ************************* -->
<firmware name="fixedwing">
<target name="ap" board="lisa_m_1.0">
<define name="LISA_M_LONGITUDINAL_X"/>
<configure name="PERIODIC_FREQUENCY" value="120"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="100"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="100"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
</target>
<target name="sim" board="pc"/>
<target name="nps" board="pc">
<!-- Note NPS needs the ppm type radio_control module -->
<module name="fdm" type="jsbsim"/>
</target>
<define name="USE_AIRSPEED"/>
<define name="AGR_CLIMB"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<!-- Sensors -->
<module name="imu" type="aspirin_v2.1"/>
<!--
<module name="ahrs" type="float_dcm">
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<define name="USE_AHRS_GPS_ACCELERATIONS"/>
</module>
-->
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN"/>
</module>
<module name="ins" type="alt_float"/>
<module name="radio_control" type="ppm"/>
<!-- Communication -->
<module name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_PORT" value="UART2"/>
</module>
<!-- Actuators -->
<module name="control" type="energy"/>
<!-- Sensors -->
<module name="navigation"/>
<module name="gps" type="ublox">
<configure name="GPS_PORT" value="UART1"/>
</module>
</firmware>
<!-- ************************* MODULES ************************* -->
<modules>
<module name="geo_mag"/>
<module name="gps" type="ubx_ucenter"/>
<module name="airspeed_ets">
<define name="AIRSPEED_ETS_SYNC_SEND"/>
<configure name="AIRSPEED_ETS_I2C_DEV" value="i2c2"/>
</module>
<module name="adc_generic">
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_1"/>
<configure name="ADC_CHANNEL_GENERIC2" value="ADC_2"/>
</module>
<module name="light">
<define name="LIGHT_LED_STROBE" value="2"/>
<define name="LIGHT_LED_NAV" value="3"/>
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
<define name="NAV_LIGHT_MODE_DEFAULT" value="4"/>
</module>
<module name="digital_cam">
<define name="DC_SHUTTER_GPIO" value="GPIOC,GPIO12"/>
</module>
<!-- module name="nav" type="catapult"/-->
<module name="nav" type="line"/>
</modules>
<!-- ************************* ACTUATORS ************************* -->
<servos>
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="AILEVON_LEFT" no="1" min="1200" neutral="1500" max="1800"/>
<servo name="ELEVATOR" no="2" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="3" min="1100" neutral="1500" max="1900"/>
<servo name="AILEVON_RIGHT" no="4" min="1800" neutral="1500" max="1200"/>
</servos>
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="YAW" value="@YAW"/>
</rc_commands>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="0.8"/>
<define name="MAX_PITCH" value="0.8"/>
</section>
<command_laws>
<set servo="AILEVON_LEFT" value="@ROLL"/>
<set servo="AILEVON_RIGHT" value="-@ROLL"/>
<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW"/>
</command_laws>
<section name="TRIM" prefix="COMMAND_">
<define name="ROLL_TRIM" value="0"/>
<define name="PITCH_TRIM" value="788."/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
<define name="DEFAULT_ROLL" value="10.0" unit="deg"/>
<define name="DEFAULT_PITCH" value="5.0" unit="deg"/>
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
</section>
<!-- ************************* SENSORS ************************* -->
<section name="IMU" prefix="IMU_">
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="-179"/>
<define name="MAG_Y_NEUTRAL" value="-21"/>
<define name="MAG_Z_NEUTRAL" value="79"/>
<define name="MAG_X_SENS" value="4.17334785618" integer="16"/>
<define name="MAG_Y_SENS" value="3.98885954135" integer="16"/>
<define name="MAG_Z_SENS" value="4.40442339014" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="0"/>
<define name="BODY_TO_IMU_THETA" value="0"/>
<define name="BODY_TO_IMU_PSI" value="0"/>
</section>
<section name="AHRS" prefix="AHRS_">
<!-- Local magnetic field, on 3D fix is update by geo_mag module -->
<define name="H_X" value="0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value="0.85490967783446"/>
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="0.0" unit="deg"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="5.9" unit="deg"/>
</section>
<!-- ************************* GAINS ************************* -->
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.89"/>
<define name="COURSE_DGAIN" value="0.27"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="1.0"/>
<define name="ROLL_MAX_SETPOINT" value="45" unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="50" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-50" unit="deg"/>
<define name="PITCH_PGAIN" value="12000"/>
<define name="PITCH_DGAIN" value="1.5"/>
<define name="ELEVATOR_OF_ROLL" value="1273.88500977"/>
<define name="ROLL_SLEW" value="1."/>
<define name="ROLL_ATTITUDE_GAIN" value="7972.02783203"/>
<define name="ROLL_RATE_GAIN" value="500."/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<!-- power -->
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.183"/>
<define name="AIRSPEED_PGAIN" value="0.217"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="10."/>
<define name="MAX_ACCELERATION" value="2."/>
<!-- energy -->
<define name="ENERGY_TOT_PGAIN" value="0.205"/>
<define name="ENERGY_TOT_IGAIN" value="0.403"/>
<define name="ENERGY_DIFF_PGAIN" value="0.403"/>
<define name="ENERGY_DIFF_IGAIN" value="0.259"/>
<define name="GLIDE_RATIO" value="7."/>
<!-- auto throttle -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0." unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0."/>
<!-- extra's -->
<define name="AUTO_THROTTLE_OF_AIRSPEED_PGAIN" value="0.0"/>
<define name="AUTO_THROTTLE_OF_AIRSPEED_IGAIN" value="0.0"/>
<!-- extra's -->
<define name="AUTO_PITCH_OF_AIRSPEED_PGAIN" value="0.0"/>
<define name="AUTO_PITCH_OF_AIRSPEED_IGAIN" value="0.0"/>
<define name="AUTO_PITCH_OF_AIRSPEED_DGAIN" value="0.0"/>
<define name="THROTTLE_SLEW_LIMITER" value="1" unit="m/s/s"/>
<!--define name="AUTO_GROUNDSPEED_SETPOINT" value="15." unit="m/s"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0"/-->
</section>
<!-- ************************* MISC ************************* -->
<section name="BAT">
<define name="MilliAmpereOfAdc(adc)" value="((adc) - 505) * 124.0f"/>
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
</section>
<section name="MISC">
<define name="CLIMB_AIRSPEED" value="14." unit="m/s"/>
<define name="NOMINAL_AIRSPEED" value="16." unit="m/s"/>
<define name="GLIDE_AIRSPEED" value="12." unit="m/s"/>
<define name="RACE_AIRSPEED" value="25." unit="m/s"/>
<define name="STALL_AIRSPEED" value="10." unit="m/s"/>
<define name="CARROT" value="5." unit="s"/>
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0."/>
</section>
<section name="CATAPULT" prefix="NAV_CATAPULT_">
<define name="MOTOR_DELAY" value="0.75" unit="seconds"/>
<define name="HEADING_DELAY" value="3.0" unit="seconds"/>
<define name="ACCELERATION_THRESHOLD" value="1.75"/>
<define name="INITIAL_PITCH" value="15.0" unit="deg"/>
<define name="INITIAL_THROTTLE" value="1.0"/>
</section>
<section name="GLS_APPROACH" prefix="APP_">
<define name="ANGLE" value="5" unit="deg"/>
<define name="INTERCEPT_AF_SD" value="10" unit="m"/>
<define name="TARGET_SPEED" value="13" unit="m/s"/>
</section>
<section name="DIGITAL_CAMERA" prefix="DC_">
<define name="AUTOSHOOT_PERIOD" value="1.5" unit="sec"/>
<define name="AUTOSHOOT_DISTANCE_INTERVAL" value="50" unit="meter"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="JSBSIM_MODEL" value="Malolo1" type="string"/>
<define name="COMMANDS_NB" value="4"/>
<define name="ACTUATOR_NAMES" value="throttle-cmd-norm, aileron-cmd-norm, elevator-cmd-norm, rudder-cmd-norm" type="string[]"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<define name="JS_AXIS_MODE" value="4"/>
<define name="BYPASS_AHRS" value="TRUE"/>
<define name="BYPASS_INS" value="TRUE"/>
</section>
</airframe>
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,240 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="itsybitsy">
<description>
Base is a LadyBird quadrotor frame but now equiped with Lisa/S 1.0
The LadyBird frame comes with four brushed motors in an X configuration.
The motor and rotor configuration is the following:
Front
^
|
Motor3(NW) Motor0(NE)
CW CCW
\ /
,___,
| |
| |
|___|
/ \
CCW CW
Motor2(SW) Motor1(SE)
The Lisa/S is rotated by 13deg CCW against the frame.
</description>
<firmware name="rotorcraft">
<target name="ap" board="lisa_s_1.0">
<module name="radio_control" type="superbitrf_rc"> <!-- type="ppm" -->
<!-- To store the binding parameters for the superbit radio in your
airframe file uncomment the following three lines and set the
correct values based on the output of the superbitrf telemetry
messages. -->
<!--define name="RADIO_TRANSMITTER_ID" value="1335259868"/--> <!-- MX22 module no1 -->
<!--define name="RADIO_TRANSMITTER_CHAN" value="9"/-->
<!--define name="RADIO_TRANSMITTER_PROTOCOL" value="0x01"/--><!--DSM_DSM2_2-->
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
</module>
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/>
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<!-- This airframe is using the servo PWM outputs directly to drive mosfets, which in turn directly drive brushed motors.
With the following settings we will be driving the motors with a 36KHz signal that should be well above anyone's hearing range.
If we went with the 500Hz that woul be the default we would be hearing a very annoying high pitched sound coming from the motors.
-->
<!-- Setting the PWM timer base frequency to 36MHz -->
<define name="PWM_BASE_FREQ" value="36000000"/>
<!-- Setting the PWM interval to 36KHz -->
<define name="SERVO_HZ" value="36000"/>
<define name="USE_SERVOS_1AND2"/>
</module>
<module name="telemetry" type="superbitrf"/>
<!-- Comment the previous line and uncomment the following one if you need
to use the debug serial interface for telemetry. -->
<!--module name="telemetry" type="transparent"/-->
<module name="imu" type="lisa_s_v1.0">
<define name="LISA_S_UPSIDE_DOWN"/> <!-- Upside down is a relative term. :) -->
</module>
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
<module name="ins"/>
<module name="gps" type="ubx_ucenter"/>
<module name="geo_mag"/>
<module name="air_data"/>
<!-- below temporary until tsted then remove it-->
<module name="send_imu_mag_current"/>
</firmware>
<!-- The no= value is the phisycal connector on the autopilot board -->
<servos driver="Pwm">
<servo name="NE" no="0" min="0" neutral="50" max="1000"/>
<servo name="SE" no="1" min="0" neutral="50" max="1000"/>
<servo name="SW" no="2" min="0" neutral="50" max="1000"/>
<servo name="NW" no="3" min="0" neutral="50" max="1000"/>
</servos>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="NE" value="motor_mixing.commands[0]"/>
<set servo="SE" value="motor_mixing.commands[1]"/>
<set servo="SW" value="motor_mixing.commands[2]"/>
<set servo="NW" value="motor_mixing.commands[3]"/>
</command_laws>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="-13." unit="deg"/>
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- MAGNETO CALIBRATION NL -->
<define name="MAG_X_NEUTRAL" value="360"/>
<define name="MAG_Y_NEUTRAL" value="-602"/>
<define name="MAG_Z_NEUTRAL" value="-313"/>
<define name="MAG_X_SENS" value="3.87956285611" integer="16"/>
<define name="MAG_Y_SENS" value="4.00524696232" integer="16"/>
<define name="MAG_Z_SENS" value="4.09474740848" integer="16"/>
<!-- MAGNETO CURRENT CALIBRATION -->
<define name="MAG_X_CURRENT_COEF" value="0.0103422023767"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0084568317783"/>
<define name="MAG_Z_CURRENT_COEF" value="-0.01935617335"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="14000"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="2.8" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="3.2" unit="V"/>
<define name="LOW_BAT_LEVEL" value="3.4" unit="V"/>
<define name="MAX_BAT_LEVEL" value="4.2" unit="V"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_PSI" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="SP_MAX_P" value="90." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="90." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="400"/>
<define name="PHI_DGAIN" value="200"/>
<define name="PHI_IGAIN" value="100"/>
<define name="THETA_PGAIN" value="400"/>
<define name="THETA_DGAIN" value="200"/>
<define name="THETA_IGAIN" value="100"/>
<define name="PSI_PGAIN" value="500"/>
<define name="PSI_DGAIN" value="300"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value=" 300"/>
<define name="PHI_AGAIN" value="0"/>
<define name="THETA_AGAIN" value="0"/>
<define name="PSI_AGAIN" value="0"/>
</section>
<section name="INS" prefix="INS_">
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="276"/>
<define name="HOVER_KD" value="455"/>
<define name="HOVER_KI" value="100"/>
<define name="GUIDANCE_V_NOMINAL_HOVER_THROTTLE" value="0.5"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value=" 0.47577"/>
<define name="H_Y" value=" 0.11811"/>
<define name="H_Z" value=" 0.87161"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="39"/>
<define name="DGAIN" value="50"/>
<define name="IGAIN" value="19"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
</airframe>
@@ -0,0 +1,490 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Trashcan">
<description>
* Airframe for the regular "Trashcan" Quadrotor frame equipped with to validate all onboard functionally.
+ Autopilot: Default Crazybee F4 Pro STM32F4 and all that comes with it
+ Actuators: Default onboard Blheli S ESCs see http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM
+ Telemetry: Default WiFi Via ESP8266 see
+ RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out on LED pin
NOTES:
+ All set to expect flying on 2s LiPo battery, 1s LiPo battery possible but no gains set (yet..)
+ Removed Camera and Video TX to be replaced by a JeVois (www.jevois.org) camera on Uart1
+ RC control also possible via wifi telemetry module
+ Vison: added a JeVois on UART1 TX/RX
+ RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out,
+ Wifi telemetry module also allows RC
WIP:
+ GPS: uBlox SAM M8Q with Magneto n Baro GNSS
</description>
<firmware name="rotorcraft">
<target name="ap" board="crazybee_f4_1.0">
<configure name="NO_LUFTBOOT" value="1"/>
<configure name="USE_BARO_BOARD" value="FALSE"/>
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/> <!-- Starts in KILL, but can now switch to NAV -->
<define name="AHRS_ALIGNER_SAMPLES_NB" value="1200"/> <!--When fidly plugging in a battery, aircraft kind of wobbly, now avoid messing up the aligner this way -->
<!-- <define name="LOW_NOISE_THRESHOLD" value="30000"/>-->
<!-- <define name="LOW_NOISE_TIME" value="10"/>-->
<!-- 2 kHz periodic -->
<configure name="PERIODIC_FREQUENCY" value="2048"/>
<define name="HFF_PRESCALER" value="40"/><!-- FIXME: determine fully correct one-->
<define name="AHRS_PROPAGATE_FREQUENCY" value="2000"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="2000"/>
<configure name="AHRS_MAG_CORRECT_FREQUENCY" value="50"/> <!-- 75 or 160 max -->
<!-- set Gyro/Accel output rate to 2kHz at 8kHz internal sampling -->
<define name="IMU_MPU_LOWPASS_FILTER" value="MPU60X0_DLPF_256HZ"/><!--This sets the internal sample rate to 8KHz. -->
<define name="IMU_MPU_ACCEL_LOWPASS_FILTER" value="MPU60X0_DLPF_ACC_44HZ"/><!-- FIXME check value -->
<define name="IMU_MPU_SMPLRT_DIV" value="3"/> <!-- for 1khz periodic IMU_MPU_SMPLRT_DIV=7 sr = gr(8) /1+IMU_MPU_SMPLRT_DIV (1+7/8=1khz-->
<configure name="NAVIGATION_FREQUENCY" value="16"/>
<configure name="CONTROL_FREQUENCY" value="2000"/>
<configure name="TELEMETRY_FREQUENCY" value="120"/>
<configure name="MODULES_FREQUENCY" value="2048"/>
<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/><!-- handy with the short flight time between tuning sets, not tested if it works yet, this board we have 16kb reserved -->
<define name="BAT_CHECKER_DELAY" value="70"/> <!-- to avoid bat low spike detection when strong up movement withch draws short sudden power-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="90"/> <!-- in 10/s seconds-->
</target>
<module name="radio_control" type="cc2500_frsky">
<define name="CC2500_RX_LED" value="LED_2"/>
<define name="CC2500_BIND_BUTTON" value="BIND_BUTTON"/>
<define name="CC2500_TELEMETRY_SENSORS" value="SENSOR_NONE"/>
</module>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="480"/>
</module>
<module name="dfu_command"/>
<!-- <module name="telemetry" type="transparent_usb"/> -->
<module name="telemetry" type="transparent_frsky_x"/>
<module name="imu" type="mpu6000">
<configure name="IMU_MPU_SPI_DEV" value="spi1"/>
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE0"/>
<!-- define name="ICM20608"/> --> <!-- Not used atm -->
<!-- To be able (for now) to set AP IMU orientaion -->
<define name="IMU_GYRO_P_SIGN" value="1"/>
<define name="IMU_GYRO_Q_SIGN" value="-1"/>
<define name="IMU_GYRO_R_SIGN" value="-1"/>
<define name="IMU_ACCEL_X_SIGN" value="1"/>
<define name="IMU_ACCEL_Y_SIGN" value="-1"/>
<define name="IMU_ACCEL_Z_SIGN" value="-1"/>
</module>
<!-- not all are tested or tuned -->
<!-- <module name="stabilization" type="rate"/>--><!-- not working yet..)
<!-- <module name="stabilization" type="rate_indi"/> -->
<module name="stabilization" type="int_quat"/>
<!--<module name="stabilization" type="float_quat"/>-->
<!-- <module name="stabilization" type="indi_simple" /> -->
<!-- <module name="stabilization" type="indi" /> -->
<module name="ins" type="extended"/>
<!-- Not yet tested -->
<!--<module name="osd_max7456">
<configure name="MAX7456_SPI_DEV" value="SPI2"/>
<configure name="MAX7456_SLAVE_IDX" value="SPI_SLAVE1"/>
</module>-->
<!-- <module name="filter_1euro_imu"> -->
<!--<define name="IMU_F1E_ID" value="30"/>-->
<!--<define name="AHRS_ICQ_IMU_ID" value="F1E_IMU_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="F1E_IMU_ID"/>-->
<!-- </module> -->
<!--module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
</module-->
<module name="ahrs" type="float_cmpl_quat">
<!--<define name="AHRS_ICQ_IMU_ID" value="IMU_F1E_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="IMU_F1E_ID"/>-->
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/> <!-- True for Optitrack false for real magneto-->
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="TRUE"/> <!-- for dronerace -->
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="0"/> <!-- TODO: determine best... Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. -->
<define name="AHRS_PROPAGATE_LOW_PASS_RATES" value="FALSE"/> <!-- apply a low pass filter on rotational velocity"-->
</module>
<!-- WIP for setting values e.g. P/D roll tune via RC Tranmitter, need a new setting file WIP -->
<!--<module name="settings" type="rc"/>-->
<!-- only for... dronerace... -->
<!--
<module name="dronerace"/>
-->
<!-- Not yet used ATM
<module name="jevois_mavlink">
<configure name="JEVOIS_UART" value="UART1"/>
<configure name="JEVOIS_BAUD" value="B115200"/>
</module>
-->
<module name="gps" type="datalink"/> <!-- using optitrack and natnet2ivy -->
<!-- No I2C bus yet... still need to find some good spot for I2C pins... except straigt on MCU solder blobs -->
<!--
<module name="gps" type="ublox">
<configure name="GPS_PORT" value="I2C"/>
</module>
-->
<!--<module name="geo_mag"/>
<<module name="air_data"/>-->
<!-- below temporary until tested then disable it -->
<!-- <module name="send_imu_mag_current"/> -->
<!--
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm">
<define name="RADIO_CONTROL_NB_CHANNEL" value="8"/>
</module>
</target>
-->
<!-- <target name="FPV Racing" board="crazybee_f4_1.0">
WIP
For FPV setup only
No GPS
No Baro
No Magneto
Highest loop rate possible for board
Flip module
Module for OSD
Tuned for Race and ACRO
Try INDI full
</target>
-->
</firmware>
<servos driver="Pwm">
<servo name="FL" no="3" min="1000" neutral="1030" max="2000"/> <!-- maybe shorter on the cost of resolution... but low high differcnce MUST be bigger than 140-->
<servo name="FR" no="1" min="1000" neutral="1030" max="2000"/>
<servo name="BR" no="0" min="1000" neutral="1030" max="2000"/>
<servo name="BL" no="2" min="1000" neutral="1030" max="2000"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="REVERSE" value="TRUE"/>
<define name="TYPE" value="QUAD_X"/>
</section>
<!-- in case we need much more precise mixing use the table here instead of motor_mixing_run
<!-- section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section-->
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="FL" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="FR" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BR" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BL" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="FILTER_1EURO" prefix="FILTER_1EURO_">
<define name="ENABLED" value="FALSE"/> <!-- activate or not the filter by default -->
<define name="GYRO_MINCUTOFF" value="10."/> <!-- minimum cutoff freq for gyro signal -->
<define name="GYRO_BETA" value="0.1"/> <!-- adaptation coefficient for gyro signal -->
<define name="ACCEL_MINCUTOFF" value="0.1"/> <!-- minimum cutoff freq for accel signal -->
<define name="ACCEL_BETA" value="0.01"/> <!-- adaptation coefficient for accel signal -->
<!--<define name="FREQ" value="512"set fixed frequency, if not defined but INS/AHRS_PROPAGATE_FREQUENCY is defined it is used, otherwise autofreq is used-->
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
<!-- Tere is no MAG per default, but in case one adds one , make it correct -->
<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>
<!-- replace this with your own calibration -->
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="8.0" integer="16"/>
<define name="MAG_Y_SENS" value="8.0" integer="16"/>
<define name="MAG_Z_SENS" value="8.0" integer="16"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="2400." unit="deg/s"/>
<define name="SP_MAX_Q" value="2400." unit="deg/s"/>
<define name="SP_MAX_R" value="2400" unit="deg/s"/>
<define name="DEADBAND_P" value="10"/>
<define name="DEADBAND_Q" value="10"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="800"/>
<define name="GAIN_Q" value="800"/>
<define name="GAIN_R" value="700"/>
<define name="IGAIN_P" value="140"/>
<define name="IGAIN_Q" value="140"/>
<define name="IGAIN_R" value="90"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<define name="SP_MAX_PHI" value="50." unit="deg"/>
<define name="SP_MAX_THETA" value="50." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="2"/>
<define name="DEADBAND_E" value="2"/>
<define name="DEADBAND_R" value="100"/>
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<define name="PHI_PGAIN" value="185"/>
<define name="PHI_DGAIN" value="70"/>
<define name="PHI_IGAIN" value="1"/>
<define name="THETA_PGAIN" value="185"/>
<define name="THETA_DGAIN" value="70"/>
<define name="THETA_IGAIN" value="1"/>
<define name="PSI_PGAIN" value="350"/>
<define name="PSI_DGAIN" value="100"/>
<define name="PSI_IGAIN" value="3"/>
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</section>
<!-- when using stabilization type float_quat use ones below, not tuned yet! -->
<!--
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<define name="REF_OMEGA_P" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_P" value="{0.85}"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_Q" value="{0.85}"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="{RadOfDeg(250)}"/>
<define name="REF_ZETA_R" value="{0.85}"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<define name="PHI_PGAIN" value="{1000}"/>
<define name="PHI_DGAIN" value="{1000}"/>
<define name="PHI_IGAIN" value="{200}"/>
<define name="THETA_PGAIN" value="{1000}"/>
<define name="THETA_DGAIN" value="{1000}"/>
<define name="THETA_IGAIN" value="{200}"/>
<define name="PSI_PGAIN" value="{500}"/>
<define name="PSI_DGAIN" value="{500}"/>
<define name="PSI_IGAIN" value="{10}"/>
<define name="PHI_DGAIN_D" value="{100}"/>
<define name="THETA_DGAIN_D" value="{100}"/>
<define name="PSI_DGAIN_D" value="{100}"/>
<define name="PHI_DDGAIN" value="{300}"/>
<define name="THETA_DDGAIN" value="{300}"/>
<define name="PSI_DDGAIN" value="{300}"/>
</section>
-->
<!-- when using stabilization type indi use ones below, not tuned yet! -->
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.05"/>
<define name="G1_Q" value="0.025"/>
<define name="G1_R" value="0.0022"/>
<define name="G2_R" value="0.20"/>
<!-- For some airframes, e.g. Bebop2 we need to filter the roll rate due to the dampers -->
<define name="FILTER_ROLL_RATE" value="FALSE"/>
<define name="FILTER_PITCH_RATE" value="FALSE"/>
<define name="FILTER_YAW_RATE" value="FALSE"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="170.0"/>
<define name="REF_ERR_Q" value="600.0"/>
<define name="REF_ERR_R" value="600.0"/>
<define name="REF_RATE_P" value="14.3"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>
<!-- second order filter parameters -->
<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>
<define name="FILT_CUTOFF" value="5.0"/>
<define name="FILT_CUTOFF_P" value="5.0"/>
<!-- first order actuator dynamics (indi_simple) -->
<define name="ACT_DYN_P" value="0.06"/>
<define name="ACT_DYN_Q" value="0.06"/>
<define name="ACT_DYN_R" value="0.06"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="TRUE"/>
<define name="ADAPTIVE_MU" value="0.0003"/>
<!--Maxium yaw rate, to avoid instability -->
<define name="MAX_R" value="120" unit="deg/s"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.33"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="INS" prefix="INS_">
<!-- Use GPS altitude measurments and set the R gain -->
<define name="USE_GPS_ALT" value="1"/>
<define name="VFF_R_GPS" value="0.01"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value=" 0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value=" 0.85490967783446"/>
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="60." unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="650"/>
<define name="DGAIN" value="350"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="1.0" unit="m/s"/>
<define name="DESCEND_VSPEED" value="-0.7" unit="m/s"/>
</section>
<section name="MISC">
<define name="ARRIVED_AT_WAYPOINT" value="0.2" unit="m"/>
</section>
<!-- ********************** AP ************************** -->
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_ATTITUDE_DIRECT"/><!-- if GNSS use AP_MODE_NAV ...-->
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_RATE_DIRECT"/><!-- for now...-->
<define name="MODE_AUTO2" value="AP_MODE_GUIDED"/> <!-- for dronerrace -->
<!-- <define name="MODE_AUTO2" value="AP_MODE_NAV"/>--> <!-- If GNSS device is added for autonomous flight -->
<!--<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>-->
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="TRUE"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<!-- If flying on a 2S1P 300mAh 40/80C LiPo -->
<section name="BAT">
<define name="MAX_BAT_CAPACITY" value="300" unit="mAh"/>
<!-- tested at V 7.6 the avg --> <!-- idle RPM then ?A half throttle ?A-->
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="10" unit="mA"/> <!-- TODO ??mA, with additional RC receiver and wifi and jevois cam ~??mA -->
<define name="MILLIAMP_AT_FULL_THROTTLE" value="240" unit="mA"/> <!-- TODO At 7.2 ?? A at 8.2v ??A rounded then to ?? to be at safe side-->
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/> <!-- TODO: test when AP board switches off -->
<define name="CRITIC_BAT_LEVEL" value="6.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="7.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="8.7" unit="V"/> <!-- 2s LiPo HV 2x4.35 = 8.7 -->
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="FL, FR, BR, BL" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<!-- <define name="JS_AXIS_MODE" value="4"/>-->
</section>
<section name="GCS">
<define name="SPEECH_NAME" value="Trashcan"/>
<define name="AC_ICON" value="quadrotor_x"/>
<define name="ALT_SHIFT_PLUS_PLUS" value="2"/> <!-- 2m low diff for e.g. optitrack, use e.g 10m for outside-->
<define name="ALT_SHIFT_PLUS" value="1" unit="m"/>
<define name="ALT_SHIFT_MINUS" value="-1" unit="m"/>
</section>
</airframe>
@@ -0,0 +1,202 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="mavtec">
<!-- ************************* FIRMWARE ************************* -->
<firmware name="rotorcraft">
<target name="ap" board="lisa_mx_2.1">
<configure name="FLASH_MODE" value="SWD"/>
<module name="radio_control" type="ppm"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_FLAPS"/>
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>
<define name="USE_I2C_ACTUATORS_REBOOT_HACK"/>
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="asctec_v2"/>
<module name="actuators" type="pwm"/>
<module name="telemetry" type="xbee_api"/>
<module name="imu" type="lisa_mx_v2.1"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="float_mlkf"/>
<module name="ins" type="hff"/>
</firmware>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<!-- ************************* MODULES ************************* -->
<modules main_freq="512">
<!-- <module name="logger_spi_link"/>
<module name="imu_quality_assessment"/> -->
<module name="switch" type="servo"/>
<module name="send_imu_mag_current"/>
<module name="gps" type="ubx_ucenter" />
<module name="nav" type="survey_rectangle_rotorcraft"/>
<module name="nav" type="survey_poly_rotorcraft"/>
<module name="geo_mag"/>
</modules>
<!-- ************************* ACTUATORS ************************* -->
<servos driver="Asctec_v2">
<!-- This is hardcoded in actec_driver: keep this naming
and numbering at all times -->
<servo name="FRONT" no="0" min="0" neutral="3" max="200"/><!-- FRONTLEFT -->
<servo name="BACK" no="1" min="0" neutral="3" max="200"/><!-- FRONTRIGHT -->
<servo name="LEFT" no="2" min="0" neutral="3" max="200"/><!-- BACKRIGHT -->
<servo name="RIGHT" no="3" min="0" neutral="3" max="200"/><!-- BACKLEFT -->
</servos>
<servos driver="Pwm">
<servo name="DROP" no="4" min="1100" neutral="1500" max="2100"/>
</servos>
<section name="SWITCH_SERVO">
<define name="SWITCH_SERVO_SERVO" value="DROP"/>
<define name="SWITCH_SERVO_ON_VALUE" value="SERVO_DROP_MIN"/>
<define name="SWITCH_SERVO_OFF_VALUE" value="SERVO_DROP_MAX"/>
<define name="DropOpen()" value="SwitchServoOn()"/>
<define name="DropClose()" value="SwitchServoOff()"/>
</section>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<!-- FrontLeft - FrontRight - BackRight - BackLeft -->
<define name="ROLL_COEF" value="{ 256, -256, -256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, 256, -256, -256 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[0]"/>
<set servo="BACK" value="motor_mixing.commands[1]"/>
<set servo="LEFT" value="motor_mixing.commands[2]"/>
<set servo="RIGHT" value="motor_mixing.commands[3]"/>
</command_laws>
<!-- ************************* SENSORS ************************* -->
<section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<define name="MAG_X_NEUTRAL" value="140"/>
<define name="MAG_Y_NEUTRAL" value="146"/>
<define name="MAG_Z_NEUTRAL" value="80"/>
<define name="MAG_X_SENS" value="3.68116427889" integer="16"/>
<define name="MAG_Y_SENS" value="3.74966778358" integer="16"/>
<define name="MAG_Z_SENS" value="4.05311539389" integer="16"/>
<define name= "MAG_X_CURRENT_COEF" value="0.00322676138551"/>
<define name= "MAG_Y_CURRENT_COEF" value="0.00266367218758"/>
<define name= "MAG_Z_CURRENT_COEF" value="-0.0004557295634"/>
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="270." unit="deg"/>
</section>
<section name="INS" prefix="INS_">
</section>
<!-- ************************* GAINS ************************* -->
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="65." unit="deg"/>
<define name="SP_MAX_THETA" value="65." unit="deg"/>
<define name="SP_MAX_R" value="250." unit="deg/s"/>
<define name="DEADBAND_R" value="200"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="600" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.87"/>
<define name="REF_MAX_P" value="300." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="600" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.87"/>
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="400"/>
<define name="PHI_DGAIN" value="100"/>
<define name="PHI_IGAIN" value="10"/>
<define name="THETA_PGAIN" value="400"/>
<define name="THETA_DGAIN" value="100"/>
<define name="THETA_IGAIN" value="10"/>
<define name="PSI_PGAIN" value="500"/>
<define name="PSI_DGAIN" value="90"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="100"/>
<define name="THETA_DDGAIN" value="100"/>
<define name="PSI_DDGAIN" value="200"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="500"/>
<define name="HOVER_KD" value="200"/>
<define name="HOVER_KI" value="100"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.4"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="100"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="0"/>
</section>
<!-- ************************* MISC ************************* -->
<section name="MAGNETICS" prefix="AHRS_H_">
<define name="X" value="0.4"/>
<define name="Y" value="0"/>
<define name="Z" value="0.9"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="20000"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
</airframe>
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
@@ -1,13 +1,13 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
* Vivify (http://www.openuas.org/)
<airframe name="Vivify">
<description>
* Vivify (http://www.openuas.org/airframes)
Lisa M v2.0 (http://paparazzi.enac.fr/wiki/index.php/)
With modified power routing by setting Jumper J1
+ Aspirin v2.2 inclusive MS5611
+ XBee XSC 900Mhz or XBP868 depending on location flown
+ depending on location flown
+ uBlox LEA5H and Sarantel helix GPS antenna
+ Spektrum RX DSMX clone - optional mission demanding a R16Scan40MHZ RX
+ Open RXSR - optional mission demanding a R16Scan40MHZ RX
+ Analog Airspeed sensor
+ MK2 Second LisaM as FTD, plus additional power measurement for this board
@@ -25,9 +25,8 @@
Modules to activate:
+ Current sensor on battery wires going to motor
+ geo_mag module if fixed for fixedwing
-->
<airframe name="Vivify">
</description>
<!-- ************************* FIRMWARE ************************* -->
<firmware name="fixedwing">
<define name="RADIO_CONTROL_NB_CHANNEL" value="8" />
@@ -61,7 +60,7 @@
<define name="USE_AIRSPEED"/>
<define name="AGR_CLIMB"/>
<!-- <define name="ALT_KALMAN"/>-->
<define name="TUNE_AGRESSIVE_CLIMB"/>
<define name="STRONG_WIND"/>
<define name="WIND_INFO"/>
@@ -79,13 +78,12 @@
<!-- * Communication * -->
<module name="telemetry" type="transparent">
<!-- or use type="xbee_api"> -->
<configure name="MODEM_BAUD" value="B9600"/>
<!-- <configure name="MODEM_BAUD" value="B57600"/>-->
<configure name="MODEM_PORT" value="UART2"/>
</module>
<module name="control" type="energy"/>
<module name="control" type="energy"/><!-- or energyadaptive-->
<!-- * Sensors * -->
<module name="gps" type="ublox">
@@ -102,7 +100,6 @@
<target name="fbw" board="lisa_m_2.0">
<configure name="SEPARATE_FBW" value="1"/>
<configure name="FLASH_MODE" value="SWD"/>
<configure name="SYS_TIME_LED" value="2"/>
@@ -159,8 +156,8 @@
<!-- ****************************** SIM *********************************-->
<target name="sim" board="pc">
<define name="INS_BARO_ID" value="BARO_SIM_SENDER_ID"/>
<module name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B9600"/>
<module name="telemetry" type="xbee_api">
<configure name="MODEM_BAUD" value="B9600"/>
</module>
<module name="control" type="energy"/>
<module name="imu" type="aspirin_v2.2"/>
@@ -190,10 +187,14 @@
<define name="AIR_DATA_CALC_AMSL_BARO" value="TRUE" />
</module>
<!-- CDW: module name="obc2014"/-->
<!-- Load -->
<!-- module name="sys_mon"/> -->
<!--
<module name="flight_benchmark">
<define name="BENCHMARK_AIRSPEED value="TRUE"/>
<define name="BENCHMARK_ALTITUDE value="TRUE"/>
<define name="BENCHMARK_POSITION value="TRUE"/>
<define name="BENCHMARK_TOLERANCE_AIRSPEED" value="2" unit="m/s"/>
<define name="BENCHMARK_TOLERANCE_ALTITUDE" value="4" unit="m"/>
<define name="BENCHMARK_TOLERANCE_POSITION" value="6" unit="m"/>
@@ -207,7 +208,7 @@
<define name="AIRSPEED_ADC_BIAS" value="413"/>
</module>
<module name="tune_airspeed" />
<module name="tune_airspeed"/>
<module name="adc_generic">
<!-- If we want to read the voltage of battery voltage main engine over AP board via V_BATT -->
@@ -261,10 +262,10 @@
<module name="nav" type="bungee_takeoff"/>
</firmware>
<firmware name="test_progs">
<!--<firmware name="test_progs">
<target name="test_can" board="lisa_m_2.0"/>
</firmware>
</firmware>-->
<firmware name="setup">
<target name="tunnel" board="lisa_m_2.0"/>
</firmware>
@@ -598,7 +599,6 @@ we had an option to use glovs, or start up spinning the prop after a throw. If t
<!-- ************************ GCS SPECIFICS ******************************** -->
<section name="GCS">
<define name="SPEECH_NAME" value="Vivify"/>
<!--TODO: rather see this in <airframe name="Vivify" spokenname="sayitnow"> as optional parameter-->
<define name="AC_ICON" value="flyingwing"/>
</section>
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
+24 -23
View File
@@ -83,6 +83,8 @@
<target name="ap" board="disco">
<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/>
<!-- Towards better kind of aligner initial conditions -->
<!--
<define name="AHRS_ALIGNER_SAMPLES_NB" value="600"/>
@@ -119,8 +121,7 @@
<configure name="TELEMETRY_FREQUENCY" value="60"/> <!-- unit="Hz" -->
<configure name="MODULES_FREQUENCY" value="512"/> <!-- unit="Hz" -->
<module name="imu" type="disco">
</module>
<module name="imu" type="disco"/>
<module name="sonar_bebop"><!-- already in IMU as autoload but we need to set a few things-->
<define name="SONAR_BEBOP_FILTER_NARROW_OBSTACLES" value="FALSE"/><!-- activate later if all works and test GLS autoland with it -->
@@ -153,7 +154,7 @@
<!--<module name="flight_benchmark">
<define name="BENCHMARK_AIRSPEED value="TRUE"/>
<define name="BENCHMARK_ALTITUDE value="TRUE"/>
<define name="BENCHMARK_P/mnt/ad9c1acf-3293-427b-9b65-3f121f8e1d3d/develop/allthings_paparazzi/paparazzi/sw/ground_segment/tmtc/gpsd2ivy OSITION value="TRUE"/>
<define name="BENCHMARK_POSITION value="TRUE"/>
<define name="BENCHMARK_TOLERANCE_AIRSPEED" value="1" unit="m/s"/>
<define name="BENCHMARK_TOLERANCE_ALTITUDE" value="4" unit="m"/>
<define name="BENCHMARK_TOLERANCE_POSITION" value="6" unit="m"/>
@@ -295,7 +296,7 @@
<module name="gps" type="ublox"/>
<module name="tune_airspeed"/> <!-- Enable if one want to perform airspeed tuning -->
<module name="ahrs" type="float_cmpl_quat"> <!-- Compare e.g. float_dcm -->
<module name="ahrs" type="float_cmpl_quat"> <!-- Compare e.g.cmpl_quat float_dcm -->
<configure name="AHRS_USE_MAGNETOMETER" value="TRUE"/> <!-- as in USE it for values in the AHRS -->
<!--<configure name="AHRS_ALIGNER_LED" value="2"/>--><!-- Which color you want sir? ;) -->
<define name="AHRS_MAG_UPDATE_ALL_AXES" value="TRUE"/> <!-- if TRUE with those high roll n pith angles magneto should be calibrated well or use UKF autocalib -->
@@ -307,8 +308,8 @@
<define name="AHRS_HEADING_UPDATE_GPS_MIN_SPEED" value="3.0"/> <!--unit="m/s"--> <!-- CAREFULL, Don't update heading from GPS course if GPS ground speed is below is this threshold in m/s" -->
<!-- Some insights https://lists.nongnu.org/archive/html/paparazzi-devel/2013-10/msg00126.html -->
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="0.5"/> <!-- TODO: determine Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. -->
<define name="AHRS_ICQ_IMU_ID" value="ABI_BROADCAST"/> <!-- ABI sender id of IMU to use -->
<define name="AHRS_ICQ_MAG_ID" value="MAG_CALIB_UKF_ID" /><!-- for when using the mag_clib_ukf -->
<define name="AHRS_FC_IMU_ID" value="ABI_BROADCAST"/> <!-- ABI sender id of IMU to use -->
<define name="AHRS_FC_MAG_ID" value="MAG_CALIB_UKF_ID" /><!-- for when using the mag_clib_ukf -->
</module>
<module name="ins" type="alt_float"/> <!--Does not work in SIM: extended thus use alt_float"/> -->
@@ -341,14 +342,10 @@
<module name="nav" type="flower"/>
<!-- can be used in flightplan during takeoff/landing or lowflyby with default sonar -->
<!--<module name="agl_dist">
</module>-->
<!-- can be used in flightplan during takeoff/landing or lowflyby with default sonar -->
<module name="agl_dist">
<define name="USE_SONAR"/>
</module>
<!-- Propellor spinup of Disco is to slow with direct handlaunch, "catapult" module not all to usable -->
<!-- <module name="nav" type="catapult"/>-->
@@ -480,7 +477,7 @@
<!-- <set command="CALIB" value="@GAIN2"/> -->
</rc_commands>
<!-- ************************ AUTO RC COMMANDS ***************************** -->
<!-- ************************ AUTO RC COMMANDS ********************* -->
<auto_rc_commands>
<!--**TEMPorary for heading change steering if someting not OK with course in Autonomous flight **-->
<set command="YAW" value="@YAW"/>
@@ -493,7 +490,7 @@
<!--<set command="PITCH" value="@PITCH"/>-->
</auto_rc_commands>
<!-- ************************ COMMANDS ***************************** -->
<!-- *************************** COMMANDS ************************** -->
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="5"/>
@@ -501,7 +498,7 @@
<axis name="YAW" failsafe_value="0"/>
</commands>
<!-- ************************ AUTO1 ***************************** -->
<!-- *************************** AUTO1 ***************************** -->
<!-- Do not set MAX_ROLL, MAX_PITCH to small of a value, otherwise one can NOT control the plane very well manually -->
<!-- If you have dual rate swith it of with same swtch as mode switch thus auto1 means dualrate is switched off also -->
<section name="AUTO1" prefix="AUTO1_">
@@ -509,7 +506,7 @@
<define name="MAX_PITCH" value="45" unit="deg"/> <!-- More autority while testflying for first time -->
</section>
<!-- ************************ TRIM ***************************** -->
<!-- **************************** TRIM ***************************** -->
<section name="TRIM" prefix="COMMAND_">
<define name="ROLL_TRIM" value="0.0"/>
<define name="PITCH_TRIM" value="0.0"/>
@@ -524,10 +521,10 @@
<define name="DELAY_WITHOUT_GPS" value="5" unit="s"/>
</section>
<!-- ************************* IMU ************************* -->
<!-- **************************** IMU ****************************** -->
<section name="IMU" prefix="IMU_">
<!-- ***************** GYRO *****************-->
<!-- ********************* GYRO ********************-->
<define name="GYRO_P_SENS" value=" 1.01" integer="16"/>
<define name="GYRO_Q_SENS" value=" 1.01" integer="16"/>
<define name="GYRO_R_SENS" value=" 1.01" integer="16"/>
@@ -608,18 +605,19 @@ The most crucial part for the magnetometer calibration:
<!-- ************************* AHRS ************************* -->
<section name="AHRS" prefix="AHRS_">
<!-- Values used if no GNSS fix, on 3D fix is update by geo_mag module -->
<!-- Better keep geo_mag module ifyou have a GNSDS, else replace the values with your local magnetic field -->
<!-- Values used if no GNSS fix, on 3D fix is updated by geo_mag module -->
<!-- Better use the geo_mag module if you have a GNSS, else replace the values with your local magnetic field -->
<!-- Local Magnetic field DE2019 -->
<define name="H_X" value="0.38644"/>
<define name="H_Y" value="0.02054"/>
<define name="H_Z" value="0.92209"/>
<!--North, East and Vertical Components do: Normalize[{19738.7, 899.5, 44845.6}] -->
<!-- Local Magnetic field DE2020 -->
<define name="H_X" value="0.402784"/>
<define name="H_Y" value="0.018355"/>
<define name="H_Z" value="0.915111"/>
</section>
<!-- ************************* INS ************************* -->
<section name="INS">
<!-- For those super precice target landings ;) well better build in a uBLox M8P-->
<!-- For those super precise target landings ;) well better build in a uBLox M8P-->
<define name="INS_BODY_TO_GPS_X" value="0.11" unit="m"/>
<define name="INS_BODY_TO_GPS_Y" value="0.0" unit="m"/>
<define name="INS_BODY_TO_GPS_Z" value="0.03" unit="m"/>
@@ -764,6 +762,9 @@ The most crucial part for the magnetometer calibration:
<define name="AIRSPEED_PGAIN" value="0.19"/>
<!-- For control classic as in not new or enegry etc.-->
<define name="AUTO_AIRSPEED_PGAIN" value="0.18" unit="%/(m/s)"/>
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="3.0" unit="m/s"/> <!-- TODO: Determine -->
<define name="MAX_ACCELERATION" value="0.9" unit="G"/> <!-- TODO: Determine -->
-244
View File
@@ -1,244 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!--
* Psi a slightly modified Parrot AR.Drone 2.0 (http://www.openuas.org/)
+ uBlox LEA5H and Sarantel helix GPS antenna
NOTES:
+ Original ballbearings replaced with real ball bearings for all axis
+ Frontcamera movable by servo on debug port - optional
+ Spektrum RX DSMX clone on debug port - optional
+ Iridium 9603N - optional
+ Flies on INDI control
-->
<airframe name="Psi">
<firmware name="rotorcraft">
<target name="ap" board="ardrone2">
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/>
<!--<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/>-->
<define name="BAT_CHECKER_DELAY" value="50"/>
<!-- amount of time it take for the bat to check -->
<!-- to avoid bat low spike detection when strong up movement withch draws short sudden power-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="50"/><!-- in seconds-->
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
</target>
<define name="USE_SONAR" value="TRUE"/>
<!--<define name="USE_UART2"/>-->
<!--<define name="DEBUG_NMEA"/>-->
<!-- <define name="DEBUG_SIRF"/>-->
<!-- Subsystem section -->
<module name="telemetry" type="transparent_udp"/>
<module name="radio_control" type="datalink"/>
<module name="motor_mixing"/>
<module name="actuators" type="ardrone2"/>
<module name="imu" type="ardrone2"/>
<module name="gps" type="ublox"/>
<!--<module name="gps" type="nmea"/>-->
<!-- for testing parrot dongele enablethis-->
<!-- <module name="gps" type="sirf">-->
<!--<configure name="UART2_DEV" value="UART2"/>-->
<!--<configure name="GPS_PORT" value="UART2_DEV"/>-->
<!-- <configure name="GPS_BAUD" value="B57600"/>-->
<!-- </module> -->
<module name="stabilization" type="indi_simple"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
</module>
<module name="ins" type="extended"/>
</firmware>
<modules main_freq="512">
<module name="bat_voltage_ardrone2"/>
<module name="gps" type="ubx_ucenter"/>
<module name="send_imu_mag_current"/>
<module name="air_data"/>
<module name="logger_file"/>
</modules>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="3000"/>
</commands>
<servos driver="Default">
<servo name="TOP_LEFT" no="0" min="0" neutral="1" max="500"/>
<servo name="TOP_RIGHT" no="1" min="0" neutral="1" max="500"/>
<servo name="BOTTOM_RIGHT" no="2" min="0" neutral="1" max="500"/>
<servo name="BOTTOM_LEFT" no="3" min="0" neutral="1" max="500"/>
</servos>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<!-- Time cross layout (X), with order NW (CW), NE (CCW), SE (CW), SW (CCW) -->
<define name="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="IMU" prefix="IMU_">
<!-- Accelero -->
<define name="ACCEL_X_NEUTRAL" value="2048"/>
<define name="ACCEL_Y_NEUTRAL" value="2048"/>
<define name="ACCEL_Z_NEUTRAL" value="2048"/>
<!-- Magneto calibration for this specific airframe TODO-->
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="-180"/>
<define name="MAG_X_SENS" value="16." integer="16"/>
<define name="MAG_Y_SENS" value="16." integer="16"/>
<define name="MAG_Z_SENS" value="16." integer="16"/>
<!-- Magneto current calibration TODO -->
<define name="MAG_X_CURRENT_COEF" value="0.0"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0"/>
<define name="MAG_Z_CURRENT_COEF" value="0.0"/>
<!-- TODO should be zeros in ideal scenario -->
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- Local Magnetic field NL Testfield-->
<!--
<define name="H_X" value="0.382478"/>
<define name="H_Y" value="0.00563406"/>
<define name="H_Z" value="0.923948"/>
-->
<!-- Local Magnetic field DE Testfield -->
<define name="H_X" value="0.403896"/>
<define name="H_Y" value="0.012277"/>
<define name="H_Z" value="0.914723"/>
</section>
<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="2.2"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="180" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
</section>
<section name="ATTITUDE_REFERENCE" prefix="STABILIZATION_ATTITUDE_">
<!-- attitude reference generation model -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="600." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="450" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="600." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.032"/>
<define name="G1_Q" value="0.025"/>
<define name="G1_R" value="0.0032"/>
<define name="G2_R" value="0.16"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="380.0"/>
<define name="REF_ERR_Q" value="380.0"/>
<define name="REF_ERR_R" value="250.0"/>
<define name="REF_RATE_P" value="21.6"/>
<define name="REF_RATE_Q" value="21.6"/>
<define name="REF_RATE_R" value="21.0"/>
<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="3.2"/>
<define name="FILT_CUTOFF_R" value="3.2"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.06"/>
<define name="ACT_DYN_Q" value="0.06"/>
<define name="ACT_DYN_R" value="0.06"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="283"/>
<define name="HOVER_KD" value="82"/>
<define name="HOVER_KI" value="13"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="20" unit="deg"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="79"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="30"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_ardrone2" type="string"/>
<define name="JSBSIM_INIT" value="reset00" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_ardrone2.h" type="string"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.7" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
File diff suppressed because it is too large Load Diff
+332
View File
@@ -0,0 +1,332 @@
<conf>
<aircraft
name="ARDrone_2"
ac_id="238"
airframe="airframes/OPENUAS/openuas_parrot_ardrone_2.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/cv_opticflow.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/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/opticflow_hover.xml modules/stabilization_indi_simple.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#ffffb25313ae"
/>
<aircraft
name="Bebop"
ac_id="205"
airframe="airframes/OPENUAS/openuas_parrot_bebop.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.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/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#ffffe8b36503"
/>
<aircraft
name="Bebop_2_Black"
ac_id="240"
airframe="airframes/OPENUAS/openuas_parrot_bebop_2.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.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/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#d294d294d294"
/>
<aircraft
name="Bebop_2_White"
ac_id="239"
airframe="airframes/OPENUAS/openuas_parrot_bebop_2.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.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/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#f18bf18bf18b"
/>
<aircraft
name="Bebopeye"
ac_id="198"
airframe="airframes/OPENUAS/openuas_parrot_bebop.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.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/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#ffffe8b36503"
/>
<aircraft
name="Crazyfly_2_1"
ac_id="197"
airframe="airframes/OPENUAS/openuas_bitcraze_crazyflie_2_1.xml"
radio="radios/OPENUAS/openuas_mx22_cppm_7.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_madgwick.xml modules/air_data.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/opticflow_pmw3901.xml modules/sonar_vl53l1x.xml modules/stabilization_int_quat.xml"
gui_color="#ffffec9c9ef7"
/>
<aircraft
name="Disco_A"
ac_id="206"
airframe="airframes/OPENUAS/openuas_parrot_disco.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/control/ctl_energyadaptive.xml] [settings/estimation/ac_char.xml] [settings/control/ctl_adaptive_h_ff.xml]"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/bebop_cam.xml modules/photogrammetry_calculator.xml modules/dc_ctrl_parrot_mykonos.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#fffff2dd04af"
/>
<aircraft
name="Disco_B"
ac_id="207"
airframe="airframes/OPENUAS/openuas_parrot_disco.xml"
radio="radios/OPENUAS/openuas_sbus_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_energyadaptive.xml settings/estimation/ac_char.xml settings/control/ctl_adaptive_h_ff.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/bebop_cam.xml modules/photogrammetry_calculator.xml modules/dc_ctrl_parrot_mykonos.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#ffff0000e91e"
/>
<aircraft
name="Disco_C"
ac_id="208"
airframe="airframes/OPENUAS/openuas_parrot_disco.xml"
radio="radios/OPENUAS/openuas_sbus_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_energyadaptive.xml settings/estimation/ac_char.xml settings/control/ctl_adaptive_h_ff.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/bebop_cam.xml modules/photogrammetry_calculator.xml modules/dc_ctrl_parrot_mykonos.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#0000ffffffff"
/>
<aircraft
name="Disco_D"
ac_id="209"
airframe="airframes/OPENUAS/openuas_parrot_disco.xml"
radio="radios/OPENUAS/openuas_sbus_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_energyadaptive.xml settings/estimation/ac_char.xml settings/control/ctl_adaptive_h_ff.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/bebop_cam.xml modules/photogrammetry_calculator.xml modules/dc_ctrl_parrot_mykonos.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml modules/digital_cam_video.xml modules/video_capture.xml modules/video_rtp_stream.xml"
gui_color="#0000ffffffff"
/>
<aircraft
name="EFlite_T28"
ac_id="216"
airframe="airframes/OPENUAS/openuas_eflite_t28.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] [settings/control/tune_agr_climb.xml] [settings/control/ctl_energyadaptive.xml]"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="white"
/>
<aircraft
name="Flexo"
ac_id="190"
airframe="airframes/OPENUAS/openuas_own_flexo.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] [settings/control/tune_agr_climb.xml] [settings/control/ctl_energyadaptive.xml]"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="#fffff44a2254"
/>
<aircraft
name="G2"
ac_id="204"
airframe="airframes/OPENUAS/openuas_durafly_g2.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/default_fixedwing.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml settings/control/tune_agr_climb.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_tfmini.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
gui_color="#ffffeb519c78"
/>
<aircraft
name="Goblin"
ac_id="181"
airframe="airframes/OPENUAS/openuas_durafly_goblin.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_new.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="yellow"
/>
<aircraft
name="Iris_Plus"
ac_id="235"
airframe="airframes/OPENUAS/openuas_3dr_iris_plus.xml"
radio="radios/OPENUAS/openuas_sbus_out.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.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/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/px4flow_i2c.xml modules/stabilization_indi_simple.xml"
gui_color="#ffffec9c9ef7"
/>
<aircraft
name="Itsy_Bitsy"
ac_id="253"
airframe="airframes/OPENUAS/openuas_own_itsy_bitsy.xml"
radio="radios/spektrum.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="[settings/rotorcraft_basic.xml] settings/superbitrf.xml settings/control/stabilization_att_int_quat.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/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
gui_color="#fffff92a2254"
/>
<aircraft
name="Mini_Spirit"
ac_id="182"
airframe="airframes/OPENUAS/openuas_df_mini_spirit.xml"
radio="radios/OPENUAS/openuas_mx22_cppm.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.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="white"
/>
<aircraft
name="Minimag"
ac_id="233"
airframe="airframes/OPENUAS/openuas_multiplex_minimag.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] [settings/control/tune_agr_climb.xml] [settings/control/ctl_energyadaptive.xml] settings/control/ctl_new.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="white"
/>
<aircraft
name="Moksha"
ac_id="236"
airframe="airframes/OPENUAS/openuas_own_moksha.xml"
radio="radios/OPENUAS/openuas_mx22_cppm.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/OPENUAS/openuas_tuning_a_fresh_fixedwing.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/gps.xml modules/guidance_energy.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
gui_color="#ffffed9b40f2"
/>
<aircraft
name="Quadshot_W_Negative"
ac_id="245"
airframe="airframes/OPENUAS/openuas_transitionrobotics_quadshot.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
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/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml"
gui_color="#ffff36c42e8d"
/>
<aircraft
name="Quadshot_W_Positive"
ac_id="244"
airframe="airframes/OPENUAS/openuas_transitionrobotics_quadshot.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
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/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml"
gui_color="#224fffff36c4"
/>
<aircraft
name="Sumo_II"
ac_id="189"
airframe="airframes/OPENUAS/openuas_own_sumo_ii.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] [settings/control/tune_agr_climb.xml] [settings/control/ctl_energyadaptive.xml]"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="#fffff44a2254"
/>
<aircraft
name="Taxi_III"
ac_id="225"
airframe="airframes/OPENUAS/openuas_graupner_taxi_iii.xml"
radio="radios/OPENUAS/openuas_mx22.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/digital_cam.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/infrared_adc.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
gui_color="#ffffeb519c78"
/>
<aircraft
name="Tinyhawk_II"
ac_id="179"
airframe="airframes/OPENUAS/openuas_emax_tinyhawk_ii.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/rotorcraft_basic.xml settings/persistent_settings.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"
gui_color="white"
/>
<aircraft
name="Trashcan"
ac_id="203"
airframe="airframes/OPENUAS/openuas_eachine_trashcan.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
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"
gui_color="yellow"
/>
<aircraft
name="Trashcan_voir"
ac_id="202"
airframe="airframes/OPENUAS/openuas_eachine_trashcan.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
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]"
gui_color="white"
/>
<aircraft
name="Twinstar_ND"
ac_id="184"
airframe="airframes/OPENUAS/openuas_multiplex_twinstar_nd.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] [settings/control/tune_agr_climb.xml] [settings/control/ctl_energyadaptive.xml]"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/digital_cam.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="white"
/>
<aircraft
name="UMX_Sbach_342"
ac_id="219"
airframe="airframes/OPENUAS/openuas_eflite_umx_sbach_342.xml"
radio="radios/OPENUAS/openuas_mx22_cppm_7.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] settings/control/tune_agr_climb.xml [settings/control/ctl_energyadaptive.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_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="#ffffffffffff"
/>
<aircraft
name="Vivify"
ac_id="246"
airframe="airframes/OPENUAS/openuas_own_vivify.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/OPENUAS/openuas_obc2014_kingaroy.xml"
settings="settings/estimation/ac_char.xml settings/fixedwing_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/airspeed_adc.xml modules/photogrammetry_calculator.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml modules/digital_cam_uart.xml"
gui_color="#fffffac7c07a"
/>
<aircraft
name="XVert"
ac_id="217"
airframe="airframes/OPENUAS/openuas_eflite_xvert.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft_slow.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/gps.xml modules/guidance_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
gui_color="#fffff3c90091"
/>
</conf>
+1 -123
View File
@@ -1,71 +1,4 @@
<conf>
<aircraft
name="Disco_A"
ac_id="206"
airframe="airframes/OPENUAS/openuas_parrot_disco.xml"
radio="radios/OPENUAS/openuas_sbus_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/control/ctl_energyadaptive.xml] [settings/estimation/ac_char.xml] settings/control/ctl_adaptive_h_ff.xml"
settings_modules="modules/digital_cam_video.xml modules/dc_ctrl_parrot_mykonos.xml modules/video_rtp_stream.xml modules/video_capture.xml modules/bebop_cam.xml modules/photogrammetry_calculator.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/geo_mag.xml modules/air_data.xml modules/nav_basic_fw.xml modules/guidance_energy.xml modules/stabilization_adaptive_fw.xml modules/ahrs_float_cmpl_quat.xml modules/tune_airspeed.xml modules/gps.xml modules/airspeed_ms45xx_i2c.xml modules/gps_ubx_ucenter.xml modules/imu_common.xml"
gui_color="#fffff2dd04af"
/>
<aircraft
name="Disco_B"
ac_id="207"
airframe="airframes/OPENUAS/openuas_parrot_disco.xml"
radio="radios/OPENUAS/openuas_sbus_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_energyadaptive.xml settings/estimation/ac_char.xml settings/control/ctl_adaptive_h_ff.xml"
settings_modules="modules/digital_cam_video.xml modules/dc_ctrl_parrot_mykonos.xml modules/video_rtp_stream.xml modules/video_capture.xml modules/bebop_cam.xml modules/photogrammetry_calculator.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/geo_mag.xml modules/air_data.xml modules/nav_basic_fw.xml modules/guidance_energy.xml modules/stabilization_adaptive_fw.xml modules/ahrs_float_cmpl_quat.xml modules/tune_airspeed.xml modules/gps.xml modules/airspeed_ms45xx_i2c.xml modules/gps_ubx_ucenter.xml modules/imu_common.xml"
gui_color="#ffff0000e91e"
/>
<aircraft
name="Disco_C"
ac_id="208"
airframe="airframes/OPENUAS/openuas_parrot_disco.xml"
radio="radios/OPENUAS/openuas_sbus_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml settings/control/ctl_energyadaptive.xml settings/estimation/ac_char.xml settings/control/ctl_adaptive_h_ff.xml"
settings_modules="modules/digital_cam_video.xml modules/dc_ctrl_parrot_mykonos.xml modules/video_rtp_stream.xml modules/video_capture.xml modules/bebop_cam.xml modules/photogrammetry_calculator.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/geo_mag.xml modules/air_data.xml modules/nav_basic_fw.xml modules/guidance_energy.xml modules/stabilization_adaptive_fw.xml modules/ahrs_float_cmpl_quat.xml modules/tune_airspeed.xml modules/gps.xml modules/airspeed_ms45xx_i2c.xml modules/gps_ubx_ucenter.xml modules/imu_common.xml"
gui_color="#0000ffffffff"
release="8e50f043b163f2b838dadaf1740a3e17b292505b"
/>
<aircraft
name="EFlite_T28"
ac_id="216"
airframe="airframes/OPENUAS/openuas_eflite_t28.xml"
radio="radios/OPENUAS/openuas_openrxsr_sbus_16_out.xml"
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] [settings/control/tune_agr_climb.xml] [settings/control/ctl_energyadaptive.xml]"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="white"
/>
<aircraft
name="Itsy-Bitsy"
ac_id="229"
airframe="airframes/OPENUAS/openuas_itsybitsy.xml"
radio="radios/cockpitSX.xml"
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/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/radio_control_superbitrf_rc.xml modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml"
gui_color="#fffffe72b9fd"
/>
<aircraft
name="Leapfrogeye"
ac_id="228"
airframe="airframes/OPENUAS/openuas_leapfrogeye.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_survey.xml"
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
settings_modules="modules/digital_cam_video.xml modules/video_capture.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/video_rtp_stream.xml modules/cv_blob_locator.xml modules/bebop_cam.xml modules/air_data.xml modules/geo_mag.xml modules/guidance_indi.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffe8b36503"
/>
<aircraft
name="Minimag"
ac_id="233"
@@ -74,62 +7,7 @@
telemetry="telemetry/OPENUAS/openuas_fixedwing_imu_rc.xml"
flight_plan="flight_plans/OPENUAS/openuas_versatile_unified.xml"
settings="settings/fixedwing_basic.xml [settings/estimation/ac_char.xml] [settings/control/ctl_energy.xml] [settings/control/tune_agr_climb.xml] [settings/control/ctl_energyadaptive.xml] settings/control/ctl_new.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/filter_1euro_imu.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/air_data.xml modules/photogrammetry_calculator.xml modules/geo_mag.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/tune_airspeed.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_adaptive_fw.xml"
gui_color="white"
/>
<aircraft
name="Moksha"
ac_id="226"
airframe="airframes/OPENUAS/openuas_moksha.xml"
radio="radios/OPENUAS/openuas_mx22_cppm.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/OPENUAS/openuas_tuning_a_fresh_fixedwing.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/nav_catapult.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/nav_basic_fw.xml modules/gps.xml modules/guidance_energy.xml modules/stabilization_attitude_fw.xml"
gui_color="#ffffeb519c78"
/>
<aircraft
name="Psi"
ac_id="225"
airframe="airframes/OPENUAS/openuas_psi.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/OPENUAS/openuas_rotorcraft_simple.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/gps_ubx_ucenter.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#fffffe72b9fd"
/>
<aircraft
name="Quadyshoty"
ac_id="224"
airframe="airframes/examples/quadshot_asp21_spektrum.xml"
radio="radios/dummy.xml"
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/guidance_hybrid.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml"
gui_color="#ffffffffffff"
/>
<aircraft
name="TaxiIII"
ac_id="223"
airframe="airframes/OPENUAS/openuas_taxiiii.xml"
radio="radios/OPENUAS/openuas_mx22.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/OPENUAS/openuas_nav_modules_test.xml"
settings="settings/fixedwing_basic.xml"
settings_modules="modules/nav_catapult.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/digital_cam.xml modules/infrared_adc.xml modules/gps_ubx_ucenter.xml modules/nav_basic_fw.xml modules/gps.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="#ffffeb519c78"
/>
<aircraft
name="Vivify"
ac_id="222"
airframe="airframes/OPENUAS/openuas_vivify.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
flight_plan="flight_plans/OPENUAS/openuas_obc2014_kingaroy.xml"
settings="settings/estimation/ac_char.xml settings/fixedwing_basic.xml"
settings_modules="modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/digital_cam_uart.xml modules/photogrammetry_calculator.xml modules/tune_airspeed.xml modules/airspeed_adc.xml modules/air_data.xml modules/nav_basic_fw.xml modules/gps_ubx_ucenter.xml modules/gps.xml modules/guidance_energy.xml modules/stabilization_attitude_fw.xml modules/ahrs_int_cmpl_quat.xml modules/imu_common.xml"
gui_color="#fffffac7c07a"
/>
</conf>
@@ -166,7 +166,7 @@
</program>
<program name="Link Combiner"/>
</session>
<session name="OpenUAS testflights">
<session name="OpenUAS testflights 2020">
<program name="GCS">
<arg flag="-speech"/>
<arg flag="-layout" constant="OPENUAS/openuas_bottom_settings.xml"/>
@@ -185,7 +185,6 @@
<arg flag="-s" constant="57600"/>
</program>
<program name="Server"/>
<program name="GPSd position display"/>
</session>
<session name="Flight USB-serial@9600">
<program name="Data Link">