Browse Source

Copter: current_loc to Location class

master
Randy Mackay 10 years ago
parent
commit
84fd8da944
  1. 3
      ArduCopter/Copter.h
  2. 7
      ArduCopter/system.cpp

3
ArduCopter/Copter.h

@ -34,6 +34,7 @@ @@ -34,6 +34,7 @@
// Common dependencies
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Menu/AP_Menu.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
@ -407,7 +408,7 @@ private: @@ -407,7 +408,7 @@ private:
// 3D Location vectors
// Current location of the copter (altitude is relative to home)
struct Location current_loc;
Location_Class current_loc;
// Navigation Yaw control
// auto flight mode's yaw mode

7
ArduCopter/system.cpp

@ -200,7 +200,12 @@ void Copter::init_ardupilot() @@ -200,7 +200,12 @@ void Copter::init_ardupilot()
ahrs.set_optflow(&optflow);
#endif
// initialise position controllers
// init Location class
Location_Class::set_ahrs(&ahrs);
#if AP_TERRAIN_AVAILABLE
Location_Class::set_terrain(&terrain);
#endif
pos_control.set_dt(MAIN_LOOP_SECONDS);
// init the optical flow sensor

Loading…
Cancel
Save