Skip to content

Commit

Permalink
Adds recommended changes from previous PR review
Browse files Browse the repository at this point in the history
  • Loading branch information
colejmero committed Mar 5, 2021
1 parent f24e111 commit c26e328
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 7 deletions.
3 changes: 1 addition & 2 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ 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),
SCHED_TASK(adjust_altitude_target, 10, 200),
#if ADVANCED_FAILSAFE == ENABLED
Expand All @@ -62,7 +61,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_CLASS(AS5600_AOA, &plane.aoa_sensor, update, 10, 200),
SCHED_TASK(accel_cal_update, 10, 50),
#if OPTFLOW == ENABLED
SCHED_TASK_CLASS(OpticalFlow, &plane.optflow, update, 50, 50),
Expand Down
6 changes: 2 additions & 4 deletions libraries/AP_AS5600_AOA/AS5600_AOA.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,21 +72,19 @@ bool AS5600_AOA::init()
* Description: gets raw value of magnet position.
* start, end, and max angle settings do not apply
*******************************************************/
uint16_t AS5600_AOA::getRawAngle(void)
void AS5600_AOA::update(void)
{
WITH_SEMAPHORE(dev->get_semaphore());

//uint16_t angleRaw = readTwoBytes(REG_RAW_ANG_HI, REG_RAW_ANG_LO);
if (!dev->read_registers(REG_RAW_ANG_HI, &highByte, 1) || !dev->read_registers(REG_RAW_ANG_LO, &lowByte, 1)){
return -1;
return;
}

//Gets the two relevant register values and multiplies by conversion factor to get degrees
uint16_t angleRaw = ((highByte << 8) | lowByte)*0.087;

AP::logger().Write("AOAR", "TimeUS, Angle", "QH", AP_HAL::micros64(), angleRaw);

return angleRaw;
}


Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_AS5600_AOA/AS5600_AOA.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,14 @@ class AS5600_AOA {

bool init();

void update(void);

uint16_t setMaxAngle(uint16_t newMaxAngle = -1);
uint16_t getMaxAngle();
uint16_t setStartPosition(uint16_t startAngle = -1);
uint16_t getStartPosition();
uint16_t setEndPosition(uint16_t endAngle = -1);
uint16_t getEndPosition();
uint16_t getRawAngle(void);
uint16_t getScaledAngle();

int detectMagnet();
Expand Down

0 comments on commit c26e328

Please sign in to comment.