Skip to content

Commit

Permalink
Add PyBullet FDM for nps. (#3024)
Browse files Browse the repository at this point in the history
  • Loading branch information
Fabien-B committed Apr 16, 2023
1 parent 53987d5 commit 2a98d9f
Show file tree
Hide file tree
Showing 12 changed files with 2,402 additions and 23 deletions.
57 changes: 34 additions & 23 deletions conf/airframes/ENAC/conf_enac.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,28 +10,6 @@
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/power_switch.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
<aircraft
name="ARD2_101"
ac_id="101"
airframe="airframes/ENAC/quadrotor/ard2_basic.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic_safety.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_float_invariant.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="red"
/>
<aircraft
name="ARD2_103"
ac_id="103"
airframe="airframes/ENAC/quadrotor/ard2_basic_adhoc.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic_safety.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="yellow"
/>
<aircraft
name="CHIMERA"
ac_id="23"
Expand Down Expand Up @@ -73,7 +51,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/basic.xml"
settings="settings/fixedwing_basic.xml [settings/nps.xml]"
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/gps.xml [modules/gps_ubx_ucenter.xml] modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/power_switch.xml modules/stabilization_adaptive_fw.xml"
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/gps.xml modules/gps_ublox.xml [modules/gps_ubx_ucenter.xml] modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/power_switch.xml modules/stabilization_adaptive_fw.xml"
gui_color="#ffff7d7d0000"
/>
<aircraft
Expand Down Expand Up @@ -131,4 +109,37 @@
settings_modules="modules/ahrs_float_cmpl_quat.xml modules/ahrs_float_dcm.xml modules/air_data.xml modules/gps.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/stabilization_adaptive_fw.xml"
gui_color="blue"
/>
<aircraft
name="RoBoBee"
ac_id="2"
airframe="airframes/ENAC/quadrotor/robobee.xml"
radio="radios/FrSky_X-Lite.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/filter_1euro_imu.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/jevois.xml modules/logger_sd_chibios.xml modules/nav_rotorcraft.xml modules/stabilization_indi.xml modules/tag_tracking.xml"
gui_color="#3ce8d771db45"
/>
<aircraft
name="ANTON"
ac_id="217"
airframe="airframes/ENAC/quadrotor/anton_indi_aruco.xml"
radio="radios/FrSky_X-Lite.xml"
telemetry="telemetry/rotorcraft_imav2022.xml"
flight_plan="flight_plans/competitions/IMAV2022_drop.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/filter_1euro_imu.xml modules/gps.xml modules/guidance_indi.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/jevois.xml modules/logger_sd_chibios.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/stabilization_indi.xml modules/switch_servo.xml modules/tag_tracking.xml"
gui_color="#fdd12f992f99"
/>
<aircraft
name="ULYSSE"
ac_id="218"
airframe="airframes/ENAC/quadrotor/ulysse_indi.xml"
radio="radios/FrSky_X-Lite.xml"
telemetry="telemetry/rotorcraft_imav2022.xml"
flight_plan="flight_plans/competitions/IMAV2022_drop.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/gps.xml modules/guidance_indi.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/jevois.xml modules/logger_sd_chibios.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/stabilization_indi.xml modules/switch_servo.xml modules/tag_tracking.xml"
gui_color="#c6d33e3ef958"
/>
</conf>
272 changes: 272 additions & 0 deletions conf/airframes/ENAC/quadrotor/anton_indi_aruco.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,272 @@
<!DOCTYPE airframe SYSTEM "../../airframe.dtd">

<airframe name="Quadricopter ANTON Tawaki">

<description>
* Autopilot: Tawaki
* Actuators: 4 in 4 Holybro BLHELI ESC
* Telemetry: XBee
* GPS: ublox
* RC: FrSky XM+
</description>

<firmware name="rotorcraft">
<configure name="PERIODIC_FREQUENCY" value="1000"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="$(PERIODIC_FREQUENCY)"/>

<target name="ap" board="tawaki_1.0">
<configure name="BARO_PERIODIC_FREQUENCY" value="50"/>
<module name="radio_control" type="sbus"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GAIN1"/>
<define name="LOW_NOISE_TIME" value="10"/>
</target>

<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm"/>
</target>

<module name="telemetry" type="xbee_api"/>

<module name="motor_mixing"/>

<module name="actuators" type="dshot">
<!--define name="DSHOT_SPEED" value="300"/-->
</module>

<module name="board" type="tawaki">
<define name="IMU_MPU_LOWPASS_FILTER" value="MPU60X0_DLPF_256HZ"/>
<define name="IMU_MPU_ACCEL_LOWPASS_FILTER" value="MPU60X0_DLPF_ACC_218HZ"/>
<define name="IMU_MPU_SMPLRT_DIV" value="0"/>
<!--configure name="BOARD_TAWAKI_ROTATED" value="TRUE"/-->
<configure name="MAG_LIS3MDL_I2C_DEV" value="i2c2"/>
</module>
<module name="gps" type="ublox">
<configure name="GPS_BAUD" value="B115200"/>
<define name="USE_GPS_UBX_RTCM" value="TRUE"/>
</module>

<module name="stabilization" type="indi"/>
<module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
<define name="GUIDANCE_INDI_THRUST_DYNAMICS" value="0.03"/>
<define name="GUIDANCE_INDI_RC_DEBUG" value="FALSE"/>
</module>

<module name="ins"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="air_data"/>

<module name="actuators" type="pwm"/>
<module name="switch" type="servo"/>

<module name="filter" type="1euro_imu">
<define name="AHRS_ICQ_IMU_ID" value="IMU_F1E_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="IMU_F1E_ID"/>
</module>

<!--module name="sonar_adc">
<configure name="ADC_SONAR" value="ADC_1"/>
<define name="USE_SONAR"/>
</module>
<module name="agl_dist"/-->

<module name="tag_tracking">
<configure name="JEVOIS_UART" value="UART3" description="UART on which Jevois camera is connected"/>
</module>

<module name="flight_recorder"/>
<!--module name="logger" type="tune_indi"/-->
</firmware>

<servos driver="DShot">
<servo name="FR" no="3" min="0" neutral="100" max="2000"/>
<servo name="BR" no="4" min="0" neutral="100" max="2000"/>
<servo name="BL" no="2" min="0" neutral="100" max="2000"/>
<servo name="FL" no="1" min="0" neutral="100" max="2000"/>
</servos>

<servos driver="Pwm">
<servo name="SWITCH" no="1" min="1000" neutral="1000" max="2000"/>
</servos>

<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>

<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TYPE" value="QUAD_X"/>
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
</section>

<command_laws>
<set servo="FR" value="autopilot_get_motors_on() ? actuators_pprz[0] : -MAX_PPRZ"/>
<set servo="BR" value="autopilot_get_motors_on() ? actuators_pprz[1] : -MAX_PPRZ"/>
<set servo="BL" value="autopilot_get_motors_on() ? actuators_pprz[2] : -MAX_PPRZ"/>
<set servo="FL" value="autopilot_get_motors_on() ? actuators_pprz[3] : -MAX_PPRZ"/>
</command_laws>

<section name="IMU" prefix="IMU_">
<define name="GYRO_P_SIGN" value="-1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="1"/>

<define name="ACCEL_X_SIGN" value="-1"/>
<define name="ACCEL_Y_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="1"/>
<define name="ACCEL_X_NEUTRAL" value="-90"/>
<define name="ACCEL_Y_NEUTRAL" value="40"/>
<define name="ACCEL_Z_NEUTRAL" value="12"/>
<define name="ACCEL_X_SENS" value="2.321864827044042" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.450207588413862" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.4560049628471914" integer="16"/>

<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>
<define name="MAG_X_NEUTRAL" value="-3868"/>
<define name="MAG_Y_NEUTRAL" value="2013"/>
<define name="MAG_Z_NEUTRAL" value="-101"/>
<define name="MAG_X_SENS" value="0.6497766229092939" integer="16"/>
<define name="MAG_Y_SENS" value="0.6352026516080006" integer="16"/>
<define name="MAG_Z_SENS" value="0.6627284899394246" 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="-45." unit="deg"/>
</section>

<section name="MAG">
<define name="LIS3MDL_MAG_TO_IMU_PHI" value="0." unit="deg"/>
<define name="LIS3MDL_MAG_TO_IMU_THETA" value="0." unit="deg"/>
<define name="LIS3MDL_MAG_TO_IMU_PSI" value="90." unit="deg"/>
</section>

<include href="conf/mag/delft_valkenburg.xml"/>

<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="60." unit="deg/s"/>
<define name="DEADBAND_R" value="250"/>
</section>

<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">

<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="101"/>
<define name="REF_ERR_Q" value="101"/>
<define name="REF_ERR_R" value="124"/>
<define name="REF_RATE_P" value="12.6"/>
<define name="REF_RATE_Q" value="14.0"/>
<define name="REF_RATE_R" value="14.0"/>

<define name="MAX_R" value="60" unit="deg/s"/>

<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="4.0"/>
<define name="FILT_CUTOFF_R" value="4.0"/>

<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>

<!-- Full INDI -->
<!-- control effectiveness -->
<define name="G1_ROLL" value="{-40 , -40, 40 , 40 }"/>
<define name="G1_PITCH" value="{40 , -40, -40 , 40 }"/>
<define name="G1_YAW" value="{5, -5, 5, -5}"/>
<define name="G1_THRUST" value="{-1.5, -1.5, -1.5, -1.5}"/>
<!--Counter torque effect of spinning up a rotor-->
<define name="G2" value="{150.0, -150.0, 150.0, -150.0 }"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN" value="{0.03, 0.03, 0.03, 0.03}"/>
<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>

<!--Priority for each axis (roll, pitch, yaw and thrust)-->
<define name="WLS_PRIORITIES" value="{1000, 1000, 1, 100}"/>
</section>


<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="REF_MIN_ZDD" value="-0.4*9.81"/>
<define name="REF_MAX_ZDD" value=" 0.4*9.81"/>
<define name="REF_MIN_ZD" value="-1.5"/>
<define name="REF_MAX_ZD" value=" 1."/>
<define name="HOVER_KP" value="87"/>
<define name="HOVER_KD" value="120"/>
<define name="HOVER_KI" value="11"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.30"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
<define name="ADAPT_NOISE_FACTOR" value="1."/>
<define name="ADAPT_INITIAL_HOVER_THROTTLE" value="0.25"/>
</section>

<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="PGAIN" value="40"/>
<define name="DGAIN" value="108"/>
<define name="IGAIN" value="20"/>
<define name="NGAIN" value="0"/>
<!-- feedforward -->
<define name="AGAIN" value="0"/>
<define name="REF_MAX_SPEED" value="2.5"/>
<define name="REF_MAX_ACCEL" value="2.5"/>
</section>

<section name="NAV">
<define name="ARRIVED_AT_WAYPOINT" value="2.0"/>
<define name="NAV_CLIMB_VSPEED" value="1.0"/>
<define name="NAV_DESCEND_VSPEED" value="-0.5"/>
<define name="RECTANGLE_SURVEY_HEADING_NS" value="0."/>
</section>

<section name="BAT">
<define name="CRITIC_BAT_LEVEL" value="9.3" unit="V"/>
</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="SONAR">
<!--define name="SENSOR_SYNC_SEND_SONAR"/-->
<define name="SONAR_SCALE" value="0.0025"/> <!-- Vcc/1024 per cm => (3.3/2^12)*(0.01/(3.3/2^10) = 0.01*2^10/2^12 -->
</section>

<section name="AGL" prefix="AGL_DIST_SONAR_">
<define name="ID" value="ABI_BROADCAST"/>
<define name="MAX_RANGE" value="6." unit="m"/>
<define name="MIN_RANGE" value="0.01" unit="m"/>
<define name="FILTER" value="0.15"/> <!--Low pass filter time constant-->
</section>

<section name="TAG_TRACKING" prefix="TAG_TRACKING_">
<define name="BODY_TO_CAM_PSI" value="0"/>
<define name="CAM_POS_Y" value="-0.12"/>
</section>

<section name="GCS">
<define name="ALT_SHIFT_PLUS_PLUS" value="3"/>
<define name="ALT_SHIFT_PLUS" value="1"/>
<define name="ALT_SHIFT_MINUS" 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"/>
<define name="NO_MOTOR_MIXING" value="TRUE"/>
</section>

</airframe>

0 comments on commit 2a98d9f

Please sign in to comment.