Merge pull request #1956 from EwoudSmeur/conf_cleanup

Removed configurations inactive developers
This commit is contained in:
Freek van Tienen
2016-11-24 13:40:06 +01:00
committed by GitHub
14 changed files with 0 additions and 2399 deletions
-230
View File
@@ -1,230 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="bebop2_indi">
<firmware name="rotorcraft">
<target name="ap" board="bebop2">
<define name="USE_SONAR" value="TRUE"/>
<define name="STABILIZATION_INDI_G2_R" value="0.20"/>
<!--define name="FAILSAFE_GROUND_DETECT"/-->
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="udp"/>
<!-- rotor inertia not modelled in simple_quad JSBSim model, set G2 to zero -->
<define name="STABILIZATION_INDI_G2_R" value="0.0"/>
</target>
<!-- 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="ublox"/>
<module name="stabilization" type="indi"/>
<module name="ahrs" type="float_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE"/>
<define name="AHRS_HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
</module>
<!-- Enable the vertical estimator -->
<module name="ins" type="extended"/>
<!-- Enable the horizontal estimator -->
<!-- <module name="ins" type="hff"> -->
<!-- <define name="GPS_LAG" value="0.35"/> -->
<!-- </module> -->
<define name="KILL_ON_GROUND_DETECT" value="TRUE"/>
</firmware>
<modules main_freq="512">
<module name="geo_mag"/>
<module name="air_data"/>
<!-- <module name="send_imu_mag_current"/>-->
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</module>
</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_LEFT" no="0" min="2500" neutral="2500" max="12000"/>
<servo name="TOP_RIGHT" no="1" min="2500" neutral="2500" max="12000"/>
<servo name="BOTTOM_RIGHT" no="2" min="2500" neutral="2500" max="12000"/>
<servo name="BOTTOM_LEFT" no="3" min="2500" neutral="2500" 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="REVERSE" value="TRUE"/>
<define name="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_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 -->
<define name="MAG_X_NEUTRAL" value="-74"/>
<define name="MAG_Y_NEUTRAL" value="33"/>
<define name="MAG_Z_NEUTRAL" value="-189"/>
<define name="MAG_X_SENS" value="7.32880539549" integer="16"/>
<define name="MAG_Y_SENS" value="7.38826972194" integer="16"/>
<define name="MAG_Z_SENS" value="7.71693452252" integer="16"/>
<!-- Accelerometer Calibration -->
<!-- <define name="ACCEL_X_NEUTRAL" value="72"/>
<define name="ACCEL_Y_NEUTRAL" value="-20"/>
<define name="ACCEL_Z_NEUTRAL" value="42"/>
<define name="ACCEL_X_SENS" value="2.44509248843" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.44634245634" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.43962899631" integer="16"/>-->
</section>
<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<define name="GRAVITY_HEURISTIC_FACTOR" value="0"/>
<define name="H_X" value="0.0"/>
<define name="H_Y" value="0.0"/>
<define name="H_Z" value="0.0"/>
</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="35" unit="deg"/>
<define name="SP_MAX_THETA" value="35" unit="deg"/>
<define name="SP_MAX_R" value="400" 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.05"/>
<define name="G1_Q" value="0.025"/>
<define name="G1_R" value="0.0022"/>
<!-- For the bebop2 we need to filter the roll rate due to the dampers -->
<define name="FILTER_ROLL_RATE" value="TRUE"/>
<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="FILT_OMEGA" value="20.0"/>
<define name="FILT_ZETA" value="0.55"/>
<define name="FILT_OMEGA_R" value="20.0"/>
<define name="FILT_ZETA_R" value="0.55"/>
<!-- 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="350"/>
<define name="HOVER_KD" value="85"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.55"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="12" unit="deg"/>
<define name="REF_MAX_SPEED" value="1" unit="m/s"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="120"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="30"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="1.0"/>
<define name="DESCEND_VSPEED" value="-0.5"/>
</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>
-35
View File
@@ -1,35 +0,0 @@
<conf>
<aircraft
name="bebop2"
ac_id="51"
airframe="airframes/DB/db_bebop2_indi.xml"
radio="radios/dummy.xml"
telemetry="telemetry/DB/db_default_rotorcraft.xml"
flight_plan="flight_plans/DB/db_outdoors.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/rotorcraft_speed.xml settings/control/stabilization_indi.xml [settings/control/stabilization_rate.xml] [settings/control/stabilization_att_int.xml] [settings/control/stabilization_att_int_quat.xml] [settings/control/stabilization_att_float_euler.xml]"
settings_modules="modules/gps.xml modules/geo_mag.xml modules/air_data.xml"
gui_color="#0d890debf1c6"
/>
<aircraft
name="mavshot"
ac_id="52"
airframe="airframes/DB/db_mavshot.xml"
radio="radios/dummy.xml"
telemetry="telemetry/DB/db_default_rotorcraft.xml"
flight_plan="flight_plans/DB/db_outdoors.xml"
settings="settings/rotorcraft_basic.xml settings/modules/config_asctec_v2_new.xml"
settings_modules="modules/geo_mag.xml [modules/gps_ubx_ucenter.xml] modules/gps.xml"
gui_color="#ee1bf3780c03"
/>
<aircraft
name="quadshot"
ac_id="53"
airframe="airframes/DB/db_quadshot_asp21_spektrum.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/DB/db_quadshot.xml"
flight_plan="flight_plans/DB/db_quadshot_delft.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_indi.xml settings/control/hybrid_guidance.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/gps.xml"
gui_color="blue"
/>
</conf>
-248
View File
@@ -1,248 +0,0 @@
<?xml version="1.0"?>
<control_panel name="paparazzi control panel">
<section name="programs">
<program name="Server" command="sw/ground_segment/tmtc/server"/>
<program name="Data Link" command="sw/ground_segment/tmtc/link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
</program>
<program name="Link Combiner" command="sw/ground_segment/python/redundant_link/link_combiner.py"/>
<program name="GCS" command="sw/ground_segment/cockpit/gcs"/>
<program name="Flight Plan Editor" command="sw/ground_segment/cockpit/gcs">
<arg flag="-edit"/>
</program>
<program name="Messages" command="sw/ground_segment/tmtc/messages"/>
<program name="Messages (Python)" command="sw/ground_segment/python/messages_app/messagesapp.py"/>
<program name="Settings" command="sw/ground_segment/tmtc/settings">
<arg flag="-ac" constant="@AIRCRAFT"/>
</program>
<program name="Settings (Python)" command="sw/ground_segment/python/settings_app/settingsapp.py">
<arg flag="--ac_id" constant="@AC_ID"/>
</program>
<program name="GPSd position display" command="sw/ground_segment/tmtc/gpsd2ivy"/>
<program name="Log Plotter" command="sw/logalizer/logplotter"/>
<program name="Real-time Plotter" command="sw/logalizer/plotter"/>
<program name="Real-time Plotter (Python)" command="sw/ground_segment/python/real_time_plot/realtimeplotapp.py"/>
<program name="Log File Player" command="sw/logalizer/play"/>
<program name="Simulator" command="sw/simulator/pprzsim-launch">
<arg flag="-a" constant="@AIRCRAFT"/>
</program>
<program name="Video Synchronizer" command="sw/ground_segment/misc/video_synchronizer"/>
<program name="Joystick" command="sw/ground_segment/joystick/input2ivy">
<arg flag="-ac" constant="@AIRCRAFT"/>
<arg flag="xbox_gamepad.xml"/>
</program>
<program name="Environment Simulator" command="sw/simulator/gaia"/>
<program name="Http Server" command="$python">
<arg flag="-m" constant="SimpleHTTPServer"/>
<arg flag="8889"/>
</program>
<program name="Plot Meteo Profile" command="sw/logalizer/plotprofile"/>
<program name="Weather Station" command="sw/ground_segment/misc/davis2ivy">
<arg flag="-d" constant="/dev/ttyUSB1"/>
</program>
<program name="Attitude Visualizer" command="sw/tools/attitude_viz.py"/>
<program name="App Server" command="sw/ground_segment/tmtc/app_server"/>
<program name="NatNet" command="sw/ground_segment/misc/natnet2ivy"/>
<program name="Ivy2Nmea" command="sw/ground_segment/tmtc/ivy2nmea">
<arg flag="--port" constant="/dev/ttyUSB1"/>
<arg flag="--id" constant="1"/>
</program>
<program name="BluegigaUsbDongleScanner" command="sw/tools/bluegiga_usb_dongle/bluegiga_usb_driver">
<arg flag="/dev/ttyACM2"/>
<arg flag="scan" />
</program>
<program name="BluegigaUsbDongle" command="sw/tools/bluegiga_usb_dongle/bluegiga_usb_driver">
<arg flag="/dev/ttyACM2"/>
<arg flag="00:07:00:2d:d6:bb" />
<arg flag="4242" />
<arg flag="4252" />
</program>
<program name="ADS-B Intruders receiver" command="sw/ground_segment/misc/sbs2ivy">
<arg flag="--ac" constant="@AC_ID"/>
</program>
</section>
<section name="sessions">
<session name="Flight UDP/WiFi">
<program name="Server"/>
<program name="GCS"/>
<program name="Data Link">
<arg flag="-udp"/>
</program>
</session>
<session name="Flight USB-serial@9600">
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
</program>
<program name="Server"/>
<program name="GCS"/>
</session>
<session name="Flight USB-serial@57600">
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
<arg flag="-s" constant="57600"/>
</program>
<program name="Server"/>
<program name="GCS"/>
</session>
<session name="Flight USB-XBee-API@57600">
<program name="Data Link">
<arg flag="-d" constant="/dev/paparazzi/xbee"/>
<arg flag="-transport" constant="xbee"/>
<arg flag="-s" constant="57600"/>
</program>
<program name="Server"/>
<program name="GCS"/>
</session>
<session name="Flight USB-serial Redundant">
<program name="Server"/>
<program name="GCS"/>
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
<arg flag="-id" constant="1"/>
<arg flag="-redlink"/>
</program>
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyUSB1"/>
<arg flag="-id" constant="2"/>
<arg flag="-redlink"/>
</program>
<program name="Link Combiner"/>
</session>
<session name="SupperBitRF">
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyACM0"/>
</program>
<program name="Server"/>
<program name="GCS"/>
<program name="Messages"/>
</session>
<session name="SupperBitRF cable telemetry">
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyACM1"/>
<arg flag="-s" constant="57600"/>
</program>
<program name="Server"/>
<program name="GCS"/>
<program name="Messages"/>
<program name="Messages"/>
</session>
<session name="Messages and Settings">
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
<arg flag="-s" constant="57600"/>
</program>
<program name="Server">
<arg flag="-n"/>
</program>
<program name="Messages"/>
<program name="Settings">
<arg flag="-ac" constant="@AIRCRAFT"/>
</program>
</session>
<session name="Raw Sensors">
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
<arg flag="-s" constant="57600"/>
</program>
<program name="Server">
<arg flag="-n"/>
</program>
<program name="Messages">
<arg flag="-g" constant="300x400+0-220"/>
</program>
<program name="Settings">
<arg flag="-ac" constant="@AIRCRAFT"/>
<arg flag="-g" constant="800x200+0-0"/>
</program>
<program name="Real-time Plotter">
<arg flag="-g" constant="1000x250-0+0"/>
<arg flag="-t" constant="ACC"/>
<arg flag="-u" constant="0.05"/>
<arg flag="-c" constant="0.00"/>
<arg flag="-c" constant="*:telemetry:IMU_ACCEL_RAW:ax"/>
<arg flag="-c" constant="*:telemetry:IMU_ACCEL_RAW:ay"/>
<arg flag="-c" constant="*:telemetry:IMU_ACCEL_RAW:az"/>
<arg flag="-n"/>
<arg flag="-g" constant="1000x250-0+250"/>
<arg flag="-t" constant="GYRO"/>
<arg flag="-u" constant="0.05"/>
<arg flag="-c" constant="0.00"/>
<arg flag="-c" constant="*:telemetry:IMU_GYRO_RAW:gp"/>
<arg flag="-c" constant="*:telemetry:IMU_GYRO_RAW:gq"/>
<arg flag="-c" constant="*:telemetry:IMU_GYRO_RAW:gr"/>
<arg flag="-n"/>
<arg flag="-g" constant="1000x250-0+500"/>
<arg flag="-t" constant="MAG"/>
<arg flag="-u" constant="0.05"/>
<arg flag="-c" constant="0.00"/>
<arg flag="-c" constant="*:telemetry:IMU_MAG_RAW:mx"/>
<arg flag="-c" constant="*:telemetry:IMU_MAG_RAW:my"/>
<arg flag="-c" constant="*:telemetry:IMU_MAG_RAW:mz"/>
<arg flag="-n"/>
<arg flag="-g" constant="1000x250-0+750"/>
<arg flag="-t" constant="BARO"/>
<arg flag="-u" constant="0.05"/>
<arg flag="-c" constant="101325.0"/>
<arg flag="-c" constant="*:telemetry:BARO_RAW:abs"/>
</program>
</session>
<session name="Scaled Sensors">
<program name="Data Link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
<arg flag="-s" constant="57600"/>
</program>
<program name="Server">
<arg flag="-n"/>
</program>
<program name="Messages">
<arg flag="-g" constant="300x400+0-220"/>
</program>
<program name="Settings">
<arg flag="-ac" constant="@AIRCRAFT"/>
<arg flag="-g" constant="800x200+0-0"/>
</program>
<program name="Real-time Plotter">
<arg flag="-g" constant="1000x250-0+0"/>
<arg flag="-t" constant="ACC"/>
<arg flag="-u" constant="0.05"/>
<arg flag="-c" constant="9.81"/>
<arg flag="-c" constant="0.00"/>
<arg flag="-c" constant="-9.81"/>
<arg flag="-c" constant="*:telemetry:IMU_ACCEL_SCALED:ax:0.0009766"/>
<arg flag="-c" constant="*:telemetry:IMU_ACCEL_SCALED:ay:0.0009766"/>
<arg flag="-c" constant="*:telemetry:IMU_ACCEL_SCALED:az:0.0009766"/>
<arg flag="-n"/>
<arg flag="-g" constant="1000x250-0+250"/>
<arg flag="-t" constant="GYRO"/>
<arg flag="-u" constant="0.05"/>
<arg flag="-c" constant="0.00"/>
<arg flag="-c" constant="*:telemetry:IMU_GYRO_SCALED:gp:0.0139882"/>
<arg flag="-c" constant="*:telemetry:IMU_GYRO_SCALED:gq:0.0139882"/>
<arg flag="-c" constant="*:telemetry:IMU_GYRO_SCALED:gr:0.0139882"/>
<arg flag="-n"/>
<arg flag="-g" constant="1000x250-0+500"/>
<arg flag="-t" constant="MAG"/>
<arg flag="-u" constant="0.05"/>
<arg flag="-c" constant="0.00"/>
<arg flag="-c" constant="*:telemetry:IMU_MAG_SCALED:mx:0.0004883"/>
<arg flag="-c" constant="*:telemetry:IMU_MAG_SCALED:my:0.0004883"/>
<arg flag="-c" constant="*:telemetry:IMU_MAG_SCALED:mz:0.0004883"/>
</program>
</session>
</section>
</control_panel>
-295
View File
@@ -1,295 +0,0 @@
<!-- this is a quadshot vehicle equiped with Lisa/m2.0 and an aspirin 2.1
More information on the Quadshot can be found at transition-robotics.com -->
<airframe name="quadshot aspirin 2.1 spektrum">
<servos driver="Pwm">
<!-- <servo name="A1" no="0" min="1000" neutral="1100" max="2000"/>
<servo name="A2" no="1" min="1000" neutral="1100" max="2000"/>
<servo name="B1" no="2" min="1000" neutral="1100" max="2000"/>
<servo name="B2" no="3" min="1000" neutral="1100" max="2000"/>-->
<servo name="ELEVON_LEFT" no="4" min="1000" neutral="1500" max="2000"/>
<servo name="ELEVON_RIGHT" no="5" min="1000" neutral="1500" max="2000"/>
</servos>
<servos driver="Asctec_v2_new">
<servo name="FRONT" no="0" min="0" neutral="3" max="200"/>
<servo name="BACK" no="1" min="0" neutral="3" max="200"/>
<servo name="LEFT" no="2" min="0" neutral="3" max="200"/>
<servo name="RIGHT" no="3" min="0" neutral="3" max="200"/>
</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_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]"/>
<!-- 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"/>
<!-- Here the gains are defined for the two feedback cases, hover and forward-->
<let var="hover_left" value="3*$aileron_feedback_left"/>
<let var="hover_right" value="3*$aileron_feedback_right"/>
<let var="forward_left" value="1*$aileron_feedback_left+4*$elevator_feedback_left"/>
<let var="forward_right" value="1*$aileron_feedback_right+4*$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="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_left : $forward_left" />
<set servo="ELEVON_RIGHT" value="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_right : $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="4"/>
<define name="SCALE" value="256"/>
<define name="PITCH_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="ROLL_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="YAW_COEF" value="{ 256, -256, -128, 128 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
<!-- If you got a caliberation XML document from your IMU supplier, import this in the IMU section -->
<!-- Note that is better to have *no* caliberation file at all, than a one with incorrect caliberation values.
The default factory values are most of the time perfectly acceptable, so by default we will not use the caliberation file -->
<section name="IMU" prefix="IMU_">
<!-- Use default driver values for gyro -->
<!-- IMU calibration, make sure to calibrate the IMU properly before flight, see the wiki for more info-->
<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="4.86487566223" integer="16"/>
<define name="ACCEL_Y_SENS" value="4.89957269597" integer="16"/>
<define name="ACCEL_Z_SENS" value="4.82616398266" integer="16"/>
<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="4.19385009207" integer="16"/>
<define name="MAG_Y_SENS" value="4.32306399648" integer="16"/>
<define name="MAG_Z_SENS" value="4.63243801309" integer="16"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="90." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_FORWARD"/>
<define name="MODE_AUTO2" value="AP_MODE_RATE_DIRECT"/>
<!-- <define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/> -->
</section>
<section name="BAT">
<define name="MIN_BAT_LEVEL" value="10.9" units="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="10.3" unit="V"/>
</section>
<!-- These gains are used when the gain scheduling module is enabled (by loading it in the modules section)-->
<section name ="GAIN_SETS">
<define name="NUMBER_OF_GAINSETS" value="2"/>
<define name="SCHEDULING_VARIABLE" value="(radio.values[COMMAND_THRUST]+ transition_status"/>
<define name="SCHEDULING_POINTS" value="{1000, 6000}"/>
<define name="SCHEDULING_VARIABLE_FRAC" value="0"/>
<define name="PHI_P" value="{230, 230}"/>
<define name="PHI_D" value="{170, 170}"/>
<define name="PHI_I" value="{30, 30}"/>
<define name="PHI_DD" value="{0, 0}"/>
<define name="THETA_P" value="{200, 300}"/>
<define name="THETA_D" value="{100, 50}"/>
<define name="THETA_I" value="{40, 40}"/>
<define name="THETA_DD" value="{0, 0}"/>
<define name="PSI_P" value="{300, 300}"/>
<define name="PSI_D" value="{150, 150}"/>
<define name="PSI_I" value="{0, 0}"/>
<define name="PSI_DD" value="{0, 0}"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="60." unit="deg"/>
<define name="SP_MAX_THETA" value="60." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>
<define name="SP_PSI_DELTA_LIMIT" value="90" unit="deg"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="1500" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="300." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="1500" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="1500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="90." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="170"/>
<define name="PHI_DGAIN" value="120"/>
<define name="PHI_IGAIN" value="30"/>
<define name="THETA_PGAIN" value="150"/>
<define name="THETA_DGAIN" value="70"/>
<define name="THETA_IGAIN" value="40"/>
<define name="PSI_PGAIN" value="300"/>
<define name="PSI_DGAIN" value="150"/>
<define name="PSI_IGAIN" value="0"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 0"/>
<define name="THETA_DDGAIN" value=" 0"/>
<define name="PSI_DDGAIN" value=" 0"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.012"/>
<define name="G1_Q" value="0.04"/>
<define name="G1_R" value="0.004"/>
<define name="G2_R" value="0.0"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="70.0"/>
<define name="REF_ERR_Q" value="45.0"/>
<define name="REF_ERR_R" value="70.0"/>
<define name="REF_RATE_P" value="9.0"/>
<define name="REF_RATE_Q" value="16.0"/>
<define name="REF_RATE_R" value="12.0"/>
<!-- second order filter parameters -->
<define name="FILT_OMEGA" value="50.0"/>
<define name="FILT_ZETA" value="0.7"/>
<define name="FILT_OMEGA_R" value="20.0"/>
<define name="FILT_ZETA_R" value="0.55"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.15"/>
<define name="ACT_DYN_Q" value="0.15"/>
<define name="ACT_DYN_R" value="0.15"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<!-- Gains for vertical navigation -->
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="200"/>
<define name="HOVER_KD" value="175"/>
<define name="HOVER_KI" value="72"/>
<define name="NOMINAL_HOVER_THROTTLE" value ="0.4"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="GRAVITY_HEURISTIC_FACTOR" value="0"/>
<define name="H_X" value=" 0.47577"/>
<define name="H_Y" value=" 0.11811"/>
<define name="H_Z" value=" 0.87161"/>
</section>
<!-- Gains for horizontal navigation-->
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="100"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="0"/>
</section>
<section name="MISC">
<!-- <define name="REF_QUAT_INFINITESIMAL_STEP" value="TRUE"/> -->
<!--The Quadshot uses a slightly different axis system for the setpoint, to make both hovering and flying forward intuitive-->
<define name="USE_EARTH_BOUND_RC_SETPOINT" value="TRUE"/>
<!-- This is the pitch angle that the Quadshot will have in forward flight, where 0 degrees is hover-->
<define name="TRANSITION_MAX_OFFSET" value="-80.0" unit="deg"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<modules main_freq="512">
<module name="geo_mag"/>
<module name="gps" type="ubx_ucenter"/>
<!-- The the led_safety_status module will make the Quadshot LEDs blink in certain patterns when there are safety violations-->
<module name="led_safety_status">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="BODY"/>
</module>
<!-- Load this module to use multiple gain sets, which have to be specified in the gain sets section -->
<!--module name="gain_scheduling"/-->
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
<!-- Put the mode on channel AUX1-->
<define name="RADIO_KILL_SWITCH" value="5"/>
<!-- <configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/> -->
</module>
<configure name="FLASH_MODE" value="SWD"/>
<!-- on aspirin 2.1 the ms5611 baro is not connected via SPI, use BMP085 on Lisa/M board instead -->
<!-- <configure name="LISA_M_BARO" value="BARO_BOARD_BMP085"/> -->
<!-- If using aspirin 2.2, make sure to uncomment the following barometer configuration: -->
<configure name="LISA_M_BARO" value="BARO_MS5611_SPI"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
</module>
<module name="actuators" type="asctec_v2_new"/>
<module name="telemetry" type="transparent"/>
<module name="imu" type="aspirin_v2.2"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="indi"/>
<module name="stabilization" type="rate_indi"/>
<module name="guidance" type="hybrid"/>
<module name="logger_spi_link"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="TRUE"/>
<!--define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="TRUE"/-->
</module>
<module name="ins"/>
</firmware>
</airframe>
@@ -1,384 +0,0 @@
<!-- this is a quadshot vehicle equiped with Lisa/m2.0 and an aspirin 2.1
More information on the Quadshot can be found at transition-robotics.com -->
<airframe name="quadshot aspirin 2.1 spektrum">
<servos driver="Pwm">
<servo name="A1" no="0" min="1000" neutral="1100" max="2000"/>
<servo name="A2" no="1" min="1000" neutral="1100" max="2000"/>
<servo name="B1" no="2" min="1000" neutral="1100" max="2000"/>
<servo name="B2" no="3" min="1000" neutral="1100" max="2000"/>
<!-- <servo name="A1" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="A2" no="1" min="1000" neutral="1000" max="2000"/>
<servo name="B1" no="2" min="1000" neutral="1000" max="2000"/>
<servo name="B2" no="3" min="1000" neutral="1000" max="2000"/>-->
<!-- <servo name="ELEVON_LEFT" no="4" min="1150" neutral="1500" max="1850"/>
<servo name="ELEVON_RIGHT" no="5" min="1150" neutral="1500" max="1850"/>-->
<servo name="ELEVON_LEFT" no="4" min="1300" neutral="1500" max="1700"/>
<servo name="ELEVON_RIGHT" no="5" min="1300" neutral="1500" max="1700"/>
</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_motors_on,FALSE,values)"/>
<set servo="A1" value="motor_mixing.commands[0]"/>
<set servo="A2" value="motor_mixing.commands[1]"/>
<set servo="B1" value="motor_mixing.commands[2]"/>
<set servo="B2" value="motor_mixing.commands[3]"/>
<!-- 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"/>
<!-- Here the gains are defined for the two feedback cases, hover and forward-->
<let var="hover_left" value="15*$aileron_feedback_left"/>
<let var="hover_right" value="15*$aileron_feedback_right"/>
<!-- if using INDI -->
<!-- <let var="forward_left" value="aileron_gain*$aileron_feedback_left+elevator_gain*$elevator_feedback_left"/>
<let var="forward_right" value="aileron_gain*$aileron_feedback_right+elevator_gain*$elevator_feedback_right"/>-->
<!-- if using PID with gain scheduling -->
<let var="forward_left" value="5*$aileron_feedback_left + 4*$elevator_feedback_left"/>
<let var="forward_right" value="5*$aileron_feedback_right + 4*$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="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_left : $forward_left" />
<set servo="ELEVON_RIGHT" value="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? $hover_right : $forward_right" />
<!-- <set servo="ELEVON_RIGHT" value="AP_MODE == AP_MODE_ATTITUDE_DIRECT ? 9000 : -9000" /> -->
</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="PITCH_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="ROLL_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="YAW_COEF" value="{ -256, 256, 128, -128 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
<!-- <define name="PITCH_COEF" value="{ 0, 0, 0, 0 }"/>
<define name="ROLL_COEF" value="{ 0, 0, 0, 0 }"/>
<define name="YAW_COEF" value="{ 0, 0, 0, 0 }"/>
<define name="THRUST_COEF" value="{ 0, 0, 0, 0 }"/>-->
</section>
<!-- If you got a caliberation XML document from your IMU supplier, import this in the IMU section -->
<!-- Note that is better to have *no* caliberation file at all, than a one with incorrect caliberation values.
The default factory values are most of the time perfectly acceptable, so by default we will not use the caliberation file -->
<section name="IMU" prefix="IMU_">
<!-- Use default driver values for gyro -->
<!-- IMU calibration, make sure to calibrate the IMU properly before flight, see the wiki for more info-->
<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="4.86487566223" integer="16"/>
<define name="ACCEL_Y_SENS" value="4.89957269597" integer="16"/>
<define name="ACCEL_Z_SENS" value="4.82616398266" integer="16"/>
<!-- <define name="MAG_X_NEUTRAL" value="104"/> -->
<!-- <define name="MAG_Y_NEUTRAL" value="9"/> -->
<!-- <define name="MAG_Z_NEUTRAL" value="15"/> -->
<!-- <define name="MAG_X_SENS" value="3.57880347067" integer="16"/> -->
<!-- <define name="MAG_Y_SENS" value="3.54049742843" integer="16"/> -->
<!-- <define name="MAG_Z_SENS" value="4.0620533034" integer="16"/> -->
<define name="MAG_X_NEUTRAL" value="-86"/>
<define name="MAG_Y_NEUTRAL" value="-36"/>
<define name="MAG_Z_NEUTRAL" value="35"/>
<define name="MAG_X_SENS" value="3.98639595061" integer="16"/>
<define name="MAG_Y_SENS" value="4.00632407649" integer="16"/>
<define name="MAG_Z_SENS" value="4.17946082997" integer="16"/>
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="90." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_FORWARD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
<!-- <define name="USE_YAW_FOR_MOTOR_ARMING" value="TRUE"/> -->
</section>
<section name="BAT">
<!-- <define name="MIN_BAT_LEVEL" value="10.8" units="V"/> -->
<define name="CRITIC_BAT_LEVEL" value="10.8" unit="V"/>
<define name="LOW_BAT_LEVEL" value="10.8" unit="V"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="10.1" unit="V"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="GAIN_P" value="350"/>
<define name="GAIN_Q" value="250"/>
<define name="GAIN_R" value="350"/>
<define name="IGAIN_P" value="200"/>
<define name="IGAIN_Q" value="200"/>
<define name="IGAIN_R" value="200"/>
</section>
<!-- These gains are used when the gain scheduling module is enabled (by loading it in the modules section)-->
<section name ="GAIN_SETS">
<define name="NUMBER_OF_GAINSETS" value="2"/>
<define name="SCHEDULING_VARIABLE" value="guidance_hybrid_norm_ref_airspeed"/>
<define name="SCHEDULING_POINTS" value="{4, 10}"/>
<define name="SCHEDULING_VARIABLE_FRAC" value="8"/>
<define name="PHI_P" value="{150, 150}"/>
<define name="PHI_D" value="{150, 150}"/>
<define name="PHI_I" value="{30, 30}"/>
<define name="PHI_DD" value="{0, 0}"/>
<define name="THETA_P" value="{100, 80}"/>
<define name="THETA_D" value="{100, 110}"/>
<define name="THETA_I" value="{40, 40}"/>
<define name="THETA_DD" value="{0, 0}"/>
<define name="PSI_P" value="{300, 300}"/>
<define name="PSI_D" value="{150, 150}"/>
<define name="PSI_I" value="{0, 0}"/>
<define name="PSI_DD" value="{0, 0}"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="60." unit="deg"/>
<define name="SP_MAX_THETA" value="60." unit="deg"/>
<define name="SP_MAX_R" value="100." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>
<define name="SP_PSI_DELTA_LIMIT" value="90" unit="deg"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="1500" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="300." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="1500" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_R" value="1500" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="300." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(7000.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="150"/>
<define name="PHI_DGAIN" value="150"/>
<define name="PHI_IGAIN" value="30"/>
<define name="THETA_PGAIN" value="100"/>
<define name="THETA_DGAIN" value="100"/>
<define name="THETA_IGAIN" value="40"/>
<define name="PSI_PGAIN" value="300"/>
<define name="PSI_DGAIN" value="150"/>
<define name="PSI_IGAIN" value="0"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value=" 0"/>
<define name="THETA_DDGAIN" value=" 0"/>
<define name="PSI_DDGAIN" value=" 0"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="60." unit="deg"/>
<define name="SP_MAX_THETA" value="60." unit="deg"/>
<define name="SP_MAX_R" value="180." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
<define name="DEADBAND_A" value="250"/>
<define name="SP_PSI_DELTA_LIMIT" value="90" unit="deg"/>
<!-- control effectiveness -->
<define name="G1_P" value="0.025"/>
<define name="G1_Q" value="0.0833"/>
<define name="G1_R" value="0.00588"/>
<define name="G2_R" value="0.0"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="70.0"/>
<define name="REF_ERR_Q" value="45.0"/>
<define name="REF_ERR_R" value="70.0"/>
<define name="REF_RATE_P" value="9.0"/>
<define name="REF_RATE_Q" value="16.0"/>
<define name="REF_RATE_R" value="12.0"/>
<!-- second order filter parameters -->
<define name="FILT_OMEGA" value="50.0"/>
<define name="FILT_ZETA" value="0.7"/>
<define name="FILT_OMEGA_R" value="20.0"/>
<define name="FILT_ZETA_R" value="0.55"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.03"/>
<define name="ACT_DYN_Q" value="0.03"/>
<define name="ACT_DYN_R" value="0.03"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<!-- Gains for vertical navigation -->
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
<define name="MAX_SUM_ERR" value="2000000"/>
<define name="HOVER_KP" value="200"/>
<define name="HOVER_KD" value="175"/>
<define name="HOVER_KI" value="100"/>
<define name="NOMINAL_HOVER_THROTTLE" value ="0.2"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="AHRS" prefix="AHRS_">
<!-- Delft magnetic field -->
<define name="H_X" value="0.39049610"/>
<define name="H_Y" value="0.00278894"/>
<define name="H_Z" value="0.92060036"/>
</section>
<!-- Gains for horizontal navigation-->
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="50"/>
<define name="IGAIN" value="65"/>
<define name="MAX_BANK" value="RadOfDeg(55)"/>
<define name="FORWARD_MAX_BANK" value="RadOfDeg(35)"/>
<define name="USE_REF" value="FALSE"/>
</section>
<section name="NAV">
<define name="ARRIVED_AT_WAYPOINT" value="5" unit="m"/>
</section>
<section name="MISC">
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="{1,1,1,1,1,1,1,1,1,1,1,1}"/>
<!--The Quadshot uses a slightly different axis system for the setpoint, to make both hovering and flying forward intuitive-->
<define name="USE_EARTH_BOUND_RC_SETPOINT" value="TRUE"/>
<!-- This is the pitch angle that the Quadshot will have in forward flight, where 0 degrees is hover-->
<define name="TRANSITION_MAX_OFFSET" value="-75.0" unit="deg"/>
<define name="RC_LOST_MODE" value="MODE_AUTO2"/>
<define name="SWITCH_STICKS_FOR_RATE_CONTROL" value="TRUE"/>
<define name="AIRSPEED_ETS_I2C_DEV" value="i2c2"/>
<define name="AHRS_MAG_UPDATE_ALL_AXES" value="FALSE"/>
<define name="THRESHOLD_GROUND_DETECT" value="25.0"/>
<define name="KILL_ON_GROUND_DETECT" value="TRUE"/>
<define name="FAILSAFE_GROUND_DETECT" value="TRUE"/>
<define name="HYBRID_NAVIGATION" value="TRUE"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
<define name="ADAPTIVE_INDI" value="FALSE"/>
</section>
<modules main_freq="512">
<load name="gps_ubx_ucenter.xml"/>
<!-- The the led_safety_status module will make the Quadshot LEDs blink in certain patterns when there are safety violations-->
<load name="led_safety_status.xml">
<define name="USE_LED_BODY" value="1"/>
<define name="SAFETY_WARNING_LED" value="BODY"/>
</load>
<load name="sonar_adc.xml">
<configure name="ADC_SONAR" value="ADC_2"/>
<!-- <define name="USE_SONAR"/> -->
<define name="SENSOR_SYNC_SEND_SONAR"/>
<define name="SONAR_SCALE" value="0.0032"/>
</load>
<!--Use an airspeed sensor and get the measured airspeed in the messages-->
<!-- <load name="airspeed_ets.xml">
<define name="AIRSPEED_ETS_SYNC_SEND"/>
</load>-->
<module name="logger_spi_link"/>
<!-- <load name="AOA_adc.xml">
<configure name="ADC_AOA" value="ADC_2"/>
<define name="AOA_OFFSET" value="0"/>
<define name="AOA_FILTER" value="0"/>
<define name="USE_AOA"/>
<define name="AOA_SENS" value="2.0*M_PI/1024/4"/>
</load>-->
<!-- Load this module to use multiple gain sets, which have to be specified in the gain sets section. Does not work with INDI -->
<!-- <module name="gain_scheduling"/> -->
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
<define name="RADIO_KILL_SWITCH" value="5"/>
<!-- Put the mode on channel AUX1-->
<define name="RADIO_MODE" value="6"/>
<!-- <configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/> -->
</module>
<!-- ONLY if flashing via JTAG cable -->
<configure name="FLASH_MODE" value="SWD"/>
<configure name="BMP_PORT" value="/dev/ttyACM0" />
<!-- To use an airspeed sensor on I2C, enable I2C2-->
<!-- <define name="USE_I2C2"/> -->
<!-- If using aspirin 2.2, make sure to uncomment the following barometer configuration: -->
<!-- <configure name="LISA_M_BARO" value="BARO_MS5611_SPI"/> -->
<configure name="LISA_M_BARO" value="BARO_BOARD_BMP085"/>
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</module>
<module name="telemetry" type="xbee_api"/>
<!-- <module name="telemetry" type="transparent"/> -->
<module name="imu" type="aspirin_v2.1"/>
<module name="gps" type="ublox"/>
<!-- <module name="stabilization" type="int_quat"/> -->
<module name="stabilization" type="indi"/>
<module name="guidance" type="hybrid"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="1"/>
<define name="AHRS_USE_GPS_HEADING" value="0"/>
</module>
<module name="ins"/>
</firmware>
</airframe>
-46
View File
@@ -1,46 +0,0 @@
<conf>
<aircraft
name="Altura"
ac_id="151"
airframe="airframes/LS/ls_quadrotor_altura_lisa_m_2_0.xml"
radio="radios/spektrum.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/TUDELFT/tudelft_mavtec_outdoor_demo.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml"
settings_modules="modules/gps_ubx_ucenter.xml"
gui_color="#00000000ffff"
/>
<aircraft
name="BebopSmallGPSMes"
ac_id="1"
airframe="airframes/LS/ls_quadrotor_bebop_small_gps_messages.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_optitrack.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int_quat.xml settings/control/rotorcraft_guidance.xml"
settings_modules="modules/geo_mag.xml modules/air_data.xml"
gui_color="blue"
/>
<aircraft
name="LadyLisaBluegiga"
ac_id="2"
airframe="airframes/LS/ls_ladybird_lisa_s_bluegiga_small_gps_messages.xml"
radio="radios/spektrum.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_optitrack.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int_quat.xml"
settings_modules=""
gui_color="blue"
/>
<aircraft
name="MavTecLS"
ac_id="150"
airframe="airframes/LS/ls_quadrotor_mavtec_lisa_m_2_0.xml"
radio="radios/spektrum.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/TUDELFT/tudelft_mavtec_outdoor_demo.xml"
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml"
settings_modules=""
gui_color="#ffff00000000"
/>
</conf>
@@ -1,239 +0,0 @@
<!-- this is a LadyBird quadrotor frame 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.
-->
<!--
Applicable configuration:
airframe="airframes/examples/ladybird_lisa_s.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml"
-->
<airframe name="quadrotor_lisa_s">
<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_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 DELFT -->
<define name="MAG_X_NEUTRAL" value="286"/>
<define name="MAG_Y_NEUTRAL" value="-72"/>
<define name="MAG_Z_NEUTRAL" value="97"/>
<define name="MAG_X_SENS" value="3.94431833863" integer="16"/>
<define name="MAG_Y_SENS" value="4.14629702271" integer="16"/>
<define name="MAG_Z_SENS" value="4.54518768636" 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"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="14000"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="3.0" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="3.3" unit="V"/>
<define name="LOW_BAT_LEVEL" value="3.5" unit="V"/>
<define name="MAX_BAT_LEVEL" value="4.1" 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="2000"/>
<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_">
<define name="USE_GPS_ALT" value="1"/>
</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"/>
<define name="USE_GPS_HEADING" value="1"/>
</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>
<modules main_freq="512">
<module name="send_imu_mag_current"/>
</modules>
<firmware name="rotorcraft">
<target name="ap" board="lisa_s_1.0">
<module name="radio_control" type="datalink">
<!-- 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"/--> <!-- Esden (1BitSquared) Dx6i: TX 1 -->
<!--define name="RADIO_TRANSMITTER_CHAN" value="6"/-->
<!--define name="RADIO_TRANSMITTER_PROTOCOL" value="0x01"/-->
</module>
<configure name="USE_MAGNETOMETER" value="0"/>
<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="bluegiga"/>
<!-- 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="datalink"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins"/>
</firmware>
</airframe>
@@ -1,190 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Quadrotor LisaM_2.0 pwm">
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<!--define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/-->
</module>
<configure name="NO_LUFTBOOT" value="1"/>
<configure name="FLASH_MODE" value="SWD" />
<!-- MPU6000 is configured to output data at 2kHz, but polled at 512Hz PERIODIC_FREQUENCY -->
</target>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
<define name="USE_SERVOS_7AND8"/>
</module>
<module name="telemetry" type="xbee_api"/>
<module name="imu" type="mpu6000_hmc5883">
<!-- the default i2c2 port is used -->
</module>
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat">
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="30"/>
</module>
<module name="ins"/>
</firmware>
<modules>
<module name="gps" type="ubx_ucenter"/>
</modules>
<servos driver="Pwm">
<servo name="MOTOR_1" no="0" min="1000" neutral="1100" max="1900"/>
<servo name="MOTOR_2" no="1" min="1000" neutral="1100" max="1900"/>
<servo name="MOTOR_3" no="2" min="1000" neutral="1100" max="1900"/>
<servo name="MOTOR_4" no="3" min="1000" neutral="1100" max="1900"/>
<servo name="MOTOR_5" no="4" min="1000" neutral="1100" max="1900"/>
<servo name="MOTOR_6" no="5" min="1000" neutral="1100" max="1900"/>
<servo name="MOTOR_7" no="6" min="1000" neutral="1100" max="1900"/>
<servo name="MOTOR_8" no="7" min="1000" neutral="1100" max="1900"/>
</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="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="8"/>
<define name="SCALE" value="256"/>
<!-- order (and rotation direction) : MOTOR 1 (CW), MOTOR 2 (CCW), MOTOR 3 (CW), MOTOR 4 (CCW) -->
<!-- MOTOR 5 (CCW), MOTOR 6 (CW), MOTOR 7 (CCW), MOTOR 8 (CW) -->
<define name="ROLL_COEF" value="{ -256, -256, 256, 256, -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, -256, 256, 256, -256, -256, 256 }"/>
<define name="YAW_COEF" value="{ -256, 256, -256, 256, 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256, 256, 256, 256, 256 }"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="MOTOR_1" value="motor_mixing.commands[0]"/>
<set servo="MOTOR_2" value="motor_mixing.commands[1]"/>
<set servo="MOTOR_3" value="motor_mixing.commands[2]"/>
<set servo="MOTOR_4" value="motor_mixing.commands[3]"/>
<set servo="MOTOR_5" value="motor_mixing.commands[4]"/>
<set servo="MOTOR_6" value="motor_mixing.commands[5]"/>
<set servo="MOTOR_7" value="motor_mixing.commands[6]"/>
<set servo="MOTOR_8" value="motor_mixing.commands[7]"/>
</command_laws>
<section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="-9"/>
<define name="ACCEL_Y_NEUTRAL" value="24"/>
<define name="ACCEL_Z_NEUTRAL" value="65"/>
<define name="ACCEL_X_SENS" value="4.90393762843" integer="16"/>
<define name="ACCEL_Y_SENS" value="4.919330721" integer="16"/>
<define name="ACCEL_Z_SENS" value="4.85197383186" integer="16"/>
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="-40"/>
<define name="MAG_Y_NEUTRAL" value="-57"/>
<define name="MAG_Z_NEUTRAL" value="66"/>
<define name="MAG_X_SENS" value="4.5080259094" integer="16"/>
<define name="MAG_Y_SENS" value="4.56447191049" integer="16"/>
<define name="MAG_Z_SENS" value="5.11168950826" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="180." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.3770441"/>
<define name="H_Y" value="0.0193986"/>
<define name="H_Z" value="0.9259921"/>
</section>
<section name="INS" prefix="INS_">
</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_R" value="90." 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="400"/>
<define name="PHI_IGAIN" value="0"/>
<define name="THETA_PGAIN" value="300"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="0"/>
<define name="PSI_PGAIN" value="200"/>
<define name="PSI_DGAIN" value="400"/>
<define name="PSI_IGAIN" value="0"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</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.5"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="100"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="AUTOPILOT">
<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"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="12.4" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="12.8" unit="V"/>
<define name="LOW_BAT_LEVEL" value="13.5" unit="V"/>
<define name="MAX_BAT_LEVEL" value="16.8" unit="V"/>
</section>
</airframe>
@@ -1,188 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="bebop">
<firmware name="rotorcraft">
<target name="ap" board="bebop">
<configure name="USE_MAGNETOMETER" value="0"/> <!-- Disable magnetometer -->
</target>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
</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="datalink"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins" type="extended"/>
</firmware>
<modules main_freq="512">
<module name="geo_mag"/>
<module name="air_data"/>
<module name="send_imu_mag_current"/>
<!--module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</module-->
</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_">
<!-- 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_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 -->
<define name="MAG_X_NEUTRAL" value="18"/>
<define name="MAG_Y_NEUTRAL" value="157"/>
<define name="MAG_Z_NEUTRAL" value="49"/>
<define name="MAG_X_SENS" value="10.5007722373" integer="16"/>
<define name="MAG_Y_SENS" value="11.1147400462" integer="16"/>
<define name="MAG_Z_SENS" value="11.6479371722" integer="16"/>
<!-- Magneto current 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 -->
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
<define name="USE_GPS_HEADING" value="1"/>
</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="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_R" value="300" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="50"/>
<!-- reference -->
<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.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="2500"/>
<define name="PHI_DGAIN" value="300"/>
<define name="PHI_IGAIN" value="0"/>
<define name="THETA_PGAIN" value="2500"/>
<define name="THETA_DGAIN" value="300"/>
<define name="THETA_IGAIN" value="0"/>
<define name="PSI_PGAIN" value="8000"/>
<define name="PSI_DGAIN" value="700"/>
<define name="PSI_IGAIN" value="0"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</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="TRUE"/>
</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="100"/>
<define name="DGAIN" value="200"/>
<define name="IGAIN" value="15"/>
</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"/>
</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>
@@ -1,194 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- this is a quadrotor frame in X-configuration equiped with
* Autopilot: Lisa-m
* Actuators: HobbyKing Afro Slim 20A with BLHeli 14.0
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
* RC: one Spektrum sat http://wiki.paparazziuav.org/wiki/Subsystem/radio_control#Spektrum
-->
<airframe name="Quadrotor MavTec">
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<module name="radio_control" type="spektrum">
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<!--define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/-->
</module>
<configure name="NO_LUFTBOOT" value="1"/>
<!-- MPU6000 is configured to output data at 2kHz, but polled at 512Hz PERIODIC_FREQUENCY -->
</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">
<define name="SERVO_HZ" value="400"/>
</module>
<module name="telemetry" type="xbee_api"/>
<module name="imu" type="aspirin_v2.2"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat">
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="30"/>
</module>
<module name="ins"/>
</firmware>
<firmware name="test_progs">
</firmware>
<modules>
</modules>
<servos driver="Pwm">
<servo name="MOTOR_1" no="0" min="1148" neutral="1200" max="1832"/>
<servo name="MOTOR_2" no="1" min="1148" neutral="1200" max="1832"/>
<servo name="MOTOR_3" no="2" min="1148" neutral="1200" max="1832"/>
<servo name="MOTOR_4" no="3" min="1148" neutral="1200" max="1832"/>
</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="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"/>
<!-- order (and rotation direction) : NE (CCW), SE (CW), SW (CCW), NW (CW) -->
<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_motors_on,FALSE,values)"/>
<set servo="MOTOR_1" value="motor_mixing.commands[0]"/>
<set servo="MOTOR_2" value="motor_mixing.commands[1]"/>
<set servo="MOTOR_3" value="motor_mixing.commands[2]"/>
<set servo="MOTOR_4" value="motor_mixing.commands[3]"/>
</command_laws>
<section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="-9"/>
<define name="ACCEL_Y_NEUTRAL" value="24"/>
<define name="ACCEL_Z_NEUTRAL" value="65"/>
<define name="ACCEL_X_SENS" value="4.90393762843" integer="16"/>
<define name="ACCEL_Y_SENS" value="4.919330721" integer="16"/>
<define name="ACCEL_Z_SENS" value="4.85197383186" integer="16"/>
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="-88"/>
<define name="MAG_Y_NEUTRAL" value="42"/>
<define name="MAG_Z_NEUTRAL" value="44"/>
<define name="MAG_X_SENS" value="3.55840131062" integer="16"/>
<define name="MAG_Y_SENS" value="3.59312782171" integer="16"/>
<define name="MAG_Z_SENS" value="4.16199901926" 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="270." unit="deg"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.3770441"/>
<define name="H_Y" value="0.0193986"/>
<define name="H_Z" value="0.9259921"/>
<define name="USE_GPS_HEADING" value="0"/>
</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="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_R" value="90." unit="deg/s"/>
<define name="DEADBAND_R" 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="300." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<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="900"/>
<define name="PHI_DGAIN" value="200"/>
<define name="PHI_IGAIN" value="200"/>
<define name="THETA_PGAIN" value="900"/>
<define name="THETA_DGAIN" value="200"/>
<define name="THETA_IGAIN" value="200"/>
<define name="PSI_PGAIN" value="900"/>
<define name="PSI_DGAIN" value="200"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="75"/>
<define name="THETA_DDGAIN" value="75"/>
<define name="PSI_DDGAIN" value="75"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
<define name="MAX_SUM_ERR" value="2000000"/>
<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.5"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<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="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>
<section name="AUTOPILOT">
<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>
<section name="BAT">
<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="10.1" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
-88
View File
@@ -1,88 +0,0 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="1.5" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="8" name="Bebop2 Testing CyberZoo" security_height="0.4">
<header>
#include "autopilot.h"
#include "subsystems/ahrs.h"
#include "subsystems/electrical.h"
#include "subsystems/datalink/datalink.h"
</header>
<waypoints>
<waypoint height="0" name="HOME" x="0.0" y="0.0"/>
<waypoint height="2.2" name="CLIMB" x="1.2" y="-0.6"/>
<waypoint height="1.0" name="STDBY" x="-0.7" y="-0.8"/>
<waypoint name="TD" x="0.8" y="-1.7"/>
<waypoint lat="51.9906213" lon="4.3768628" name="_CZ1"/>
<waypoint lat="51.9905874" lon="4.3767766" name="_CZ2"/>
<waypoint lat="51.9906409" lon="4.3767226" name="_CZ3"/>
<waypoint lat="51.990667" lon="4.376806" name="_CZ4"/>
<waypoint lat="51.990624" lon="4.376845" name="_OZ1"/>
<waypoint lat="51.990601" lon="4.376782" name="_OZ2"/>
<waypoint lat="51.990638" lon="4.376748" name="_OZ3"/>
<waypoint lat="51.990657" lon="4.376804" name="_OZ4"/>
</waypoints>
<sectors>
<sector color="red" name="CyberZoo">
<corner name="_CZ1"/>
<corner name="_CZ2"/>
<corner name="_CZ3"/>
<corner name="_CZ4"/>
</sector>
<sector color="#FF9922" name="ObstacleZone">
<corner name="_OZ1"/>
<corner name="_OZ2"/>
<corner name="_OZ3"/>
<corner name="_OZ4"/>
</sector>
</sectors>
<exceptions>
<!-- <exception cond="!InsideCyberZoo(GetPosX(), GetPosY())" deroute="Standby"/>-->
<!--<exception cond="datalink_time > 22" deroute="Land here"/>-->
<!-- <exception cond="electrical.bat_low && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land"/>
<exception cond="electrical.bat_critical && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land here"/>-->
</exceptions>
<blocks>
<block name="Wait GPS">
<call fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 2)"/>
<call fun="NavSetGroundReferenceHere()"/> <!-- This sets the altitude ref -->
<!-- <call fun="NavSetAltitudeReferenceHere()"/> -->
</block>
<block name="Holding point">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block key="r" name="Start Engine">
<call fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block key="t" name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 0.9" deroute="Standby"/>
<call fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block key="s" name="Standby" strip_button="Standby" strip_icon="home.png">
<!-- <call fun="NavSetWaypointHere(WP_STDBY)"/>-->
<stay wp="STDBY"/>
</block>
<block key="l" name="Land here" strip_button="Land Here" strip_icon="land-right.png">
<call fun="NavSetWaypointHere(WP_TD)"/>
</block>
<block name="Land">
<go wp="TD"/>
</block>
<block name="Flare">
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="Landed"/>
<call fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="Landed">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>
-68
View File
@@ -1,68 +0,0 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="1.5" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="100" name="Outdoor basic flight plan" security_height="0.4">
<header>
#include "autopilot.h"
#include "subsystems/ahrs.h"
#include "subsystems/electrical.h"
#include "subsystems/datalink/datalink.h"
</header>
<waypoints>
<waypoint height="0" name="HOME" x="0.0" y="0.0"/>
<waypoint height="2.2" name="CLIMB" x="1.2" y="-0.6"/>
<waypoint height="1.0" name="STDBY" x="-0.7" y="-0.8"/>
<waypoint name="TD" x="0.8" y="-1.7"/>
</waypoints>
<exceptions>
<!-- <exception cond="!InsideCyberZoo(GetPosX(), GetPosY())" deroute="Standby"/>-->
<!--<exception cond="datalink_time > 22" deroute="Land here"/>-->
<!-- <exception cond="electrical.bat_low && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land"/>
<exception cond="electrical.bat_critical && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land here"/>-->
</exceptions>
<blocks>
<block name="Wait GPS">
<call fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 2)"/>
<call fun="NavSetGroundReferenceHere()"/> <!-- This sets the altitude ref -->
<!-- <call fun="NavSetAltitudeReferenceHere()"/> -->
</block>
<block name="Holding point">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block key="r" name="Start Engine">
<call fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block key="t" name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 0.9" deroute="Standby"/>
<call fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block key="s" name="Standby" strip_button="Standby" strip_icon="home.png">
<!-- <call fun="NavSetWaypointHere(WP_STDBY)"/>-->
<stay wp="STDBY"/>
</block>
<block key="l" name="Land here" strip_button="Land Here" strip_icon="land-right.png">
<call fun="NavSetWaypointHere(WP_TD)"/>
</block>
<block name="Land">
<go wp="TD"/>
</block>
<block name="Flare">
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="Landed"/>
<call fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="Landed">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>
-101
View File
@@ -1,101 +0,0 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<!-- Valkenburg -->
<!-- <flight_plan alt="40" ground_alt="0" lat0="52.170867" lon0="4.412194" max_dist_from_home="1000" name="Transitioning test" security_height="2"> -->
<!-- Delft -->
<flight_plan alt="40" ground_alt="0" lat0="51.979438" lon0="4.390148" max_dist_from_home="1000" name="Transitioning test" security_height="2">
<header>
#include "autopilot.h"
#include "subsystems/radio_control.h"
#include "subsystems/electrical.h"
#include "subsystems/actuators.h"
#include "firmwares/rotorcraft/guidance/guidance_h.h"
</header>
<waypoints>
<waypoint name="HOME" x="0.0" y="0.0"/>
<waypoint name="STDBY" x="-2.0" y="-5.0"/>
<waypoint name="p1" x="53.9" y="9.6"/>
<waypoint name="p2" x="-64.4" y="31.4"/>
<waypoint name="p3" x="-50.7" y="66.2"/>
<waypoint name="p4" x="60.0" y="41.3"/>
</waypoints>
<blocks>
<block name="Wait GPS">
<call fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 10)"/>
<call fun="NavSetGroundReferenceHere()"/>
</block>
<block name="Holding point">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block name="Start Engine">
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<call fun="NavResurrect()"/>
</block>
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 5.0" deroute="Climb"/>
<call fun="NavSetWaypointHere(WP_STDBY)"/>
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<attitude pitch="0" roll="0" throttle="0.5" until="FALSE" vmode="throttle"/>
</block>
<block name="Climb">
<exception cond="stateGetPositionEnu_f()->z > 20.0" deroute="Standby"/>
<call fun="NavSetWaypointHere(WP_STDBY)"/>
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<stay climb="2" vmode="climb" wp="STDBY"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<exception cond="radio_control.status > RC_OK" deroute="land"/>
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<stay wp="STDBY"/>
</block>
<block name="stay_p1">
<exception cond="radio_control.status > RC_OK" deroute="land"/>
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<stay wp="p1"/>
</block>
<block name="go_p2_p1">
<exception cond="radio_control.status > RC_OK" deroute="land"/>
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<go wp="p2"/>
<deroute block="stay_p1"/>
</block>
<block name="pylon_racing">
<exception cond="radio_control.status > RC_OK" deroute="land"/>
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<go wp="p2"/>
<go wp="p3"/>
<go wp="p4"/>
<go wp="p1"/>
<deroute block="stay_p1"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<call fun="NavSetWaypointHere(WP_STDBY)"/>
</block>
<block name="land">
<!-- <set value="FALSE" var="force_forward_flight"/> -->
<go wp="STDBY"/>
</block>
<block name="descent">
<exception cond="8.0 > stateGetPositionEnu_f()->z" deroute="descent_slow"/>
<stay climb="-1" vmode="climb" wp="STDBY"/>
</block>
<block name="descent_slow">
<exception cond="4.0 > stateGetPositionEnu_f()->z" deroute="flare"/>
<stay climb="-1" vmode="climb" wp="STDBY"/>
</block>
<block name="flare">
<exception cond="0.5 > sonar_adc.distance" deroute="landed"/>
<attitude pitch="0" roll="0" throttle="0.13" vmode="throttle"/>
</block>
<block name="landed">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>
@@ -1,93 +0,0 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="152" ground_alt="147" lat0="43 33 50.83" lon0="1 28 52.61" max_dist_from_home="150" name="Rotorcraft Basic (Enac)" security_height="2">
<header>
#include "autopilot.h"
</header>
<waypoints>
<waypoint name="HOME" x="0.0" y="0.0"/>
<waypoint name="CLIMB" x="0.0" y="5.0"/>
<waypoint name="STDBY" x="-2.0" y="-5.0"/>
<waypoint name="p1" x="3.6" y="-13.9"/>
<waypoint name="p2" x="27.5" y="-48.2"/>
<waypoint name="p3" x="16.7" y="-19.6"/>
<waypoint name="p4" x="13.7" y="-40.7"/>
<waypoint name="CAM" x="-20" y="-50" height="2."/>
<waypoint name="TD" x="5.6" y="-10.9"/>
</waypoints>
<blocks>
<block name="Wait GPS">
<call fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Geo init">
<while cond="LessThan(NavBlockTime(), 10)"/>
<call fun="NavSetGroundReferenceHere()"/>
<!--<call fun="NavSetAltitudeReferenceHere()"/>-->
</block>
<block name="Holding point">
<call fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
</block>
<block name="Start Engine">
<call fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
</block>
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 2.0" deroute="Standby"/>
<call fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay vmode="climb" climb="nav_climb_vspeed" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
</block>
<block name="stay_p1">
<stay wp="p1"/>
</block>
<block name="go_p2">
<call fun="nav_set_heading_deg(90)"/>
<go wp="p2"/>
<deroute block="stay_p1"/>
</block>
<block name="line_p1_p2">
<go from="p1" hmode="route" wp="p2"/>
<stay wp="p2" until="stage_time>10"/>
<go from="p2" hmode="route" wp="p1"/>
<deroute block="stay_p1"/>
</block>
<block name="route">
<go from="p1" hmode="route" wp="p3"/>
<go from="p3" hmode="route" wp="p4"/>
<go from="p4" hmode="route" wp="p1"/>
<deroute block="stay_p1"/>
</block>
<block name="Oval">
<oval p1="p1" p2="p2" radius="-1"/>
</block>
<block name="test yaw">
<go wp="p1"/>
<for var="i" from="1" to="16">
<heading alt="WaypointAlt(WP_p1)" course="90 * $i" until="stage_time > 3"/>
</for>
<deroute block="Standby"/>
</block>
<block name="circle CAM" pre_call="nav_set_heading_towards_waypoint(WP_CAM)">
<circle radius="nav_radius" wp="CAM"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call fun="NavSetWaypointHere(WP_TD)"/>
</block>
<block name="land">
<go wp="TD"/>
</block>
<block name="flare">
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" until="FALSE"/>
</block>
</blocks>
</flight_plan>