Skip to content

Commit

Permalink
Commit for peter to review
Browse files Browse the repository at this point in the history
  • Loading branch information
colejmero committed Mar 5, 2021
1 parent f223c83 commit f24e111
Show file tree
Hide file tree
Showing 6 changed files with 189 additions and 1,654 deletions.
13 changes: 7 additions & 6 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(navigate, 10, 150),
SCHED_TASK(update_compass, 10, 200),
SCHED_TASK(read_airspeed, 10, 100),
SCHED_TASK(read_aoa, 10, 200),
SCHED_TASK(update_alt, 10, 200),//This line added by Cole
//SCHED_TASK(read_aoa, 10, 200),
SCHED_TASK(update_alt, 10, 200),
SCHED_TASK(adjust_altitude_target, 10, 200),
#if ADVANCED_FAILSAFE == ENABLED
SCHED_TASK(afs_fs_check, 10, 100),
Expand All @@ -62,6 +62,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(read_rangefinder, 50, 100),
SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100),
SCHED_TASK_CLASS(Compass, &plane.compass, cal_update, 50, 50),
SCHED_TASK_CLASS(AS5600_AOA, &plane.aoa_sensor, getRawAngle, 10, 200),
SCHED_TASK(accel_cal_update, 10, 50),
#if OPTFLOW == ENABLED
SCHED_TASK_CLASS(OpticalFlow, &plane.optflow, update, 50, 50),
Expand Down Expand Up @@ -195,12 +196,12 @@ void Plane::update_compass(void)
}

/*
* Read and log Angle of Attack This function is code added by Cole
* Read and log Angle of Attack
*/

void Plane::read_aoa(void){
aoa_sensor.getRawAngle();
}
//void Plane::read_aoa(void){
// aoa_sensor.getRawAngle();
//}

/*
do 10Hz logging
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@
#include <AP_OSD/AP_OSD.h>

#include <AP_Rally/AP_Rally.h>
#include <AP_AS5600_AOA/AS5600_AOA.h> //Magnetic Encoder library, line added by Cole
#include <AP_AS5600_AOA/AS5600_AOA.h>

#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
#include <AP_Parachute/AP_Parachute.h>
Expand Down Expand Up @@ -197,7 +197,7 @@ class Plane : public AP_Vehicle {

AP_RPM rpm_sensor;

AS5600_AOA aoa_sensor; //This line added by Cole
AS5600_AOA aoa_sensor;

AP_TECS TECS_controller{ahrs, aparm, landing};
AP_L1_Control L1_controller{ahrs, &TECS_controller};
Expand Down Expand Up @@ -999,7 +999,7 @@ class Plane : public AP_Vehicle {
void read_airspeed(void);
void rpm_update(void);
void accel_cal_update(void);
void read_aoa(void); //This line added by Cole
void read_aoa(void);

// system.cpp
void init_ardupilot() override;
Expand Down
Loading

0 comments on commit f24e111

Please sign in to comment.