mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-04 05:42:49 +08:00
Added Iris airframe and 3dr radio
This commit is contained in:
@@ -109,6 +109,17 @@
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/logger_sd_spi_direct.xml"
|
||||
gui_color="#9b69e5ce9e7a"
|
||||
/>
|
||||
<aircraft
|
||||
name="Iris"
|
||||
ac_id="66"
|
||||
airframe="airframes/TUDELFT/tudelft_iris_indi.xml"
|
||||
radio="radios/FrSky3dr.xml"
|
||||
telemetry="telemetry/default_rotorcraft_slow.xml"
|
||||
flight_plan="flight_plans/TUDELFT/tudelft_delft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml [settings/control/stabilization_att_int_quat.xml] settings/control/stabilization_indi.xml"
|
||||
settings_modules="modules/geo_mag.xml modules/air_data.xml modules/gps_ubx_ucenter.xml"
|
||||
gui_color="#ffffcccaccca"
|
||||
/>
|
||||
<aircraft
|
||||
name="Logo600"
|
||||
ac_id="111"
|
||||
|
||||
@@ -89,6 +89,16 @@
|
||||
<arg flag="-speech" />
|
||||
</program>
|
||||
</session>
|
||||
<session name="Flight Paparazzi @57600">
|
||||
<program name="Data Link">
|
||||
<arg flag="-d" constant="/dev/paparazzi/link"/>
|
||||
<arg flag="-s" constant="57600"/>
|
||||
</program>
|
||||
<program name="Server"/>
|
||||
<program name="GCS">
|
||||
<arg flag="-speech" />
|
||||
</program>
|
||||
</session>
|
||||
<session name="Flight ACM1 @57600">
|
||||
<program name="Data Link">
|
||||
<arg flag="-d" constant="/dev/ttyACM1"/>
|
||||
|
||||
@@ -0,0 +1,250 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!-- this is a quadrotor frame equiped with
|
||||
* Autopilot: 3dr Pixhawk 2.4
|
||||
* IMU: MPU6000 + L3GD20 + LSM303D
|
||||
* Actuators: PWM motor controllers?
|
||||
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
|
||||
* RC: PPM
|
||||
-->
|
||||
<airframe name="iris_indi">
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="px4fmu_2.4" />
|
||||
<define name="BAT_CHECKER_DELAY" value="80" />
|
||||
<!-- amount of time it take for the bat to check -->
|
||||
<!-- to avoid bat low spike detection when strong pullup withch draws short sudden power-->
|
||||
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" />
|
||||
<!-- in seconds-->
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim" />
|
||||
<subsystem name="udp" />
|
||||
</target>
|
||||
<subsystem name="telemetry" type="transparent" />
|
||||
<!-- <subsystem name="imu" type="px4fmu_v2.4">-->
|
||||
<subsystem name="imu" type="mpu6000">
|
||||
<configure name="IMU_MPU_SPI_DEV" value="spi1" />
|
||||
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE2" />
|
||||
</subsystem>
|
||||
<subsystem name="gps" type="ublox" />
|
||||
<subsystem name="stabilization" type="indi" />
|
||||
<subsystem name="ahrs" type="int_cmpl_quat" />
|
||||
<subsystem name="ins" type="extended" />
|
||||
<subsystem name="current_sensor">
|
||||
<configure name="ADC_CURRENT_SENSOR" value="ADC_3" />
|
||||
</subsystem>
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART6" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="rotorcraft">
|
||||
<target name="fbw" board="px4io_2.4" />
|
||||
<subsystem name="motor_mixing" />
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1" />
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_KILL" />
|
||||
</subsystem>
|
||||
<!-- <subsystem name="radio_control" type="spektrum">-->
|
||||
<!-- <define name="RADIO_CONTROL_SPEKTRUM_NO_SIGN" value="1"/>-->
|
||||
<!-- <define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>-->
|
||||
<!-- <define name="RADIO_FBW_MODE" value="RADIO_AUX2"/>-->
|
||||
<!-- <define name="RADIO_MODE" value="RADIO_GEAR"/>-->
|
||||
<!-- <define name="SPEKTRUM_HAS_SOFT_BIND_PIN" value="1"/>-->
|
||||
<!-- </subsystem>-->
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="400" />
|
||||
</subsystem>
|
||||
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
|
||||
<!-- Switch to Failsafe or to Autopilot on RC loss? -->
|
||||
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO" />
|
||||
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_MANUAL" />
|
||||
<!-- Switch to Failsafe or to Manual on AP loss? -->
|
||||
<define name="INTERMCU_LOST_CNT" value="100" />
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART2" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_telemetry" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_baro_board" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_datalink" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<modules main_freq="512">
|
||||
<load name="px4io_flash.xml" />
|
||||
<load name="geo_mag.xml" />
|
||||
<load name="air_data.xml" />
|
||||
<load name="send_imu_mag_current.xml" />
|
||||
<load name="gps_ubx_ucenter.xml" />
|
||||
<!-- <load name="spektrum_soft_bind.xml"/>-->
|
||||
</modules>
|
||||
<section name="MISC">
|
||||
<define name="MilliAmpereOfAdc(adc)" value="((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)" />
|
||||
<!-- 100Amp = 2Volt -> 2482,42 tick/100Amp"(0.0402832*adc)" -->
|
||||
</section>
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="14" />
|
||||
<define name="MAG_Y_NEUTRAL" value="116" />
|
||||
<define name="MAG_Z_NEUTRAL" value="119" />
|
||||
<define name="MAG_X_SENS" value="5.09245681612" integer="16" />
|
||||
<define name="MAG_Y_SENS" value="5.29702744632" integer="16" />
|
||||
<define name="MAG_Z_SENS" value="5.65287938992" integer="16" />
|
||||
<define name="BODY_TO_IMU_PHI" value="180." unit="deg" />
|
||||
<define name="BODY_TO_IMU_THETA" value="180." 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>
|
||||
<rc_commands>
|
||||
<set command="THRUST" value="@THROTTLE" />
|
||||
<set command="ROLL" value="@ROLL" />
|
||||
<set command="PITCH" value="@PITCH" />
|
||||
<set command="YAW" value="@YAW" />
|
||||
</rc_commands>
|
||||
<servos driver="Default">
|
||||
<servo name="TOP_LEFT" no="2" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="TOP_RIGHT" no="0" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_RIGHT" no="3" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_LEFT" no="1" min="1140" neutral="1280" max="1850" />
|
||||
</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="FALSE" />
|
||||
<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>
|
||||
<!-- 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 -->
|
||||
<!-- Toulouse -->
|
||||
<!--define name="H_X" value="0.513081"/>
|
||||
<define name="H_Y" value="-0.00242783"/>
|
||||
<define name="H_Z" value="0.858336"/-->
|
||||
<!-- Delft -->
|
||||
<define name="H_X" value="0.3892503" />
|
||||
<define name="H_Y" value="0.0017972" />
|
||||
<define name="H_Z" value="0.9211303" />
|
||||
</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.017" />
|
||||
<define name="G1_Q" value="0.019" />
|
||||
<define name="G1_R" value="0.0011" />
|
||||
<define name="G2_R" value="0.089" />
|
||||
<!-- 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_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.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" />
|
||||
</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.4" />
|
||||
<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" />
|
||||
<define name="REF_MAX_SPEED" value="2" 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="4.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_RC_DIRECT" />
|
||||
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT" /> <!-- changing this mode may not work, since fbw will be in mode manual directly from rc!-->
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<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="10.8" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="11.1" unit="V" />
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V" />
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -0,0 +1,230 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!-- this is a quadrotor frame equiped with
|
||||
* Autopilot: 3dr Pixhawk 2.4
|
||||
* IMU: MPU6000
|
||||
* Actuators: PWM motor controllers
|
||||
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
|
||||
* RC: PPM
|
||||
-->
|
||||
<airframe name="iris_pid">
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="px4fmu_2.4" />
|
||||
<define name="BAT_CHECKER_DELAY" value="80" />
|
||||
<!-- amount of time it take for the bat to check -->
|
||||
<!-- to avoid bat low spike detection when strong pullup withch draws short sudden power-->
|
||||
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" />
|
||||
<!-- in seconds-->
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim" />
|
||||
<subsystem name="udp" />
|
||||
</target>
|
||||
<subsystem name="telemetry" type="transparent" />
|
||||
<subsystem name="imu" type="mpu6000">
|
||||
<!-- <subsystem name="imu" type="L3GD20">-->
|
||||
<configure name="IMU_MPU_SPI_DEV" value="spi1" />
|
||||
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE2" />
|
||||
</subsystem>
|
||||
<subsystem name="gps" type="ublox" />
|
||||
<subsystem name="stabilization" type="int_quat" />
|
||||
<subsystem name="ahrs" type="int_cmpl_quat" />
|
||||
<subsystem name="ins" type="extended" />
|
||||
<subsystem name="current_sensor">
|
||||
<configure name="ADC_CURRENT_SENSOR" value="ADC_3" />
|
||||
</subsystem>
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART6" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="rotorcraft">
|
||||
<target name="fbw" board="px4io_2.4" />
|
||||
<subsystem name="motor_mixing" />
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1" />
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_KILL" />
|
||||
</subsystem>
|
||||
<!-- <subsystem name="radio_control" type="spektrum">-->
|
||||
<!-- <define name="RADIO_CONTROL_SPEKTRUM_NO_SIGN" value="1"/>-->
|
||||
<!-- <define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>-->
|
||||
<!-- <define name="RADIO_FBW_MODE" value="RADIO_AUX2"/>-->
|
||||
<!-- <define name="RADIO_MODE" value="RADIO_GEAR"/>-->
|
||||
<!-- <define name="SPEKTRUM_HAS_SOFT_BIND_PIN" value="1"/>-->
|
||||
<!-- </subsystem>-->
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="400" />
|
||||
</subsystem>
|
||||
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
|
||||
<!-- Switch to Failsafe or to Autopilot on RC loss? -->
|
||||
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO" />
|
||||
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_MANUAL" />
|
||||
<!-- Switch to Failsafe or to Manual on AP loss? -->
|
||||
<define name="INTERMCU_LOST_CNT" value="100" />
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART2" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_telemetry" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_baro_board" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_datalink" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<modules main_freq="512">
|
||||
<load name="px4io_flash.xml" />
|
||||
<load name="geo_mag.xml" />
|
||||
<load name="air_data.xml" />
|
||||
<load name="send_imu_mag_current.xml" />
|
||||
<load name="gps_ubx_ucenter.xml" />
|
||||
<!-- <load name="spektrum_soft_bind.xml"/>-->
|
||||
</modules>
|
||||
<section name="MISC">
|
||||
<define name="MilliAmpereOfAdc(adc)" value="((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)" />
|
||||
<!-- 100Amp = 2Volt -> 2482,42 tick/100Amp"(0.0402832*adc)" -->
|
||||
</section>
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="14" />
|
||||
<define name="MAG_Y_NEUTRAL" value="116" />
|
||||
<define name="MAG_Z_NEUTRAL" value="119" />
|
||||
<define name="MAG_X_SENS" value="5.09245681612" integer="16" />
|
||||
<define name="MAG_Y_SENS" value="5.29702744632" integer="16" />
|
||||
<define name="MAG_Z_SENS" value="5.65287938992" integer="16" />
|
||||
<define name="BODY_TO_IMU_PHI" value="180." unit="deg" />
|
||||
<define name="BODY_TO_IMU_THETA" value="180." 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>
|
||||
<rc_commands>
|
||||
<set command="THRUST" value="@THROTTLE" />
|
||||
<set command="ROLL" value="@ROLL" />
|
||||
<set command="PITCH" value="@PITCH" />
|
||||
<set command="YAW" value="@YAW" />
|
||||
</rc_commands>
|
||||
<servos driver="Default">
|
||||
<servo name="TOP_LEFT" no="2" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="TOP_RIGHT" no="0" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_RIGHT" no="3" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_LEFT" no="1" min="1140" neutral="1280" max="1850" />
|
||||
</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="FALSE" />
|
||||
<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>
|
||||
<!-- 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 -->
|
||||
<!-- Toulouse -->
|
||||
<!--define name="H_X" value="0.513081"/>
|
||||
<define name="H_Y" value="-0.00242783"/>
|
||||
<define name="H_Z" value="0.858336"/-->
|
||||
<!-- Delft -->
|
||||
<define name="H_X" value="0.3892503" />
|
||||
<define name="H_Y" value="0.0017972" />
|
||||
<define name="H_Z" value="0.9211303" />
|
||||
</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="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="HOVER_KP" value="350" />
|
||||
<define name="HOVER_KD" value="85" />
|
||||
<define name="HOVER_KI" value="20" />
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.4" />
|
||||
<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" />
|
||||
<define name="REF_MAX_SPEED" value="2" 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="4.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_RC_DIRECT" />
|
||||
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT" />
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<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="10.8" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="11.1" unit="V" />
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V" />
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -0,0 +1,60 @@
|
||||
<?xml version="1.0"?>
|
||||
<!-- $Id$
|
||||
--
|
||||
-- (c) 2006 Pascal Brisset, Antoine Drouin
|
||||
--
|
||||
-- This file is part of paparazzi.
|
||||
--
|
||||
-- paparazzi is free software; you can redistribute it and/or modify
|
||||
-- it under the terms of the GNU General Public License as published by
|
||||
-- the Free Software Foundation; either version 2, or (at your option)
|
||||
-- any later version.
|
||||
--
|
||||
-- paparazzi is distributed in the hope that it will be useful,
|
||||
-- but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
-- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
-- GNU General Public License for more details.
|
||||
--
|
||||
-- You should have received a copy of the GNU General Public License
|
||||
-- along with paparazzi; see the file COPYING. If not, write to
|
||||
-- the Free Software Foundation, 59 Temple Place - Suite 330,
|
||||
-- Boston, MA 02111-1307, USA.
|
||||
-->
|
||||
|
||||
<!--
|
||||
-- Attributes of root (Radio) tag :
|
||||
-- name: name of RC
|
||||
-- data_min: min width of a pulse to be considered as a data pulse
|
||||
-- data_max: max width of a pulse to be considered as a data pulse
|
||||
-- sync_min: min width of a pulse to be considered as a synchro pulse
|
||||
-- sync_max: max width of a pulse to be considered as a synchro pulse
|
||||
-- pulse_type: POSITIVE ( Futaba and others) | NEGATIVE (JR)
|
||||
-- min, max and sync are expressed in micro-seconds
|
||||
-->
|
||||
|
||||
<!--
|
||||
-- Attributes of channel tag :
|
||||
-- ctl: name of the command on the transmitter - only for displaying
|
||||
-- function: logical command
|
||||
-- average: (boolean) channel filtered through several frames (for discrete commands)
|
||||
-- min: minimum pulse length (micro-seconds)
|
||||
-- max: maximum pulse length (micro-seconds)
|
||||
-- neutral: neutral pulse length (micro-seconds)
|
||||
-- Note: a command may be reversed by exchanging min and max values
|
||||
-->
|
||||
|
||||
<!DOCTYPE radio SYSTEM "radio.dtd">
|
||||
|
||||
<!-- Values set by experiment using X8R receiver SBus connection -->
|
||||
|
||||
<radio name="FrSky X9D + X8R receiver SBus connection" data_min="350" data_max="2500" sync_min ="8000" sync_max ="19000" pulse_type="POSITIVE">
|
||||
<channel ctl="D" function="ROLL" min="990" neutral="1490" max="2015" average="0"/>
|
||||
<channel ctl="C" function="PITCH" min="990" neutral="1490" max="2015" average="0"/>
|
||||
<channel ctl="A" function="THROTTLE" min="990" neutral="990" max="2015" average="0"/>
|
||||
<channel ctl="B" function="YAW" min="990" neutral="1490" max="2015" average="0"/>
|
||||
|
||||
<channel ctl="RSwtiches_Mix" function="MODE" min="1145" neutral="1500" max="1862" average="1"/>
|
||||
<channel ctl="TILT" function="AUX2" min="990" neutral="990" max="2015" average="0"/>
|
||||
<channel ctl="CH7" function="KILL" min="990" neutral="1490" max="2015" average="1"/>
|
||||
<channel ctl="E" function="UNUSED2" min="990" neutral="1900" max="2015" average="1"/>
|
||||
</radio>
|
||||
@@ -20,6 +20,9 @@ SUBSYSTEM=="tty", ATTRS{product}=="FT232R USB UART", SYMLINK+="ftdi-serial", GRO
|
||||
# Paparazzi STM32 Autopilot board USB CDC serial device
|
||||
SUBSYSTEM=="tty", ATTRS{manufacturer}=="Paparazzi UAV", ATTRS{product}=="CDC Serial STM32", SYMLINK+="paparazzi/stm32-usb-serial"
|
||||
|
||||
# Paparazzi 3dr radio
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6015", SYMLINK+="paparazzi/link", GROUP="plugdev"
|
||||
|
||||
# MaxStream xbee pro box
|
||||
SUBSYSTEM=="tty", ATTRS{product}=="MaxStream PKG-U", SYMLINK+="paparazzi/xbee", GROUP="plugdev"
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
<?xml version="1.0"?>
|
||||
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
|
||||
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
|
||||
<telemetry>
|
||||
<process name="Ap">
|
||||
<mode name="default">
|
||||
|
||||
Reference in New Issue
Block a user