AP_Mount: compiler warnings: apply is_zero(float) or is_equal(float)
This commit is contained in:
parent
20dc48ed16
commit
4ac1f8a2fa
@ -8,12 +8,13 @@
|
||||
#include <AP_Common.h>
|
||||
#include <GCS.h>
|
||||
#include <AP_SmallEKF.h>
|
||||
#include "AP_Math.h"
|
||||
|
||||
void AP_Gimbal::receive_feedback(mavlink_channel_t chan, mavlink_message_t *msg)
|
||||
{
|
||||
decode_feedback(msg);
|
||||
update_state();
|
||||
if (_ekf.getStatus() && !isCopterFlipped() && _gimbalParams.K_gimbalRate!=0.0f){
|
||||
if (_ekf.getStatus() && !isCopterFlipped() && !AP_Math::is_zero(_gimbalParams.K_gimbalRate)){
|
||||
send_control(chan);
|
||||
}
|
||||
|
||||
|
@ -154,13 +154,13 @@ void AP_Mount_Servo::stabilize()
|
||||
// lead filter
|
||||
const Vector3f &gyro = _frontend._ahrs.get_gyro();
|
||||
|
||||
if (_state._stab_roll && _state._roll_stb_lead != 0.0f && fabsf(_frontend._ahrs.pitch) < M_PI/3.0f) {
|
||||
if (_state._stab_roll && !AP_Math::is_zero(_state._roll_stb_lead) && fabsf(_frontend._ahrs.pitch) < (float)M_PI/3.0f) {
|
||||
// Compute rate of change of euler roll angle
|
||||
float roll_rate = gyro.x + (_frontend._ahrs.sin_pitch() / _frontend._ahrs.cos_pitch()) * (gyro.y * _frontend._ahrs.sin_roll() + gyro.z * _frontend._ahrs.cos_roll());
|
||||
_angle_bf_output_deg.x -= degrees(roll_rate) * _state._roll_stb_lead;
|
||||
}
|
||||
|
||||
if (_state._stab_tilt && _state._pitch_stb_lead != 0.0f) {
|
||||
if (_state._stab_tilt && !AP_Math::is_zero(_state._pitch_stb_lead)) {
|
||||
// Compute rate of change of euler pitch angle
|
||||
float pitch_rate = _frontend._ahrs.cos_pitch() * gyro.y - _frontend._ahrs.sin_roll() * gyro.z;
|
||||
_angle_bf_output_deg.y -= degrees(pitch_rate) * _state._pitch_stb_lead;
|
||||
|
Loading…
Reference in New Issue
Block a user