mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-22 04:13:39 +08:00
Merge pull request #2890 from paparazzi/multi_imu
[imu] Multi IMU support
This commit is contained in:
+32
-7
@@ -22,17 +22,17 @@
|
||||
<field name="temp" type="float" unit="deg Celcius"/>
|
||||
</message>
|
||||
|
||||
<message name="IMU_GYRO_INT32" id="4">
|
||||
<message name="IMU_GYRO" id="4">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="gyro" type="struct Int32Rates *"/>
|
||||
</message>
|
||||
|
||||
<message name="IMU_ACCEL_INT32" id="5">
|
||||
<message name="IMU_ACCEL" id="5">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="accel" type="struct Int32Vect3 *"/>
|
||||
</message>
|
||||
|
||||
<message name="IMU_MAG_INT32" id="6">
|
||||
<message name="IMU_MAG" id="6">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="mag" type="struct Int32Vect3 *"/>
|
||||
</message>
|
||||
@@ -44,10 +44,6 @@
|
||||
<field name="mag" type="struct Int32Vect3 *"/>
|
||||
</message>
|
||||
|
||||
<message name="BODY_TO_IMU_QUAT" id="8">
|
||||
<field name="q_b2i_f" type="struct FloatQuat *"/>
|
||||
</message>
|
||||
|
||||
<message name="GEO_MAG" id="9">
|
||||
<field name="h" type="struct FloatVect3 *" unit="1.0"/>
|
||||
</message>
|
||||
@@ -215,6 +211,35 @@
|
||||
<field name="rc" type="struct RadioControl *">Pointer to a radio control structure</field>
|
||||
</message>
|
||||
|
||||
<message name="IMU_GYRO_RAW" id="31">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="gyro" type="struct Int32Rates *"/>
|
||||
<field name="samples" type="uint8_t"/>
|
||||
</message>
|
||||
|
||||
<message name="IMU_ACCEL_RAW" id="32">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="accel" type="struct Int32Vect3 *"/>
|
||||
<field name="samples" type="uint8_t"/>
|
||||
</message>
|
||||
|
||||
<message name="IMU_MAG_RAW" id="33">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="mag" type="struct Int32Vect3 *"/>
|
||||
</message>
|
||||
|
||||
<message name="IMU_GYRO_INT" id="34">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="delta_gyro" type="struct FloatRates *"/>
|
||||
<field name="dt" type="uint16_t" unit="us"/>
|
||||
</message>
|
||||
|
||||
<message name="IMU_ACCEL_INT" id="35">
|
||||
<field name="stamp" type="uint32_t" unit="us"/>
|
||||
<field name="delta_accel" type="struct FloatVect3 *"/>
|
||||
<field name="dt" type="uint16_t" unit="us"/>
|
||||
</message>
|
||||
|
||||
</msg_class>
|
||||
|
||||
</protocol>
|
||||
|
||||
@@ -248,7 +248,6 @@ Aggie Air ARK
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="f_motor, fr_motor, br_motor, b_motor, bl_motor, fl_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/aggieair_ark_hexa" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
@@ -200,7 +200,6 @@
|
||||
<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"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
@@ -288,7 +288,6 @@ AggieAir Atomic Tangerine
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
|
||||
@@ -257,7 +257,6 @@ AggieAir Blujayujay
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
|
||||
@@ -262,7 +262,6 @@ AggieAir Blujayujay
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
|
||||
@@ -287,7 +287,6 @@ AggieAir El Capitan
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
|
||||
@@ -368,7 +368,6 @@
|
||||
<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">
|
||||
|
||||
@@ -279,7 +279,6 @@ AggieAir RP3 Minion
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
|
||||
@@ -291,7 +291,6 @@ AggieAir Minion Sim
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
|
||||
@@ -287,7 +287,6 @@ AggieAir Minty Fresh
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="25"/>
|
||||
<define name="JSBSIM_MODEL" value="AGGIEAIR/minion" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_THROTTLE" value="0"/>
|
||||
<define name="JS_AXIS_THROTTLE_REVERSED" value="1"/>
|
||||
|
||||
|
||||
@@ -157,7 +157,6 @@ Pin 6 on lisa/s is number 3 in airframefile = ELEVATOR
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
@@ -197,6 +196,5 @@ Pin 6 on lisa/s is number 3 in airframefile = ELEVATOR
|
||||
</module>
|
||||
<module name="ins"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
</firmware>
|
||||
</airframe>
|
||||
|
||||
@@ -226,6 +226,5 @@
|
||||
</module>
|
||||
<module name="ins"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
</firmware>
|
||||
</airframe>
|
||||
|
||||
@@ -171,7 +171,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
@@ -218,6 +217,5 @@
|
||||
</module>
|
||||
<module name="ins"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
</firmware>
|
||||
</airframe>
|
||||
|
||||
@@ -162,7 +162,6 @@
|
||||
<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"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
@@ -25,7 +25,6 @@
|
||||
|
||||
<module name="geo_mag"/>
|
||||
<module name="air_data"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
<!--module name="logger_file">
|
||||
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
|
||||
</module-->
|
||||
@@ -182,7 +181,6 @@
|
||||
<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">
|
||||
|
||||
@@ -31,7 +31,6 @@
|
||||
|
||||
<module name="geo_mag"/>
|
||||
<module name="air_data"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
<!--module name="logger_file">
|
||||
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
|
||||
</module-->
|
||||
@@ -207,7 +206,6 @@
|
||||
<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">
|
||||
|
||||
@@ -33,7 +33,6 @@
|
||||
|
||||
<module name="geo_mag"/>
|
||||
<module name="air_data"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
<!--module name="logger_file">
|
||||
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
|
||||
</module-->
|
||||
@@ -210,7 +209,6 @@
|
||||
<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">
|
||||
|
||||
@@ -176,7 +176,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
@@ -223,6 +222,5 @@
|
||||
</module>
|
||||
<module name="ins"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
</firmware>
|
||||
</airframe>
|
||||
|
||||
@@ -184,7 +184,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
@@ -221,7 +220,6 @@
|
||||
<module name="stabilization" type="int_quat"/>
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
<module name="ins"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
<module name="stereocam">
|
||||
<configure name="STEREO_UART" value="UART1"/>
|
||||
<configure name="STEREO_BAUD" value="B115200"/>
|
||||
|
||||
@@ -180,7 +180,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
@@ -229,6 +228,5 @@
|
||||
<module name="geo_mag"/>
|
||||
<module name="air_data"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
</firmware>
|
||||
</airframe>
|
||||
|
||||
@@ -162,7 +162,6 @@
|
||||
<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"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
@@ -170,7 +170,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -34,7 +34,6 @@
|
||||
<!-- <module name="logger_spi_link"/>
|
||||
<module name="imu_quality_assessment"/> -->
|
||||
<module name="switch" type="servo"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
<module name="gps" type="ubx_ucenter" />
|
||||
<module name="nav" type="survey_rectangle_rotorcraft"/>
|
||||
<module name="nav" type="survey_poly_rotorcraft"/>
|
||||
@@ -194,7 +193,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -183,7 +183,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
@@ -62,9 +62,8 @@
|
||||
|
||||
<!--run the chimera mag once every 64 seconds to avoid message spam-->
|
||||
<define name="MPU9250_MAG_PRESCALER" value="32768"/>
|
||||
</module>
|
||||
|
||||
<module name="send_imu_mag_current">
|
||||
<!-- Current calibration -->
|
||||
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="1000"/>
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="30000"/>
|
||||
<define name="CURRENT_ESTIMATION_NONLINEARITY" value="1.5"/>
|
||||
@@ -300,7 +299,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ele_left, ele_right, mot_right, mot_left" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="cyclone" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="NO_MOTOR_MIXING" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
|
||||
@@ -102,6 +102,9 @@
|
||||
<define name="ACCEL_X_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="0"/>
|
||||
<define name="ACCEL_X_SENS" value="2.45166329295" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="2.45072320868" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="2.44974997157" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0"/>
|
||||
|
||||
@@ -228,7 +228,6 @@
|
||||
<define name="CRRCSIM_COMMAND_THROTTLE" value="0"/>
|
||||
<define name="CRRCSIM_ROLL_NEUTRAL" value="0." unit="deg"/>
|
||||
<define name="CRRCSIM_PITCH_NEUTRAL" value="12." unit="deg"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -280,7 +280,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15"/>
|
||||
<define name="JSBSIM_MODEL" value="easystar" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
|
||||
@@ -197,7 +197,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15"/>
|
||||
<define name="JSBSIM_MODEL" value="easystar" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
|
||||
@@ -214,7 +214,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15"/>
|
||||
<define name="JSBSIM_MODEL" value="easystar" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
|
||||
@@ -242,7 +242,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15"/>
|
||||
<define name="JSBSIM_MODEL" value="easystar" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
|
||||
|
||||
@@ -50,7 +50,6 @@
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
<module name="ins" />
|
||||
|
||||
<module name="send_imu_mag_current"/>
|
||||
<!--module name="geo_mag"/-->
|
||||
<module name="air_data"/>
|
||||
<module name="stabilization" type="rate"/>
|
||||
@@ -248,7 +247,6 @@
|
||||
<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="HOOPERFLY/hooperfly_teensyfly_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
@@ -205,7 +205,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="JSBSIM_LAUNCHSPEED" value="15"/>
|
||||
<define name="JSBSIM_MODEL" value="easystar" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
|
||||
@@ -120,7 +120,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_ardrone2" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
|
||||
@@ -209,7 +209,6 @@
|
||||
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
|
||||
<!--define name="JSBSIM_MODEL" value="bebop" type="string"/-->
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!--define name="NO_MOTOR_MIXING" value="FALSE"/-->
|
||||
</section>
|
||||
|
||||
|
||||
@@ -216,7 +216,6 @@
|
||||
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
|
||||
<!--define name="JSBSIM_MODEL" value="bebop" type="string"/-->
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!--define name="NO_MOTOR_MIXING" value="FALSE"/-->
|
||||
</section>
|
||||
|
||||
|
||||
@@ -244,7 +244,6 @@
|
||||
<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">
|
||||
|
||||
@@ -70,7 +70,6 @@
|
||||
<define name="AHRS_ALIGNER_IMU_ID" value="IMU_F1E_ID"/>
|
||||
</module-->
|
||||
|
||||
<module name="send_imu_mag_current"/>
|
||||
</firmware>
|
||||
|
||||
<servos driver="DShot">
|
||||
@@ -281,7 +280,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, right_motor, back_motor, left_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -247,7 +247,6 @@
|
||||
<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="HOOPERFLY/hooperfly_teensyfly_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
@@ -268,7 +268,6 @@
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, right_motor, back_motor, left_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_quad_wind" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -87,7 +87,6 @@
|
||||
<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="HOOPERFLY/hooperfly_teensyfly_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
@@ -111,7 +111,6 @@
|
||||
<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="HOOPERFLY/hooperfly_teensyfly_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
@@ -183,7 +183,6 @@ B2L -> CW
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
@@ -170,7 +170,6 @@
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
@@ -180,7 +180,6 @@
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
@@ -141,7 +141,6 @@
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
@@ -155,7 +155,6 @@
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
@@ -180,7 +180,6 @@
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
@@ -176,7 +176,6 @@
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="front_motor, back_motor, right_motor, left_motor" type="string[]"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user