Rover: update GPS at 50hz
This commit is contained in:
parent
cc53b9c39d
commit
24dd9a1c2c
@ -49,8 +49,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK(read_rangefinders, 50, 200),
|
||||
SCHED_TASK(update_current_mode, 50, 200),
|
||||
SCHED_TASK(set_servos, 50, 200),
|
||||
SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300),
|
||||
SCHED_TASK(update_GPS_10Hz, 10, 300),
|
||||
SCHED_TASK(update_GPS, 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),
|
||||
@ -304,9 +303,9 @@ void Rover::one_second_loop(void)
|
||||
update_sensor_status_flags();
|
||||
}
|
||||
|
||||
void Rover::update_GPS_10Hz(void)
|
||||
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();
|
||||
|
||||
|
@ -390,8 +390,7 @@ private:
|
||||
void update_logging2(void);
|
||||
void update_aux(void);
|
||||
void one_second_loop(void);
|
||||
void update_GPS_50Hz(void);
|
||||
void update_GPS_10Hz(void);
|
||||
void update_GPS(void);
|
||||
void update_current_mode(void);
|
||||
|
||||
// capabilities.cpp
|
||||
|
Loading…
Reference in New Issue
Block a user