mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: use GPS singleton
This commit is contained in:
parent
a4584431a2
commit
fb3cba3867
|
@ -48,7 +48,7 @@ void AP_Mount_Alexmos::update()
|
|||
|
||||
// point mount to a GPS point given by the mission planner
|
||||
case MAV_MOUNT_MODE_GPS_POINT:
|
||||
if(_frontend._ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, false);
|
||||
control_axis(_angle_ef_target_rad, false);
|
||||
}
|
||||
|
|
|
@ -61,7 +61,7 @@ void AP_Mount_SToRM32::update()
|
|||
|
||||
// point mount to a GPS point given by the mission planner
|
||||
case MAV_MOUNT_MODE_GPS_POINT:
|
||||
if(_frontend._ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, true);
|
||||
resend_now = true;
|
||||
}
|
||||
|
|
|
@ -76,7 +76,7 @@ void AP_Mount_SToRM32_serial::update()
|
|||
|
||||
// point mount to a GPS point given by the mission planner
|
||||
case MAV_MOUNT_MODE_GPS_POINT:
|
||||
if(_frontend._ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, true);
|
||||
resend_now = true;
|
||||
}
|
||||
|
|
|
@ -69,7 +69,7 @@ void AP_Mount_Servo::update()
|
|||
// point mount to a GPS point given by the mission planner
|
||||
case MAV_MOUNT_MODE_GPS_POINT:
|
||||
{
|
||||
if(_frontend._ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, false);
|
||||
stabilize();
|
||||
}
|
||||
|
|
|
@ -70,7 +70,7 @@ void AP_Mount_SoloGimbal::update()
|
|||
// point mount to a GPS point given by the mission planner
|
||||
case MAV_MOUNT_MODE_GPS_POINT:
|
||||
_gimbal.set_lockedToBody(false);
|
||||
if(_frontend._ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, true);
|
||||
}
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue