mirror of https://github.com/ArduPilot/ardupilot
Rover: Implemented the HOME state update from Plane
This commit is contained in:
parent
1d51e60571
commit
2d1745ab6a
|
@ -382,6 +382,10 @@ void Rover::update_GPS_10Hz(void)
|
|||
do_take_picture();
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
update_home();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -363,7 +363,7 @@ void Rover::Log_Write_Home_And_Origin()
|
|||
#endif
|
||||
|
||||
// log ahrs home if set
|
||||
if (home_is_set) {
|
||||
if (home_is_set != HOME_UNSET) {
|
||||
DataFlash.Log_Write_Origin(LogOriginType::ahrs_home, ahrs.get_home());
|
||||
}
|
||||
}
|
||||
|
|
|
@ -314,8 +314,9 @@ private:
|
|||
// The home location used for RTL. The location is set when we first get stable GPS lock
|
||||
const struct Location &home;
|
||||
|
||||
// Flag for if we have gps lock and have set the home location
|
||||
bool home_is_set;
|
||||
// Flag for if we have g_gps lock and have set the home location in AHRS
|
||||
enum HomeState home_is_set = HOME_UNSET;
|
||||
|
||||
// The location of the previous waypoint. Used for track following and altitude ramp calculations
|
||||
struct Location prev_WP;
|
||||
// The location of the current/active waypoint. Used for track following
|
||||
|
|
|
@ -66,7 +66,7 @@ void Rover::init_home()
|
|||
gcs_send_text(MAV_SEVERITY_INFO, "init home");
|
||||
|
||||
ahrs.set_home(gps.location());
|
||||
home_is_set = true;
|
||||
home_is_set = HOME_SET_NOT_LOCKED;
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(gps.location());
|
||||
|
||||
|
@ -88,3 +88,18 @@ void Rover::restart_nav()
|
|||
prev_WP = current_loc;
|
||||
mission.start_or_resume();
|
||||
}
|
||||
|
||||
/*
|
||||
update home location from GPS
|
||||
this is called as long as we have 3D lock and the arming switch is
|
||||
not pushed
|
||||
*/
|
||||
void Rover::update_home()
|
||||
{
|
||||
if (home_is_set == HOME_SET_NOT_LOCKED) {
|
||||
ahrs.set_home(gps.location());
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(gps.location());
|
||||
}
|
||||
barometer.update_calibration();
|
||||
}
|
||||
|
|
|
@ -324,7 +324,7 @@ void Rover::do_set_home(const AP_Mission::Mission_Command& cmd)
|
|||
init_home();
|
||||
} else {
|
||||
ahrs.set_home(cmd.content.location);
|
||||
home_is_set = true;
|
||||
home_is_set = HOME_SET_NOT_LOCKED;
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(cmd.content.location);
|
||||
}
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
void Rover::update_commands(void)
|
||||
{
|
||||
if(control_mode == AUTO) {
|
||||
if(home_is_set == true && mission.num_commands() > 1) {
|
||||
if (home_is_set != HOME_UNSET && mission.num_commands() > 1) {
|
||||
mission.update();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -13,7 +13,7 @@ void Rover::navigate()
|
|||
return;
|
||||
}
|
||||
|
||||
if ((next_WP.lat == 0)||(home_is_set==false)){
|
||||
if ((next_WP.lat == 0) || (home_is_set==HOME_UNSET)){
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue