mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: update_trigger() is now called in AP_Camera update()
This commit is contained in:
parent
10a85892cf
commit
89d423556c
|
@ -91,7 +91,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||
SCHED_TASK(rc_loop, 100, 130),
|
||||
SCHED_TASK(throttle_loop, 50, 75),
|
||||
SCHED_TASK(update_GPS, 50, 200),
|
||||
SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200),
|
||||
#if OPTFLOW == ENABLED
|
||||
SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160),
|
||||
#endif
|
||||
|
@ -150,7 +150,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75),
|
||||
#endif
|
||||
#if CAMERA == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Camera, &copter.camera, update_trigger, 50, 75),
|
||||
SCHED_TASK_CLASS(AP_Camera, &copter.camera, update, 50, 75),
|
||||
#endif
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
SCHED_TASK(ten_hz_logging_loop, 10, 350),
|
||||
|
@ -515,30 +515,6 @@ void Copter::one_hz_loop()
|
|||
AP_Notify::flags.flying = !ap.land_complete;
|
||||
}
|
||||
|
||||
// called at 50hz
|
||||
void Copter::update_GPS(void)
|
||||
{
|
||||
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 Copter::init_simple_bearing()
|
||||
{
|
||||
// capture current cos_yaw and sin_yaw values
|
||||
|
|
|
@ -652,7 +652,6 @@ private:
|
|||
void twentyfive_hz_logging();
|
||||
void three_hz_loop();
|
||||
void one_hz_loop();
|
||||
void update_GPS(void);
|
||||
void init_simple_bearing();
|
||||
void update_simple_mode(void);
|
||||
void update_super_simple_bearing(bool force_update);
|
||||
|
|
Loading…
Reference in New Issue