Hello
I am trying to understand how stabilization works in AP_Mount so I can recalculate target angels for 2 axis gimbal in order for Yaw and Pitch also include compensation for Roll.
And all of this should work in RC_Targeting mode only.
From what I’ve understood, here is where we get target in RC_Targeting mode
https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Mount/AP_Mount_Servo.cpp
(AP_Mount_Servo.cpp:60)
case MAV_MOUNT_MODE_RC_TARGETING:
update_mnt_target_from_rc_target();
break;
And here we are getting target angles (:133)
// get attitude as a quaternion. returns true on success
bool AP_Mount_Servo::get_attitude_quaternion(Quaternion& att_quat)
{
// No feedback from gimbal so simply report demanded servo angles (which is
// not the same as target angles).
float roll_rad = 0.0f;
float pitch_rad = 0.0f;
float yaw_rad = 0.0f;
if (has_roll_control()) {
roll_rad = constrain_float(_angle_bf_output_rad.x, radians(_params.roll_angle_min), radians(_params.roll_angle_max));
}
if (has_pitch_control()) {
pitch_rad = constrain_float(_angle_bf_output_rad.y, radians(_params.pitch_angle_min), radians(_params.pitch_angle_max));
}
if (has_pan_control()) {
yaw_rad = constrain_float(_angle_bf_output_rad.z, radians(_params.yaw_angle_min), radians(_params.yaw_angle_max));
}
// convert to quaternion
att_quat.from_euler(roll_rad, pitch_rad, yaw_rad);
return true;
}
// private methods
// update body-frame angle outputs from earth-frame angle targets
void AP_Mount_Servo::update_angle_outputs(const MountTarget& angle_rad)
{
const AP_AHRS &ahrs = AP::ahrs();
// get target yaw in body-frame with limits applied
const float yaw_bf_rad = constrain_float(angle_rad.get_bf_yaw(), radians(_params.yaw_angle_min), radians(_params.yaw_angle_max));
// default output to target earth-frame roll and pitch angles, body-frame yaw
_angle_bf_output_rad.x = angle_rad.roll;
_angle_bf_output_rad.y = angle_rad.pitch;
_angle_bf_output_rad.z = yaw_bf_rad;
// this is sufficient for self-stabilising brushless gimbals
if (!requires_stabilization) {
return;
}
// retrieve lean angles from ahrs
Vector2f ahrs_angle_rad = {ahrs.get_roll(), ahrs.get_pitch()};
// rotate ahrs roll and pitch angles to gimbal yaw
if (has_pan_control()) {
ahrs_angle_rad.rotate(-yaw_bf_rad);
}
// add roll and pitch lean angle correction
_angle_bf_output_rad.x -= ahrs_angle_rad.x;
_angle_bf_output_rad.y -= ahrs_angle_rad.y;
// lead filter
const Vector3f &gyro = ahrs.get_gyro();
if (!is_zero(_params.roll_stb_lead) && fabsf(ahrs.get_pitch()) < M_PI/3.0f) {
// Compute rate of change of euler roll angle
float roll_rate = gyro.x + (ahrs.sin_pitch() / ahrs.cos_pitch()) * (gyro.y * ahrs.sin_roll() + gyro.z * ahrs.cos_roll());
_angle_bf_output_rad.x -= roll_rate * _params.roll_stb_lead;
}
if (!is_zero(_params.pitch_stb_lead)) {
// Compute rate of change of euler pitch angle
float pitch_rate = ahrs.cos_pitch() * gyro.y - ahrs.sin_roll() * gyro.z;
_angle_bf_output_rad.y -= pitch_rate * _params.pitch_stb_lead;
}
}
But when I am trying to insert my function into this, I am getting unexpected bugs, like lower min/max angles and weird RC controls.
Can someone point me in the correct direction?