mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: update_trigger() is now called in AP_Camera update()
This commit is contained in:
parent
2dfc7c4108
commit
6f0782abbf
@ -53,7 +53,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK(read_rangefinders, 50, 200),
|
||||
SCHED_TASK(update_current_mode, 400, 200),
|
||||
SCHED_TASK(set_servos, 400, 200),
|
||||
SCHED_TASK(update_GPS, 50, 300),
|
||||
SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300),
|
||||
SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200),
|
||||
SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200),
|
||||
@ -78,7 +78,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200),
|
||||
#endif
|
||||
#if CAMERA == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Camera, &rover.camera, update_trigger, 50, 200),
|
||||
SCHED_TASK_CLASS(AP_Camera, &rover.camera, update, 50, 200),
|
||||
#endif
|
||||
SCHED_TASK(gcs_failsafe_check, 10, 200),
|
||||
SCHED_TASK(fence_check, 10, 200),
|
||||
@ -328,18 +328,6 @@ void Rover::one_second_loop(void)
|
||||
g2.wp_nav.set_turn_params(g.turn_max_g, g2.turn_radius, g2.motors.have_skid_steering());
|
||||
}
|
||||
|
||||
void Rover::update_GPS(void)
|
||||
{
|
||||
gps.update();
|
||||
if (gps.last_message_time_ms() != last_gps_msg_ms) {
|
||||
last_gps_msg_ms = gps.last_message_time_ms();
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
camera.update();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void Rover::update_current_mode(void)
|
||||
{
|
||||
// check for emergency stop
|
||||
|
@ -238,9 +238,6 @@ private:
|
||||
// time that rudder/steering arming has been running
|
||||
uint32_t rudder_arm_timer;
|
||||
|
||||
// Store the time the last GPS message was received.
|
||||
uint32_t last_gps_msg_ms{0};
|
||||
|
||||
// latest wheel encoder values
|
||||
float wheel_encoder_last_distance_m[WHEELENCODER_MAX_INSTANCES]; // total distance recorded by wheel encoder (for reporting to GCS)
|
||||
bool wheel_encoder_initialised; // true once arrays below have been initialised to sensors initial values
|
||||
@ -285,7 +282,6 @@ private:
|
||||
void update_logging1(void);
|
||||
void update_logging2(void);
|
||||
void one_second_loop(void);
|
||||
void update_GPS(void);
|
||||
void update_current_mode(void);
|
||||
void update_mission(void);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user