Skip to content

Commit

Permalink
AP_ICEngine: ICE to use ahrs singleton
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub authored and peterbarker committed Feb 5, 2019
1 parent c31e24e commit 79c78ba
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 7 deletions.
8 changes: 4 additions & 4 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <SRV_Channel/SRV_Channel.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h>
#include "AP_ICEngine.h"

extern const AP_HAL::HAL& hal;
Expand Down Expand Up @@ -106,9 +107,8 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {


// constructor
AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm, const AP_AHRS &_ahrs) :
AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) :
rpm(_rpm),
ahrs(_ahrs),
state(ICE_OFF)
{
AP_Param::setup_object_defaults(this, var_info);
Expand Down Expand Up @@ -153,7 +153,7 @@ void AP_ICEngine::update(void)
Vector3f pos;
if (!should_run) {
state = ICE_OFF;
} else if (ahrs.get_relative_position_NED_origin(pos)) {
} else if (AP::ahrs().get_relative_position_NED_origin(pos)) {
if (height_pending) {
height_pending = false;
initial_height = -pos.z;
Expand Down Expand Up @@ -202,7 +202,7 @@ void AP_ICEngine::update(void)
if (state == ICE_START_HEIGHT_DELAY) {
// when disarmed we can be waiting for takeoff
Vector3f pos;
if (ahrs.get_relative_position_NED_origin(pos)) {
if (AP::ahrs().get_relative_position_NED_origin(pos)) {
// reset initial height while disarmed
initial_height = -pos.z;
}
Expand Down
4 changes: 1 addition & 3 deletions libraries/AP_ICEngine/AP_ICEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,11 @@

#include <AP_HAL/AP_HAL.h>
#include <AP_RPM/AP_RPM.h>
#include <AP_AHRS/AP_AHRS.h>

class AP_ICEngine {
public:
// constructor
AP_ICEngine(const AP_RPM &_rpm, const AP_AHRS &_ahrs);
AP_ICEngine(const AP_RPM &_rpm);

static const struct AP_Param::GroupInfo var_info[];

Expand All @@ -50,7 +49,6 @@ class AP_ICEngine {

private:
const AP_RPM &rpm;
const AP_AHRS &ahrs;

enum ICE_State state;

Expand Down

0 comments on commit 79c78ba

Please sign in to comment.