mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_Gimbal: Re-implement the target low-pass filter
This commit is contained in:
parent
b3dd8891c8
commit
a05fe7e117
@ -6,7 +6,6 @@
|
|||||||
#include <GCS.h>
|
#include <GCS.h>
|
||||||
#include <AP_SmallEKF.h>
|
#include <AP_SmallEKF.h>
|
||||||
|
|
||||||
uint16_t feedback_error_count;
|
|
||||||
static float K_gimbalRate = 5.0f;
|
static float K_gimbalRate = 5.0f;
|
||||||
|
|
||||||
void AP_Gimbal::receive_feedback(mavlink_channel_t chan, mavlink_message_t *msg)
|
void AP_Gimbal::receive_feedback(mavlink_channel_t chan, mavlink_message_t *msg)
|
||||||
@ -164,6 +163,15 @@ void AP_Gimbal::update_failsafe(uint8_t failsafe)
|
|||||||
_failsafe = failsafe;
|
_failsafe = failsafe;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_Gimbal::update_target(Vector3f newTarget)
|
||||||
|
{
|
||||||
|
// Low-pass filter
|
||||||
|
_angle_ef_target_rad.y = _angle_ef_target_rad.y + 0.02f*(newTarget.y - _angle_ef_target_rad.y);
|
||||||
|
// Update tilt
|
||||||
|
_angle_ef_target_rad.y = constrain_float(_angle_ef_target_rad.y,radians(-45),radians(0));
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
uint8_t AP_Gimbal::isCopterFliped(){
|
uint8_t AP_Gimbal::isCopterFliped(){
|
||||||
return fabs(_ahrs.roll)>1.0f || fabs(_ahrs.pitch)>1.0f;
|
return fabs(_ahrs.roll)>1.0f || fabs(_ahrs.pitch)>1.0f;
|
||||||
|
@ -30,6 +30,7 @@ public:
|
|||||||
AP_Gimbal(const AP_AHRS_NavEKF &ahrs, uint8_t sysid, uint8_t compid) :
|
AP_Gimbal(const AP_AHRS_NavEKF &ahrs, uint8_t sysid, uint8_t compid) :
|
||||||
_ekf(ahrs),
|
_ekf(ahrs),
|
||||||
_ahrs(ahrs),
|
_ahrs(ahrs),
|
||||||
|
K_gimbalRate(5.0f),
|
||||||
_joint_offsets(0.0f,0.0f,0.0f),
|
_joint_offsets(0.0f,0.0f,0.0f),
|
||||||
vehicleYawRateFilt(0.0f),
|
vehicleYawRateFilt(0.0f),
|
||||||
yawRateFiltPole(10.0f),
|
yawRateFiltPole(10.0f),
|
||||||
@ -40,6 +41,7 @@ public:
|
|||||||
_compid = compid;
|
_compid = compid;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void update_target(Vector3f newTarget);
|
||||||
void update_failsafe(uint8_t failsafe);
|
void update_failsafe(uint8_t failsafe);
|
||||||
void receive_feedback(mavlink_channel_t chan, mavlink_message_t *msg);
|
void receive_feedback(mavlink_channel_t chan, mavlink_message_t *msg);
|
||||||
|
|
||||||
@ -56,6 +58,8 @@ public:
|
|||||||
Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and pan angles in radians
|
Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and pan angles in radians
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
// K gain for the pointing loop
|
||||||
|
float const K_gimbalRate;
|
||||||
|
|
||||||
// These are corrections (in radians) applied to the to the gimbal joint (x,y,z = roll,pitch,yaw) measurements
|
// These are corrections (in radians) applied to the to the gimbal joint (x,y,z = roll,pitch,yaw) measurements
|
||||||
Vector3f const _joint_offsets;
|
Vector3f const _joint_offsets;
|
||||||
|
@ -95,7 +95,7 @@ void AP_Mount_MAVLink::status_msg(mavlink_channel_t chan)
|
|||||||
*/
|
*/
|
||||||
void AP_Mount_MAVLink::handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
|
void AP_Mount_MAVLink::handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
_gimbal._angle_ef_target_rad = _angle_ef_target_rad;
|
_gimbal.update_target(_angle_ef_target_rad);
|
||||||
_gimbal.receive_feedback(chan,msg);
|
_gimbal.receive_feedback(chan,msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user