Browse Source

ArduSub: update_trigger() is now called in AP_Camera update()

zr-v5.1
Mirko Denecke 5 years ago committed by Randy Mackay
parent
commit
1db0feea59
  1. 28
      ArduSub/ArduSub.cpp
  2. 1
      ArduSub/Sub.h

28
ArduSub/ArduSub.cpp

@ -26,7 +26,7 @@ @@ -26,7 +26,7 @@
*/
const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(fifty_hz_loop, 50, 75),
SCHED_TASK(update_GPS, 50, 200),
SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200),
#if OPTFLOW == ENABLED
SCHED_TASK_CLASS(OpticalFlow, &sub.optflow, update, 200, 160),
#endif
@ -47,7 +47,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { @@ -47,7 +47,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75),
#endif
#if CAMERA == ENABLED
SCHED_TASK_CLASS(AP_Camera, &sub.camera, update_trigger, 50, 75),
SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75),
#endif
SCHED_TASK(ten_hz_logging_loop, 10, 350),
SCHED_TASK(twentyfive_hz_logging, 25, 110),
@ -286,30 +286,6 @@ void Sub::one_hz_loop() @@ -286,30 +286,6 @@ void Sub::one_hz_loop()
set_likely_flying(hal.util->get_soft_armed());
}
// called at 50hz
void Sub::update_GPS()
{
static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; // time of last gps message
bool gps_updated = false;
gps.update();
// log after every gps message
for (uint8_t i=0; i<gps.num_sensors(); i++) {
if (gps.last_message_time_ms(i) != last_gps_reading[i]) {
last_gps_reading[i] = gps.last_message_time_ms(i);
gps_updated = true;
break;
}
}
if (gps_updated) {
#if CAMERA == ENABLED
camera.update();
#endif
}
}
void Sub::read_AHRS()
{
// Perform IMU calculations and get attitude info

1
ArduSub/Sub.h

@ -409,7 +409,6 @@ private: @@ -409,7 +409,6 @@ private:
void twentyfive_hz_logging();
void three_hz_loop();
void one_hz_loop();
void update_GPS(void);
void update_turn_counter();
void read_AHRS(void);
void update_altitude();

Loading…
Cancel
Save