mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-24 22:05:58 +08:00
[conf] Update rotating wing 25kg (#3455)
* [conf] Update rotating wing 25kg * [conf] Add easystar 3 * [conf] Update rotating wing 25kg * Fix ID's * Less changes * Test --------- Co-authored-by: Christophe De Wagter <dewagter@gmail.com>
This commit is contained in:
@@ -0,0 +1,267 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Easystar
|
||||
-->
|
||||
|
||||
<airframe name="Easystar3">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<configure name="PERIODIC_FREQUENCY" value="500"/>
|
||||
|
||||
<target name="ap" board="px4fmu_5.0_chibios">
|
||||
<define name="USE_BARO_BOARD" value="1"/>
|
||||
<module name="radio_control" type="sbus">
|
||||
<configure name="SBUS_PORT" value="UART3"/>
|
||||
</module>
|
||||
<module name="airspeed" type="ms45xx_i2c">
|
||||
<configure name="MS45XX_I2C_DEV" value="i2c4"/>
|
||||
</module>
|
||||
|
||||
<!-- Logger -->
|
||||
<module name="tlsf"/>
|
||||
<module name="pprzlog"/>
|
||||
<module name="logger" type="sd_chibios"/>
|
||||
<module name="flight_recorder"/>
|
||||
|
||||
<define name="RADIO_TH_HOLD" value="RADIO_AUX1"/> <!-- Throttle hold in command laws -->
|
||||
<define name="RADIO_FMODE" value="RADIO_AUX2"/> <!-- Throttle curve select -->
|
||||
<define name="RADIO_FBW_MODE" value="RADIO_AUX3"/> <!-- Switch between AP and FBW control -->
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_AUX1"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<module name="radio_control" type="datalink"/>
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
|
||||
<module name="logger_file">
|
||||
<define name="FILE_LOGGER_PATH" value="~/"/>
|
||||
</module>
|
||||
</target>
|
||||
|
||||
<module name="telemetry" type="transparent">
|
||||
<!--configure name="MODEM_PORT" value="usb_serial"/-->
|
||||
</module>
|
||||
|
||||
<module name="imu" type="mpu6000"/>
|
||||
<module name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B115200"/>
|
||||
</module>
|
||||
<!--module name="mag" type="rm3100">
|
||||
<configure name="MAG_RM3100_I2C_DEV" value="i2c4"/>
|
||||
<define name="MODULE_RM3100_UPDATE_AHRS" value="TRUE"/>
|
||||
<define name="RM3100_CHAN_X" value="1"/>
|
||||
<define name="RM3100_CHAN_Y" value="2"/>
|
||||
<define name="RM3100_CHAN_Z" value="0"/>
|
||||
<define name="RM3100_CHAN_X_SIGN" value="-"/>
|
||||
<define name="RM3100_CHAN_Y_SIGN" value="-"/>
|
||||
<define name="RM3100_CHAN_Z_SIGN" value="+"/>
|
||||
</module-->
|
||||
<module name="mag_ist8310">
|
||||
<define name="MODULE_IST8310_UPDATE_AHRS" value="TRUE"/>
|
||||
<configure name="MAG_IST8310_I2C_DEV" value="I2C3"/>
|
||||
<define name="IST8310_CHAN_X_SIGN" value="+"/>
|
||||
<define name="IST8310_CHAN_Y_SIGN" value="-"/>
|
||||
<define name="IST8310_CHAN_Z_SIGN" value="-"/>
|
||||
</module>
|
||||
<module name="ins" type="ekf2"/>
|
||||
|
||||
<module name="air_data"/>
|
||||
<module name="actuators" type="pwm"/>
|
||||
<module name="stabilization" type="indi">
|
||||
<define name="WLS_N_U_MAX" value="4"/>
|
||||
<define name="WLS_N_V_MAX" value="4"/>
|
||||
<configure name="INDI_NUM_ACT" value="3"/>
|
||||
</module>
|
||||
<module name="guidance" type="indi_hybrid_tailsitter"/>
|
||||
<module name="nav" type="hybrid">
|
||||
<define name="GUIDANCE_H_USE_REF" value="FALSE"/>
|
||||
</module>
|
||||
|
||||
<!--Switch advanced INDI scheduling functions on or off-->
|
||||
<define name="INDI_FUNCTIONS_RC_CHANNEL" value="6"/>
|
||||
</firmware>
|
||||
|
||||
<servos>
|
||||
<servo name="MOTOR" no="1" min="1090" neutral="1110" max="1870"/>
|
||||
<servo name="ELEVATOR" no="3" min="2000" neutral="1300" max="950"/>
|
||||
<servo name="RUDDER" no="4" min="2000" neutral="1500" max="1000"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<command_laws>
|
||||
<let var="th_hold" value="LessThan(RadioControlValues(RADIO_TH_HOLD), -4800)"/>
|
||||
<let var="manual" value="LessThan(RadioControlValues(RADIO_MODE), -4800)"/>
|
||||
<let var="motor_thrust" value="$manual? @THRUST : actuators_pprz[2]"/>
|
||||
|
||||
<set servo="MOTOR" value="$th_hold? -9600 : $motor_thrust"/>
|
||||
<set servo="ELEVATOR" value="$manual? @PITCH : actuators_pprz[0]"/>
|
||||
<set servo="RUDDER" value="$manual? @ROLL : actuators_pprz[1]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NO_GPS_LOST_WITH_RC_VALID" value="TRUE"/>
|
||||
<define name="NAV_CLIMB_VSPEED" value="3.5"/>
|
||||
<define name="NAV_DESCEND_VSPEED" value="-1.0"/>
|
||||
<define name="ROTORCRAFT_COMMANDS_YAW_ALWAYS_ENABLED" value="TRUE"/>
|
||||
<!--<define name="USE_AIRSPEED" value="TRUE"/>-->
|
||||
<define name="ARRIVED_AT_WAYPOINT" value="50.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FORWARD">
|
||||
<!--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="-90.0" unit="deg"/>
|
||||
<!-- For hybrid guidance by default set to 15-->
|
||||
<!--<define name="MAX_AIRSPEED" value="20.0"/>-->
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- Rotate the IMU -->
|
||||
<define name="MPU_CHAN_X" value="1"/>
|
||||
<define name="MPU_CHAN_Y" value="0"/>
|
||||
<define name="MPU_CHAN_Z" value="2"/>
|
||||
<define name="MPU_X_SIGN" value="1"/>
|
||||
<define name="MPU_Y_SIGN" value="-1"/>
|
||||
<define name="MPU_Z_SIGN" value="1"/>
|
||||
|
||||
<!-- Calibrated 2022-08-30 (Next to cyberzoo body only) -->
|
||||
<define name="ACCEL_X_NEUTRAL" value="712"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="-69"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="37"/>
|
||||
<define name="ACCEL_X_SENS" value="4.3946795784709405" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="4.892643085453153" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="4.82814860878492" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="96"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="7"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="71"/>
|
||||
<define name="MAG_X_SENS" value="12.969012324781003" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="12.93272866894083" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="13.211883046446026" integer="16"/>
|
||||
|
||||
<!-- Calibrated 2022-08-31 (Outside TU Delft) -->
|
||||
<!--define name="MAG_CALIB" value="{{.abi_id=5, .calibrated={.neutral=true, .scale=true},.neutral={-14,3,42}, .scale={{17279,2209,36874},{30247,3800,64095}}}}"/-->
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0.0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
|
||||
<!-- control effectiveness, scaled by INDI_G_SCALING (1000)-->
|
||||
<define name="G1_ROLL" value="{ 0, 0, 0}"/>
|
||||
<define name="G1_PITCH" value="{-8.79, 0, 0}"/>
|
||||
<define name="G1_YAW" value="{ 0,-15.97, 0}"/>
|
||||
<define name="G1_THRUST" value="{ 0, 0, -1.8}"/>
|
||||
<!--Counter torque effect of spinning up a rotor-->
|
||||
<define name="G2" value="{0, 0, 0}"/>
|
||||
|
||||
<!-- 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="15.0"/>
|
||||
<define name="REF_RATE_R" value="15.0"/>
|
||||
|
||||
<!--Maxium yaw rate, to avoid instability-->
|
||||
<define name="MAX_R" value="100.0" unit="deg/s"/>
|
||||
|
||||
<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>
|
||||
<define name="FILT_CUTOFF" value="5.0"/>
|
||||
|
||||
<!-- first order actuator dynamics -->
|
||||
<define name="ACT_FREQ" value="{53.9, 53.9, 23.6}"/>
|
||||
<define name="ACT_RATE_LIMIT" value="{170, 170, 9600}"/>
|
||||
<define name="ACT_IS_SERVO" value="{1, 1, 0}"/>
|
||||
|
||||
<!-- Adaptive Learning Rate -->
|
||||
<define name="USE_ADAPTIVE" value="FALSE"/>
|
||||
<define name="ADAPTIVE_MU" value="0.0001"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="40." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="25." 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="0.001" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="ctrl_eff_scheduling" prefix="FWD_">
|
||||
<!-- control effectiveness, scaled by INDI_G_SCALING (1000)-->
|
||||
<define name="G1_ROLL" value="{ 0, 0, 0}"/>
|
||||
<define name="G1_PITCH" value="{-8.79, 0, 0}"/>
|
||||
<define name="G1_YAW" value="{ 0,-15.97, 0}"/>
|
||||
<define name="G1_THRUST" value="{ 0, 0, -0.7}"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="HOVER_KP" value="310"/>
|
||||
<define name="HOVER_KD" value="130"/>
|
||||
<define name="HOVER_KI" value="10"/>
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.4"/>
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="45" unit="deg"/>
|
||||
<define name="USE_SPEED_REF" value="TRUE"/>
|
||||
<define name="PGAIN" value="60"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="AGAIN" value="0"/>
|
||||
<define name="IGAIN" value="20"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_INDI_HYBRID" prefix="GUIDANCE_INDI_">
|
||||
<define name="POS_GAIN" value="0.2"/>
|
||||
<define name="POS_GAINZ" value="0.2"/>
|
||||
<define name="SPEED_GAIN" value="1.0"/>
|
||||
<define name="SPEED_GAINZ" value="1.0"/>
|
||||
<define name="MAX_AIRSPEED" value="12."/>
|
||||
<define name="ZERO_AIRSPEED" value="FALSE"/>
|
||||
<define name="NAV_SPEED_MARGIN" value="10.0"/>
|
||||
<define name="PITCH_EFF_SCALING" value="1.0"/>
|
||||
<define name="PITCH_LIFT_EFF" value="0.12"/>
|
||||
<define name="HEADING_BANK_GAIN" value="15."/>
|
||||
<!--define name="SPECIFIC_FORCE_GAIN" value="-1300."/-->
|
||||
<!--define name="THRUST_DYNAMICS" value="0.04"/-->
|
||||
<define name="MIN_THROTTLE" value="0.0"/>
|
||||
<define name="MIN_THROTTLE_FWD" value="0.0"/>
|
||||
<define name="MIN_PITCH" value="-115."/>
|
||||
<define name="MAX_PITCH" value="-75."/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
|
||||
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_FORWARD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="9.6" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.6" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ele_left, ele_right, mot" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="disco_rotorcraft" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="NO_MOTOR_MIXING" value="TRUE"/>
|
||||
<define name="COMMANDS_NB" value="3"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -0,0 +1,256 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
Easystart
|
||||
-->
|
||||
|
||||
<airframe name="Easystar3">
|
||||
|
||||
<firmware name="fixedwing">
|
||||
<configure name="USE_MAGNETOMETER" value="TRUE"/>
|
||||
|
||||
<target name="ap" board="px4fmu_5.0_chibios">
|
||||
<define name="USE_BARO_BOARD" value="1"/>
|
||||
<configure name="PERIODIC_FREQUENCY" value="120"/>
|
||||
<module name="radio_control" type="sbus">
|
||||
<configure name="SBUS_PORT" value="UART3"/>
|
||||
</module>
|
||||
</target>
|
||||
<target name="sim" board="pc">
|
||||
<configure name="SYS_TIME_FREQUENCY" value="120"/>
|
||||
<configure name="PERIODIC_FREQUENCY" value="60"/>
|
||||
<module name="radio_control" type="ppm"/>
|
||||
</target>
|
||||
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_PORT" value="usb_serial"/>
|
||||
</module>
|
||||
|
||||
<module name="imu" type="mpu6000"/>
|
||||
<module name="ahrs" type="float_dcm"/>
|
||||
<module name="ins" type="alt_float"/>
|
||||
<!--module name="ins" type="ekf2">
|
||||
<define name="NO_RESET_UPDATE_SETPOINT_HEADING" value="true"/>
|
||||
</module-->
|
||||
<module name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B115200"/>
|
||||
</module>
|
||||
<module name="airspeed" type="ms45xx_i2c">
|
||||
<configure name="MS45XX_I2C_DEV" value="i2c4"/>
|
||||
</module>
|
||||
<module name="air_data"/>
|
||||
<module name="actuators" type="pwm"/>
|
||||
<module name="control" type="new"/>
|
||||
<module name="navigation"/>
|
||||
<module name="mag_ist8310">
|
||||
<define name="MODULE_IST8310_UPDATE_AHRS" value="TRUE"/>
|
||||
<configure name="MAG_IST8310_I2C_DEV" value="I2C3"/>
|
||||
<define name="IST8310_CHAN_X_SIGN" value="+"/>
|
||||
<define name="IST8310_CHAN_Y_SIGN" value="-"/>
|
||||
<define name="IST8310_CHAN_Z_SIGN" value="-"/>
|
||||
</module>
|
||||
|
||||
<!-- Logger -->
|
||||
<module name="tlsf"/>
|
||||
<module name="pprzlog"/>
|
||||
<module name="logger" type="sd_chibios"/>
|
||||
<module name="flight_recorder"/>
|
||||
|
||||
</firmware>
|
||||
|
||||
<servos>
|
||||
<servo name="MOTOR" no="1" min="1090" neutral="1110" max="1870"/>
|
||||
<servo name="ELEVATOR" no="3" min="1600" neutral="1300" max="950"/>
|
||||
<servo name="RUDDER" no="4" min="2000" neutral="1500" max="1000"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
</rc_commands>
|
||||
|
||||
<command_laws>
|
||||
<set servo="MOTOR" value="@THROTTLE"/>
|
||||
<set servo="ELEVATOR" value="@PITCH"/>
|
||||
<set servo="RUDDER" value="@ROLL"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="0.85"/>
|
||||
<define name="MAX_PITCH" value="0.6"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- Rotate the IMU -->
|
||||
<define name="MPU_CHAN_X" value="1"/>
|
||||
<define name="MPU_CHAN_Y" value="0"/>
|
||||
<define name="MPU_CHAN_Z" value="2"/>
|
||||
<define name="MPU_X_SIGN" value="1"/>
|
||||
<define name="MPU_Y_SIGN" value="-1"/>
|
||||
<define name="MPU_Z_SIGN" value="1"/>
|
||||
|
||||
<!-- Calibrated 2022-08-30 (Next to cyberzoo body only) -->
|
||||
<define name="ACCEL_X_NEUTRAL" value="712"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="-69"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="37"/>
|
||||
<define name="ACCEL_X_SENS" value="4.3946795784709405" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="4.892643085453153" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="4.82814860878492" integer="16"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="96"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="7"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="71"/>
|
||||
<define name="MAG_X_SENS" value="12.969012324781003" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="12.93272866894083" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="13.211883046446026" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0" unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0.0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<!--section name="AHRS" prefix="AHRS_">
|
||||
<define name="H_X" value="0.5141"/>
|
||||
<define name="H_Y" value="0.0002"/>
|
||||
<define name="H_Z" value="0.8576"/>
|
||||
</section-->
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="H_X" value="0.5141"/>
|
||||
<define name="H_Y" value="0.0002"/>
|
||||
<define name="H_Z" value="0.8576"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<!--define name="MilliAmpereOfAdc(_adc)" value="(_adc-632)*4.14"/-->
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="12." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
|
||||
|
||||
<define name="APP_ANGLE" value="8" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="0.12"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="4."/>
|
||||
<!-- disable climb rate limiter -->
|
||||
<define name="AUTO_CLIMB_LIMIT" value="2*V_CTL_ALTITUDE_MAX_CLIMB"/>
|
||||
|
||||
<!-- Cruise throttle + limits -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.4"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.1"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
|
||||
|
||||
<!-- Climb loop (throttle) -->
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.088" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0.004"/>
|
||||
<define name="AUTO_THROTTLE_DGAIN" value="0.0"/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0."/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.15"/>
|
||||
|
||||
<!-- Climb loop (pitch) -->
|
||||
<define name="AUTO_PITCH_PGAIN" value="0.027"/>
|
||||
<define name="AUTO_PITCH_DGAIN" value="0.01"/>
|
||||
<define name="AUTO_PITCH_IGAIN" value="0.0"/>
|
||||
<!--define name="AUTO_PITCH_CLIMB_THROTTLE_INCREMENT" value="0.14"/-->
|
||||
<define name="AUTO_PITCH_MAX_PITCH" value="20" unit="deg"/>
|
||||
<define name="AUTO_PITCH_MIN_PITCH" value="-20" unit="deg"/>
|
||||
|
||||
<!-- airspeed control -->
|
||||
<define name="AUTO_AIRSPEED_SETPOINT" value="16."/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_PGAIN" value="0.1"/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_DGAIN" value="0.12"/>
|
||||
<define name="AUTO_AIRSPEED_THROTTLE_IGAIN" value="0.0"/>
|
||||
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.06"/>
|
||||
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.0"/>
|
||||
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.042"/>
|
||||
<define name="AIRSPEED_MAX" value="30"/>
|
||||
<define name="AIRSPEED_MIN" value="10"/>
|
||||
|
||||
<!-- groundspeed control -->
|
||||
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15"/>
|
||||
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
|
||||
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>
|
||||
|
||||
<!-- pitch trim -->
|
||||
<define name="PITCH_LOITER_TRIM" value="0." unit="deg"/>
|
||||
<define name="PITCH_DASH_TRIM" value="0." unit="deg"/>
|
||||
|
||||
<define name="THROTTLE_SLEW" value="0.1"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="0.743"/>
|
||||
<define name="COURSE_TAU" value="0.5"/>
|
||||
<define name="ROLL_MAX_SETPOINT" value="30." unit="deg"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="30." unit="deg"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-30." unit="deg"/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="5000."/>
|
||||
<define name="ROLL_RATE_GAIN" value="250."/>
|
||||
<define name="ROLL_IGAIN" value="50."/>
|
||||
<define name="ROLL_KFFA" value="0"/>
|
||||
<define name="ROLL_KFFD" value="0"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="17250"/>
|
||||
<define name="PITCH_DGAIN" value="500."/>
|
||||
<define name="PITCH_IGAIN" value="400"/>
|
||||
<define name="PITCH_KFFA" value="0."/>
|
||||
<define name="PITCH_KFFD" value="0."/>
|
||||
|
||||
<define name="PITCH_OF_ROLL" value="1." unit="deg"/>
|
||||
<define name="AILERON_OF_THROTTLE" value="0.0"/>
|
||||
<define name="ELEVATOR_OF_ROLL" value="1400"/>
|
||||
</section>
|
||||
|
||||
<section name="NAV">
|
||||
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DELAY_WITHOUT_GPS" value="2" unit="s"/>
|
||||
<define name="DEFAULT_THROTTLE" value="0.3" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.3" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.5" unit="rad"/>
|
||||
<define name="HOME_RADIUS" value="100" unit="m"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="50"/><!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
|
||||
<define name="BLEND_END" value="15"/><!-- Altitude Error to Blend Aggressive to Regular Climb Modes CANNOT BE ZERO!!-->
|
||||
<define name="CLIMB_THROTTLE" value="0.9"/><!-- Gaz for Aggressive Climb -->
|
||||
<define name="CLIMB_PITCH" value="0.35"/><!-- Pitch for Aggressive Climb -->
|
||||
<define name="DESCENT_THROTTLE" value="0.05"/><!-- Gaz for Aggressive Decent -->
|
||||
<define name="DESCENT_PITCH" value="-0.35"/><!-- Pitch for Aggressive Decent -->
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMU">
|
||||
<define name="ROLL_RESPONSE_FACTOR" value="20"/>
|
||||
<define name="JSBSIM_MODEL" value=""Malolo1""/>
|
||||
<!--define name="JSBSIM_INIT" value=""Malolo1-IC""/-->
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15.0"/>
|
||||
<define name="JSBSIM_IR_ROLL_NEUTRAL" value="RadOfDeg(0.)"/>
|
||||
<define name="JSBSIM_IR_PITCH_NEUTRAL" value="RadOfDeg(0.)"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -41,11 +41,11 @@
|
||||
</module>
|
||||
|
||||
<!-- MAVLink Genius communication -->
|
||||
<module name="mavlink">
|
||||
<!--module name="mavlink">
|
||||
<configure name="MAVLINK_BAUD" value="B57600"/>
|
||||
<configure name="MAVLINK_PORT" value="UART3"/>
|
||||
<define name="MAV_AUTOPILOT_ID" value="MAV_AUTOPILOT_ARDUPILOTMEGA"/>
|
||||
</module>
|
||||
</module-->
|
||||
|
||||
<!-- Log in high speed (Remove for outdoor flights) -->
|
||||
<!-- <define name="IMU_LOG_HIGHSPEED" value="TRUE"/> -->
|
||||
@@ -164,14 +164,11 @@
|
||||
<module name="agl_dist"/>
|
||||
<module name="approach_moving_target"/>
|
||||
|
||||
|
||||
<!-- Forward FuelCell data back to the GCS -->
|
||||
<module name="can_fuelcell"/>
|
||||
|
||||
</firmware>
|
||||
|
||||
|
||||
|
||||
<!-- Can bus 1 actuators -->
|
||||
<servos driver="Uavcan1">
|
||||
<servo no="0" name="BMOTOR_FRONT" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
|
||||
@@ -41,11 +41,11 @@
|
||||
</module>
|
||||
|
||||
<!-- MAVLink Genius communication -->
|
||||
<module name="mavlink">
|
||||
<!--module name="mavlink">
|
||||
<configure name="MAVLINK_BAUD" value="B57600"/>
|
||||
<configure name="MAVLINK_PORT" value="UART3"/>
|
||||
<define name="MAV_AUTOPILOT_ID" value="MAV_AUTOPILOT_ARDUPILOTMEGA"/>
|
||||
</module>
|
||||
</module-->
|
||||
|
||||
<!-- Log in high speed (Remove for outdoor flights) -->
|
||||
<!-- <define name="IMU_LOG_HIGHSPEED" value="TRUE"/> -->
|
||||
@@ -156,7 +156,7 @@
|
||||
<!-- Other -->
|
||||
<module name="sys_id_doublet"/>
|
||||
<module name="sys_id_auto_doublets"/>
|
||||
<module name="ground_detect"/>
|
||||
<module name="ground_detect"/>
|
||||
<module name="rotwing_state"/>
|
||||
<module name="preflight_checks">
|
||||
<define name="SDLOG_PREFLIGHT_ERROR" value="TRUE"/>
|
||||
@@ -169,15 +169,13 @@
|
||||
|
||||
</firmware>
|
||||
|
||||
|
||||
|
||||
<!-- Can bus 1 actuators -->
|
||||
<servos driver="Uavcan1">
|
||||
<servo no="0" name="BMOTOR_FRONT" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="1" name="BMOTOR_RIGHT" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="2" name="BMOTOR_BACK" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="3" name="MOTOR_LEFT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC is neutral -->
|
||||
<servo no="4" name="BMOTOR_PUSH" min="-3276" neutral="-2500" max="3605"/> <!-- Supercan (1100-1940us) -->
|
||||
<servo no="4" name="BMOTOR_PUSH" min="-4095" neutral="-3522" max="4095"/> <!-- Supercan (1070 idle 1000-2000) -->
|
||||
<servo no="5" name="BPARACHUTE" min="-8191" neutral="0" max="8191"/>
|
||||
</servos>
|
||||
|
||||
@@ -197,7 +195,7 @@
|
||||
<servo no="1" name="MOTOR_RIGHT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
|
||||
<servo no="2" name="MOTOR_BACK" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
|
||||
<servo no="3" name="BMOTOR_LEFT" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="4" name="MOTOR_PUSH" min="-3276" neutral="-2500" max="3605"/> <!-- Supercan (1100-1940us) -->
|
||||
<servo no="4" name="MOTOR_PUSH" min="-4095" neutral="-3522" max="4095"/> <!-- Supercan (1070 idle 1000-2000) -->
|
||||
<servo no="5" name="PARACHUTE" min="-8191" neutral="0" max="8191"/>
|
||||
</servos>
|
||||
|
||||
|
||||
@@ -0,0 +1,368 @@
|
||||
<!-- This is a Rotating Wing 25kg
|
||||
* Airframe: ???
|
||||
* Autopilot: Pixhawk 6X
|
||||
* Datalink: Herelink
|
||||
* GPS: UBlox F9P (2x)
|
||||
* RC: SBUS Crossfire (diversity)
|
||||
-->
|
||||
|
||||
<airframe name="RotatingWing7">
|
||||
<description>RotatingWing 7</description>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="pixhawk_6x">
|
||||
<configure name="PERIODIC_FREQUENCY" value="500"/> <!-- Configure the main periodic frequency to 500Hz -->
|
||||
|
||||
<module name="radio_control" type="sbus"/>
|
||||
<module name="sys_mon"/>
|
||||
<module name="flight_recorder"/>
|
||||
|
||||
<!-- RC switches -->
|
||||
<define name="RADIO_TH_HOLD" value="RADIO_AUX1"/>
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_AUX1"/>
|
||||
<define name="RADIO_FMODE" value="RADIO_AUX2"/>
|
||||
<define name="RADIO_FBW_MODE" value="RADIO_AUX3"/>
|
||||
<define name="RADIO_CONTROL_THRUST_X" value="RADIO_AUX4"/>
|
||||
<define name="RADIO_PARACHUTE" value="RADIO_AUX6"/>
|
||||
|
||||
<!-- EKF2 configure inputs -->
|
||||
<define name="INS_EKF2_GYRO_ID" value="IMU_PIXHAWK2_ID"/>
|
||||
<define name="INS_EKF2_ACCEL_ID" value="IMU_PIXHAWK2_ID"/>
|
||||
<define name="INS_EKF2_MAG_ID" value="MAG_RM3100_SENDER_ID"/>
|
||||
|
||||
<!--Only send gyro and accel that is being used-->
|
||||
<define name="IMU_GYRO_ABI_SEND_ID" value="IMU_PIXHAWK2_ID"/>
|
||||
<define name="IMU_ACCEL_ABI_SEND_ID" value="IMU_PIXHAWK2_ID"/>
|
||||
|
||||
<!-- Sensors connected to supercan -->
|
||||
<module name="range_sensor_uavcan"/>
|
||||
<module name="power_uavcan">
|
||||
<define name="POWER_UAVCAN_BATTERY_CIRCUITS" value="{{14,0},{6,1}}"/>
|
||||
</module>
|
||||
|
||||
<!-- MAVLink Genius communication -->
|
||||
<!--module name="mavlink">
|
||||
<configure name="MAVLINK_BAUD" value="B57600"/>
|
||||
<configure name="MAVLINK_PORT" value="UART3"/>
|
||||
<define name="MAV_AUTOPILOT_ID" value="MAV_AUTOPILOT_ARDUPILOTMEGA"/>
|
||||
</module-->
|
||||
|
||||
<!-- Log in high speed (Remove for outdoor flights) -->
|
||||
<!-- <define name="IMU_LOG_HIGHSPEED" value="TRUE"/> -->
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<module name="radio_control" type="datalink"/>
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
|
||||
<!--Not dealing with these in the simulation-->
|
||||
<define name="RADIO_TH_HOLD" value="0"/> <!-- Throttle hold in command laws -->
|
||||
<define name="RADIO_FMODE" value="0"/> <!-- Throttle curve select -->
|
||||
<define name="RADIO_FBW_MODE" value="0"/> <!-- Switch between AP and FBW control -->
|
||||
<define name="RADIO_KILL_SWITCH" value="0"/>
|
||||
<define name="RADIO_CONTROL_THRUST_X" value="0"/>
|
||||
<define name="RADIO_PARACHUTE" value="0"/>
|
||||
|
||||
<define name="PREFLIGHT_CHECK_BYPASS" value="TRUE"/>
|
||||
<define name="USE_SONAR" value="1"/> <!-- Because uavcan can't handle simulation yet -->
|
||||
|
||||
|
||||
<!-- MAVLink simulation -->
|
||||
<module name="mavlink">
|
||||
<define name="MAV_AUTOPILOT_ID" value="MAV_AUTOPILOT_ARDUPILOTMEGA"/>
|
||||
<define name="UDP1_PORT_OUT" value="24550"/>
|
||||
<define name="UDP1_PORT_IN" value="14551"/>
|
||||
<define name="UDP1_HOST" value="127.0.0.1"/>
|
||||
<define name="MAVLINK_DEBUG" value="printf"/>
|
||||
<configure name="MAVLINK_PORT" value="UDP1"/>
|
||||
</module>
|
||||
</target>
|
||||
|
||||
<!-- Herelink datalink -->
|
||||
<module name="telemetry" type="transparent">
|
||||
<!--configure name="MODEM_PORT" value="usb_serial"/-->
|
||||
<configure name="MODEM_BAUD" value="B460800"/>
|
||||
</module>
|
||||
|
||||
<!-- Sensors -->
|
||||
<module name="mag" type="rm3100">
|
||||
<configure name="MAG_RM3100_I2C_DEV" value="I2C1"/>
|
||||
<define name="MODULE_RM3100_UPDATE_AHRS" value="TRUE"/>
|
||||
</module>
|
||||
<module name="airspeed" type="ms45xx_i2c">
|
||||
<configure name="MS45XX_I2C_DEV" value="I2C2"/>
|
||||
<define name="MS45XX_PRESSURE_SCALE" value="1.3231"/>
|
||||
<define name="USE_AIRSPEED_LOWPASS_FILTER" value="TRUE"/>
|
||||
<define name="MS45XX_LOWPASS_TAU" value="0.15"/>
|
||||
</module>
|
||||
<module name="airspeed" type="uavcan">
|
||||
<define name="AIRSPEED_UAVCAN_LOWPASS_FILTER" value="TRUE" />
|
||||
<define name="AIRSPEED_UAVCAN_LOWPASS_PERIOD" value="0.1" />
|
||||
<define name="AIRSPEED_UAVCAN_SEND_ABI" value="0" /> <!-- Read Airspeed for logging but do not use it -->
|
||||
</module>
|
||||
<module name="air_data"/>
|
||||
|
||||
<configure name="PRIMARY_GPS" value="ublox"/>
|
||||
<configure name="SECONDARY_GPS" value="ublox2"/>
|
||||
<module name="gps" type="ublox">
|
||||
<configure name="UBX_GPS_BAUD" value="B460800"/>
|
||||
<configure name="UBX2_GPS_BAUD" value="B460800"/>
|
||||
<define name="USE_GPS_UBX_RTCM" value="TRUE"/>
|
||||
</module>
|
||||
|
||||
<!-- IMU / INS -->
|
||||
<module name="imu" type="pixhawk6x"/>
|
||||
<module name="ins" type="ekf2">
|
||||
<!-- The Cube is mounted 37cm forwards of the CG -->
|
||||
<define name="INS_EKF2_IMU_POS_X" value="0.324"/>
|
||||
<define name="INS_EKF2_IMU_POS_Y" value="0.0"/>
|
||||
<define name="INS_EKF2_IMU_POS_Z" value="0.0"/>
|
||||
|
||||
<!-- The main GPS is mounted at the tail 1.44m backwards and 10cm above the CG -->
|
||||
<define name="INS_EKF2_GPS_POS_X" value="-1.28"/>
|
||||
<define name="INS_EKF2_GPS_POS_Y" value="0.0"/>
|
||||
<define name="INS_EKF2_GPS_POS_Z" value="0.1"/>
|
||||
</module>
|
||||
|
||||
<!-- Actuators on dual CAN bus -->
|
||||
<module name="actuators" type="uavcan">
|
||||
<configure value="TRUE" name="UAVCAN_USE_CAN1"/>
|
||||
<configure value="TRUE" name="UAVCAN_USE_CAN2"/>
|
||||
<define value="FALSE" name="UAVCAN_ACTUATORS_USE_CURRENT"/>
|
||||
<!-- Don't oversaturate the UAVCAN bus -->
|
||||
<define name="ACTUATORS_UAVCAN_RAW_DIV" value="2"/> <!-- ESC's at half the PERIODIC_FREQ -->
|
||||
<define name="ACTUATORS_UAVCAN_CMD_DIV" value="4"/> <!-- Servo's at 1/4 the PERIODIC_FREQ -->
|
||||
</module>
|
||||
<!-- Rotation mechanism actuator on UART -->
|
||||
<module name="actuators" type="faulhaber"/>
|
||||
|
||||
<!-- Control -->
|
||||
<module name="stabilization" type="indi">
|
||||
<configure name="INDI_NUM_ACT" value="9"/>
|
||||
<configure name="INDI_OUTPUTS" value="5"/>
|
||||
<define name="WLS_N_U_MAX" value="9"/>
|
||||
<define name="WLS_N_V_MAX" value="5"/>
|
||||
</module>
|
||||
|
||||
<module name="stabilization" type="rate_indi"/>
|
||||
|
||||
<module name="eff_scheduling_rotwing"/>
|
||||
|
||||
<module name="guidance" type="indi_hybrid_quadplane"/>
|
||||
<module name="nav" type="hybrid">
|
||||
<define name="GUIDANCE_H_USE_REF" value="FALSE"/>
|
||||
</module>
|
||||
|
||||
<!-- Other -->
|
||||
<module name="sys_id_doublet"/>
|
||||
<module name="sys_id_auto_doublets"/>
|
||||
<module name="ground_detect"/>
|
||||
<module name="rotwing_state"/>
|
||||
<module name="preflight_checks">
|
||||
<define name="SDLOG_PREFLIGHT_ERROR" value="TRUE"/>
|
||||
</module>
|
||||
<module name="agl_dist"/>
|
||||
<module name="approach_moving_target"/>
|
||||
|
||||
<!-- Forward FuelCell data back to the GCS -->
|
||||
<module name="can_fuelcell"/>
|
||||
|
||||
</firmware>
|
||||
|
||||
<!-- Can bus 1 actuators -->
|
||||
<servos driver="Uavcan1">
|
||||
<servo no="0" name="BMOTOR_FRONT" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="1" name="BMOTOR_RIGHT" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="2" name="BMOTOR_BACK" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="3" name="MOTOR_LEFT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC is neutral -->
|
||||
<servo no="4" name="BMOTOR_PUSH" min="-4095" neutral="-3522" max="4095"/> <!-- Supercan (1070 idle 1000-2000) -->
|
||||
<servo no="5" name="BPARACHUTE" min="-8191" neutral="0" max="8191"/>
|
||||
</servos>
|
||||
|
||||
<!-- CAN BUS 1 command outputs-->
|
||||
<servos driver="Uavcan1Cmd">
|
||||
<servo no="6" name="SERVO_ELEVATOR" min="-7300" neutral="-7300" max="4650"/> <!-- 2500 is level 4650 is 10deg -7300 is -50deg -->
|
||||
<servo no="7" name="SERVO_RUDDER" min="-4000" neutral="0" max="4000"/>
|
||||
<servo no="8" name="AIL_RIGHT" min="-3250" neutral="0" max="3250"/>
|
||||
<servo no="9" name="FLAP_RIGHT" min="-3250" neutral="0" max="3250"/>
|
||||
<servo no="10" name="AIL_LEFT" min="-3250" neutral="0" max="3250"/>
|
||||
<servo no="11" name="FLAP_LEFT" min="-3250" neutral="0" max="3250"/>
|
||||
</servos>
|
||||
|
||||
<!-- Can bus 2 actuators -->
|
||||
<servos driver="Uavcan2">
|
||||
<servo no="0" name="MOTOR_FRONT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
|
||||
<servo no="1" name="MOTOR_RIGHT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
|
||||
<servo no="2" name="MOTOR_BACK" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
|
||||
<servo no="3" name="BMOTOR_LEFT" min="0" neutral="1000" max="8191"/> <!-- Supercan (1100-1202.56-1940us) -->
|
||||
<servo no="4" name="MOTOR_PUSH" min="-4095" neutral="-3522" max="4095"/> <!-- Supercan (1070 idle 1000-2000) -->
|
||||
<servo no="5" name="PARACHUTE" min="-8191" neutral="0" max="8191"/>
|
||||
</servos>
|
||||
|
||||
<!-- CAN BUS 1 command outputs-->
|
||||
<servos driver="Uavcan2Cmd">
|
||||
<servo no="6" name="BSERVO_ELEVATOR" min="-7300" neutral="-7300" max="4650"/> <!-- 2500 is level 4650 is 10deg -7300 is -50deg -->
|
||||
<servo no="7" name="BSERVO_RUDDER" min="-4000" neutral="0" max="4000"/>
|
||||
<servo no="8" name="BAIL_RIGHT" min="-3250" neutral="0" max="3250"/>
|
||||
<servo no="9" name="BFLAP_RIGHT" min="-3250" neutral="0" max="3250"/>
|
||||
<servo no="10" name="BAIL_LEFT" min="-3250" neutral="0" max="3250"/>
|
||||
<servo no="11" name="BFLAP_LEFT" min="-3250" neutral="0" max="3250"/>
|
||||
</servos>
|
||||
|
||||
<servos driver="Faulhaber">
|
||||
<servo no="0" name="ROTATION_MECH" min="140" neutral="1805" max="3470"/>
|
||||
</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"/>
|
||||
<axis name="THRUST_X" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
|
||||
<command_laws>
|
||||
<let var="rc_motors_off" value="Or(LessThan(RadioControlValues(RADIO_KILL_SWITCH), -4800), MoreThan(RadioControlValues(RADIO_PARACHUTE), 4800))"/>
|
||||
<let var="th_hold" value="Or($rc_motors_off, !autopilot_get_motors_on())"/>
|
||||
<let var="servo_hold" value="LessThan(RadioControlValues(RADIO_TH_HOLD), -4800)"/>
|
||||
<let var="hover_off" value="Or($th_hold, !rotwing_state.hover_motors_enabled)"/>
|
||||
|
||||
<call fun="sys_id_doublet_add_values(autopilot_get_motors_on(),FALSE,actuators_pprz)"/>
|
||||
<!-- Main bus -->
|
||||
<set servo="MOTOR_FRONT" value="($hover_off? -9600 : actuators_pprz[0])"/>
|
||||
<set servo="MOTOR_RIGHT" value="($hover_off? -9600 : actuators_pprz[1])"/>
|
||||
<set servo="MOTOR_BACK" value="($hover_off? -9600 : actuators_pprz[2])"/>
|
||||
<set servo="MOTOR_LEFT" value="($hover_off? -9600 : actuators_pprz[3])"/>
|
||||
<set servo="MOTOR_PUSH" value="($th_hold? -9600 : actuators_pprz[8])"/>
|
||||
<set servo="SERVO_ELEVATOR" value="($servo_hold? (RadioControlValues(RADIO_PITCH)/4+7200) : (!autopilot_in_flight()? 0 : actuators_pprz[5]))"/>
|
||||
<set servo="SERVO_RUDDER" value="($servo_hold? RadioControlValues(RADIO_YAW) : (!autopilot_in_flight()? 0 : actuators_pprz[4]))"/>
|
||||
<set servo="AIL_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
|
||||
<set servo="FLAP_RIGHT" value="($servo_hold? (RadioControlValues(RADIO_ROLL) + rw_flap_offset) : actuators_pprz[7] + rw_flap_offset)"/>
|
||||
<set servo="AIL_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
|
||||
<set servo="FLAP_LEFT" value="($servo_hold? (RadioControlValues(RADIO_ROLL) - rw_flap_offset) : actuators_pprz[7] - rw_flap_offset)"/>
|
||||
<set servo="PARACHUTE" value="RadioControlValues(RADIO_PARACHUTE)"/>
|
||||
|
||||
<!-- Second bus -->
|
||||
<set servo="BMOTOR_FRONT" value="($hover_off? -9600 : actuators_pprz[0])"/>
|
||||
<set servo="BMOTOR_RIGHT" value="($hover_off? -9600 : actuators_pprz[1])"/>
|
||||
<set servo="BMOTOR_BACK" value="($hover_off? -9600 : actuators_pprz[2])"/>
|
||||
<set servo="BMOTOR_LEFT" value="($hover_off? -9600 : actuators_pprz[3])"/>
|
||||
<set servo="BMOTOR_PUSH" value="($th_hold? -9600 : actuators_pprz[8])"/>
|
||||
<set servo="BSERVO_ELEVATOR" value="($servo_hold? (RadioControlValues(RADIO_PITCH)/4+7200) : (!autopilot_in_flight()? 0 : actuators_pprz[5]))"/>
|
||||
<set servo="BSERVO_RUDDER" value="($servo_hold? RadioControlValues(RADIO_YAW) : (!autopilot_in_flight()? 0 : actuators_pprz[4]))"/>
|
||||
<set servo="BAIL_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
|
||||
<set servo="BFLAP_RIGHT" value="($servo_hold? (RadioControlValues(RADIO_ROLL) + rw_flap_offset) : actuators_pprz[7] + rw_flap_offset)"/>
|
||||
<set servo="BAIL_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
|
||||
<set servo="BFLAP_LEFT" value="($servo_hold? (RadioControlValues(RADIO_ROLL) - rw_flap_offset) : actuators_pprz[7] - rw_flap_offset)"/>
|
||||
<set servo="BPARACHUTE" value="RadioControlValues(RADIO_PARACHUTE)"/>
|
||||
|
||||
<!-- Rotation mechanism -->
|
||||
<set servo="ROTATION_MECH" value="rotwing_state.skew_cmd"/>
|
||||
</command_laws>
|
||||
|
||||
|
||||
<section PREFIX="SYS_ID_" NAME="SYS_ID">
|
||||
<define name="DOUBLET_AXES" value="{0,1,2,3,4,5,6,7,8}"/>
|
||||
<define name="DOUBLET_RADIO_CHANNEL" value="6"/>
|
||||
|
||||
<define name="AUTO_DOUBLETS_N_ACTUATORS" value="4"/>
|
||||
<define name="AUTO_DOUBLETS_ACTUATORS" value="{0,1,2,3}"/>
|
||||
<define name="AUTO_DOUBLETS_AMPLITUDE" value="{1500,1000,1500,1000}"/>
|
||||
|
||||
<define name="AUTO_DOUBLETS_TIME" value="1.0"/>
|
||||
<define name="AUTO_DOUBLETS_INTERVAL" value="3.0"/>
|
||||
<define name="AUTO_DOUBLETS_REPEATS" value="4"/>
|
||||
|
||||
<define name="CHIRP_AXES" value="{0,1,2,3}"/>
|
||||
<define name="CHIRP_RADIO_CHANNEL" value="9"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- Magnetometers calibration (NOT DONE!) -->
|
||||
<define name="MAG_CALIB" type="array">
|
||||
<field type="struct">
|
||||
<field name="abi_id" value="5"/>
|
||||
<field name="calibrated" type="struct">
|
||||
<field name="neutral" value="true"/>
|
||||
<field name="scale" value="true"/>
|
||||
<field name="rotation" value="true"/>
|
||||
</field>
|
||||
<field name="neutral" value="132,415,-357" type="int[]"/>
|
||||
<field name="scale" value="{{13019,21924,2280},{22037,40349,3953}}"/>
|
||||
<field name="body_to_sensor" value="{{0,-16384,0, -16384,0,0, 0,0,-16384}}"/>
|
||||
</field>
|
||||
</define>
|
||||
|
||||
<!-- Accelerometers calibration (NOT DONE!) -->
|
||||
<define name="ACCEL_CALIB" type="array">
|
||||
<field type="struct">
|
||||
<field name="abi_id" value="26"/>
|
||||
<field name="calibrated" type="struct">
|
||||
<field name="neutral" value="true"/>
|
||||
<field name="scale" value="true"/>
|
||||
<field name="rotation" value="false"/>
|
||||
<field name="filter" value="true"/>
|
||||
</field>
|
||||
<field name="filter_sample_freq" value="4042"/>
|
||||
<field name="filter_freq" value="30"/>
|
||||
<field name="neutral" value="-6,-7,-47" type="int[]"/>
|
||||
<field name="scale" value="{{32406,25097,35786},{6623,5114,7131}}"/>
|
||||
</field>
|
||||
</define>
|
||||
|
||||
<!-- Gyrometer calibration (NOT DONE!) -->
|
||||
<define name="GYRO_CALIB" type="array">
|
||||
<field type="struct">
|
||||
<field name="abi_id" value="26"/>
|
||||
<field name="calibrated" type="struct">
|
||||
<field name="neutral" value="false"/>
|
||||
<field name="scale" value="false"/>
|
||||
<field name="rotation" value="false"/>
|
||||
<field name="filter" value="true"/>
|
||||
</field>
|
||||
<field name="filter_sample_freq" value="4042"/>
|
||||
<field name="filter_freq" value="30"/>
|
||||
</field>
|
||||
</define>
|
||||
|
||||
<!-- High speed IMU logging for debugging only -->
|
||||
<!--define name="LOG_HIGHSPEED" value="TRUE"/-->
|
||||
|
||||
<!-- Define axis in hover frame -->
|
||||
<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="180." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<checklist>
|
||||
<item name="pic" type="text">Enter the PIC</item>
|
||||
<item name="pac" type="text">Enter the PAC</item>
|
||||
<item name="gcs" type="text">Enter the GCS op</item>
|
||||
<item name="goal" type="text">Goal of the flight</item>
|
||||
<item name="basic law">Location, airspace and weather</item>
|
||||
<item name="RC Battery">Check the RC battery</item>
|
||||
<item name="wings">Check wings secured (and taped)</item>
|
||||
<item name="rotation">Initialize and check wing rotation</item>
|
||||
<item name="attitude">Check attitude and heading</item>
|
||||
<item name="airspeed">Calibrate airspeed sensor</item>
|
||||
<item name="takeoff location">Put UAV on take-off location</item>
|
||||
<item name="flight plan">Check flight plan</item>
|
||||
<item name="flight block">Switch to correct flight block</item>
|
||||
<item name="drone tag">Switch on drone tag</item>
|
||||
<item name="camera">Switch on camera</item>
|
||||
<item name="parachute">Arm parachute</item>
|
||||
<item name="announce">Announce flight to other airspace users</item>
|
||||
</checklist>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="36.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="37.2" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="48.4" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="52.2" unit="V"/>
|
||||
<define name="TAKEOFF_BAT_LEVEL" value="48.4" unit="V"/>
|
||||
<define name="BAT_NB_CELLS" value="12"/>
|
||||
</section>
|
||||
|
||||
<include href="conf/airframes/tudelft/rotwing_25kg_common.xml" />
|
||||
</airframe>
|
||||
@@ -55,10 +55,6 @@
|
||||
|
||||
<!-- AGL distance -->
|
||||
<define name="AGL_DIST_FILTER" value="0.07"/>
|
||||
|
||||
<!-- Don't oversaturate the UAVCAN bus -->
|
||||
<define name="ACTUATORS_UAVCAN_RAW_DIV" value="2"/> <!-- ESC's at half the PERIODIC_FREQ -->
|
||||
<define name="ACTUATORS_UAVCAN_CMD_DIV" value="4"/> <!-- Servo's at 1/4 the PERIODIC_FREQ -->
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
|
||||
@@ -205,7 +205,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -326,7 +326,7 @@
|
||||
telemetry="telemetry/default_rotorcraft_slow.xml"
|
||||
flight_plan="flight_plans/tudelft/delft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml [modules/air_data.xml] modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml [modules/air_data.xml] modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
gui_color="#ffffcccaccca"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -524,7 +524,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/tudelft/disco_convergence.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_rotorcraft.xml modules/stabilization_indi.xml"
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/stabilization_indi.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -703,4 +703,37 @@
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/eff_scheduling_rotwing.xml modules/ekf_aw.xml modules/electrical.xml modules/follow_me.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/parachute.xml modules/pfc_actuators.xml modules/preflight_checks.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
name="Rotwing7"
|
||||
ac_id="40"
|
||||
airframe="airframes/tudelft/rotwing7.xml"
|
||||
radio="radios/crossfire_sbus.xml"
|
||||
telemetry="telemetry/highspeed_rotorcraft.xml"
|
||||
flight_plan="flight_plans/tudelft/rotwing_EHVB.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/actuators_faulhaber.xml modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/eff_scheduling_rotwing.xml modules/electrical.xml modules/follow_me.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/preflight_checks.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
name="Easystar3"
|
||||
ac_id="41"
|
||||
airframe="airframes/tudelft/easystar3.xml"
|
||||
radio="radios/crossfire_sbus.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/tudelft/disco_convergence.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/stabilization_indi.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
name="Easystar3_FW"
|
||||
ac_id="42"
|
||||
airframe="airframes/tudelft/easystar3_fw.xml"
|
||||
radio="radios/crossfire_sbus.xml"
|
||||
telemetry="telemetry/fixedwing_flight_recorder.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/logger_sd_chibios.xml modules/nav_basic_fw.xml modules/stabilization_adaptive_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
Reference in New Issue
Block a user