Hi all.
I have recently tried to fly a quad (in + configuration) with paparazzi, and it was impossible to fly it.
It was really difficult to control, absolutelly unstable.
In addition, sometimes the PFD got “frozen” (and other times responded with delay), with no apparent reason.
We tried the hover mode, to observe if the autopilot actuated in every control, but nothing happened.
We are using Paparazzi v5.1_devel, LisaM/v2 board with NO barometer, aspirin 2.2 IMU, and ublox LEA-5 GPS.
The accelerometers and magnetometers are well calibrated.
Any advice is really appreciated.
Maybe is a problem because of not having barometer? Maybe the autopilot and the motors have to be alimented with separate batteries? I saw some reported problems in the mailing list, but I don´t know exactly how related are with my problem.
Thanks in advance.
Here is the airframe code we used:
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Quadrotor LisaM_2.0 pwm">
<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<define name="NO_RC_THRUST_LIMIT"/>
<configure name="AHRS_PROPAGATE_FREQUENCY" value="500"/>
</target>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
</target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
</subsystem>
<subsystem name="radio_control" type="ppm">
<configure name="RADIO_CONTROL_PPM_PIN" value="SERVO6"/>
</subsystem>
<subsystem name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_PORT" value="UART2"/>
</subsystem>
<subsystem name="imu" type="aspirin_v2.2"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_PORT" value="UART3"/>
</subsystem>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat">
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="30"/>
</subsystem>
<subsystem name="ins"/>
<!--define name="KILL_ON_GROUND_DETECT" value="TRUE"/-->
<define name="TELEMETRY_MODE_FBW" value="1" />
</firmware>
<modules main_freq="512">
<load name="gps_ubx_ucenter.xml">
<define name="GPS_UBX_NAV5_DYNAMICS" value="NAV5_DYN_PEDESTRIAN"/>
</load>
</modules>
<servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1100" max="1900"/>
<servo name="BACK" no="1" min="1000" neutral="1100" max="1900"/>
<servo name="RIGHT" no="2" min="1000" neutral="1100" max="1900"/>
<servo name="LEFT" no="3" min="1000" neutral="1100" max="1900"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<!-- front/back turning CW, right/left CCW -->
<define name="ROLL_COEF" value="{ 0, 0, -256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0 }"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[SERVO_FRONT]"/>
<set servo="BACK" value="motor_mixing.commands[SERVO_BACK]"/>
<set servo="RIGHT" value="motor_mixing.commands[SERVO_RIGHT]"/>
<set servo="LEFT" value="motor_mixing.commands[SERVO_LEFT]"/>
</command_laws>
<!-- inaki he puesto mis valores-->
<section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="24"/>
<define name="ACCEL_Y_NEUTRAL" value="8"/>
<define name="ACCEL_Z_NEUTRAL" value="264"/>
<define name="ACCEL_X_SENS" value="4.93314498567" integer="16"/>
<define name="ACCEL_Y_SENS" value="4.86671471234" integer="16"/>
<define name="ACCEL_Z_SENS" value="4.86346803582" integer="16"/>
<!-- REEMPLAZADO POR MI CALIBRACION INAKI -->
<define name="MAG_X_NEUTRAL" value="8"/>
<define name="MAG_Y_NEUTRAL" value="-12"/>
<define name="MAG_Z_NEUTRAL" value="35"/>
<define name="MAG_X_SENS" value="3.53511175627" integer="16"/>
<define name="MAG_Y_SENS" value="3.49864611794" integer="16"/>
<define name="MAG_Z_SENS" value="3.96410626337" 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." unit="deg"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.3770441"/>
<define name="H_Y" value="0.0193986"/>
<define name="H_Z" value="0.9259921"/>
</section>
<section name="INS" prefix="INS_">
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="DEADBAND_P" value="20"/>
<define name="DEADBAND_Q" value="20"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>
<define name="IGAIN_P" value="75"/>
<define name="IGAIN_Q" value="75"/>
<define name="IGAIN_R" value="50"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="250" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="1000"/>
<define name="PHI_DGAIN" value="400"/>
<define name="PHI_IGAIN" value="200"/>
<define name="THETA_PGAIN" value="1000"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="200"/>
<define name="PSI_PGAIN" value="500"/>
<define name="PSI_DGAIN" value="300"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="300"/>
<define name="THETA_DDGAIN" value="300"/>
<define name="PSI_DDGAIN" value="300"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
<define name="MAX_SUM_ERR" value="2000000"/>
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.6"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="100"/>
<define name="AGAIN" value="100"/>
<define name="IGAIN" value="20"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
<define name="JSBSIM_INIT" value=""reset00""/>
<define name="JSBSIM_MODEL" value=""simple_quad""/>
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<define name="JS_AXIS_MODE" value="4"/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_KILL"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
<define name="MODE_AUTO1" value="AP_MODE_RC_DIRECT"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="10.1" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
<define name="MILLIAMP_AT_FULL_THROTTLE" value="30000"/>
</section>
</airframe>