Rover: remove arguments to send_home and send_ekf_origin
This commit is contained in:
parent
217fd73100
commit
0e8f01021d
@ -75,8 +75,8 @@ bool Rover::set_home(const Location& loc, bool lock)
|
||||
ahrs.Log_Write_Home_And_Origin();
|
||||
|
||||
// send new home and ekf origin to GCS
|
||||
gcs().send_home(loc);
|
||||
gcs().send_ekf_origin(loc);
|
||||
gcs().send_home();
|
||||
gcs().send_ekf_origin();
|
||||
|
||||
// send text of home position to ground stations
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %.2fm",
|
||||
@ -123,7 +123,7 @@ void Rover::update_home()
|
||||
if (get_distance(loc, ahrs.get_home()) > DISTANCE_HOME_MAX) {
|
||||
ahrs.set_home(loc);
|
||||
ahrs.Log_Write_Home_And_Origin();
|
||||
gcs().send_home(gps.location());
|
||||
gcs().send_home();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user