Altitude hold issue in Tilt Wing craft

I am testing a three motor TiltWing craft that takes off as a tricopter. During those tests I am holding it during the whole time, preventing it from getting out of control, but not influencing it otherwise.

The procedure is the following:

  • I take off in QStabilize
  • Once it gets to the desired height QHover is engaged
  • I procceed to force it up and down, to test the response to the altitude hold
    The image below is a log of a case in which it works fine.

Sporadically, once I engage QHover mode, it sets a climb rate that forces the craft up, despite being in the correct height or close to it. In those cases I hold it preventing it from going up. The image below shows a log in which it happens.

If I understood the height controller correctly, the climb rate is defined by the error in height times Q_PZ_P which is then used as input of the Throttle controller. This does not seem to be happening in the log. Once the height reaches the desired altitude (DAlt), there is still a positive desired climb rate (DCRt).

The function for the rate of ascent (AC_PosControl.cpp:507) seems to indicate a simple P controlller too. I suppose the issue might have to do with the feed-forward controller, but I am not yet sure.

// pos_to_rate_z - position to rate controller for Z axis
// calculates desired rate in earth-frame z axis and passes to rate controller
// vel_up_max, vel_down_max should have already been set before calling this method
void AC_PosControl::pos_to_rate_z()
{
float curr_alt = _inav.get_altitude();

// clear position limit flags
_limit.pos_up = false;
_limit.pos_down = false;

// calculate altitude error
_pos_error.z = _pos_target.z - curr_alt;

// do not let target altitude get too far from current altitude
if (_pos_error.z > _leash_up_z) {
    _pos_target.z = curr_alt + _leash_up_z;
    _pos_error.z = _leash_up_z;
    _limit.pos_up = true;
}
if (_pos_error.z < -_leash_down_z) {
    _pos_target.z = curr_alt - _leash_down_z;
    _pos_error.z = -_leash_down_z;
    _limit.pos_down = true;
}

// calculate _vel_target.z using from _pos_error.z using sqrt controller
_vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);

// check speed limits
// To-Do: check these speed limits here or in the pos->rate controller
_limit.vel_up = false;
_limit.vel_down = false;
if (_vel_target.z < _speed_down_cms) {
    _vel_target.z = _speed_down_cms;
    _limit.vel_down = true;
}
if (_vel_target.z > _speed_up_cms) {
    _vel_target.z = _speed_up_cms;
    _limit.vel_up = true;
}

// add feed forward component
if (_flags.use_desvel_ff_z) {
    _vel_target.z += _vel_desired.z;
}

// call rate based throttle controller which will update accel based throttle controller targets
rate_to_accel_z();

}

Has anyone experienced similar behaviors? Any insight will be welcome.

1 Like