mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Mount: convert to new GPS API
This commit is contained in:
parent
f07e4dee52
commit
eb67948171
@ -216,9 +216,8 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
AP_Mount::AP_Mount(const struct Location *current_loc, GPS *&gps, const AP_AHRS &ahrs, uint8_t id) :
|
||||
_ahrs(ahrs),
|
||||
_gps(gps)
|
||||
AP_Mount::AP_Mount(const struct Location *current_loc, const AP_AHRS &ahrs, uint8_t id) :
|
||||
_ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
_current_loc = current_loc;
|
||||
@ -381,7 +380,7 @@ void AP_Mount::update_mount_position()
|
||||
// point mount to a GPS point given by the mission planner
|
||||
case MAV_MOUNT_MODE_GPS_POINT:
|
||||
{
|
||||
if(_gps->fix) {
|
||||
if(_ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||
calc_GPS_target_angle(&_target_GPS_location);
|
||||
stabilize();
|
||||
}
|
||||
|
@ -32,7 +32,7 @@ class AP_Mount
|
||||
{
|
||||
public:
|
||||
//Constructor
|
||||
AP_Mount(const struct Location *current_loc, GPS *&gps, const AP_AHRS &ahrs, uint8_t id);
|
||||
AP_Mount(const struct Location *current_loc, const AP_AHRS &ahrs, uint8_t id);
|
||||
|
||||
//enums
|
||||
enum MountType {
|
||||
@ -88,7 +88,6 @@ private:
|
||||
|
||||
//members
|
||||
const AP_AHRS &_ahrs; ///< Rotation matrix from earth to plane.
|
||||
GPS *& _gps;
|
||||
const struct Location * _current_loc;
|
||||
struct Location _target_GPS_location;
|
||||
MountType _mount_type;
|
||||
|
Loading…
Reference in New Issue
Block a user