mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Rover: support SET_GPS_GLOBAL_ORIGIN message
This commit is contained in:
parent
a477ef7cd6
commit
894bf2a23f
@ -643,6 +643,23 @@ void GCS_MAVLINK_Rover::handle_change_alt_request(AP_Mission::Mission_Command &c
|
||||
void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
|
||||
case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
|
||||
{
|
||||
mavlink_set_gps_global_origin_t packet;
|
||||
mavlink_msg_set_gps_global_origin_decode(msg, &packet);
|
||||
// sanity check location
|
||||
if (!check_latlng(packet.latitude, packet.longitude)) {
|
||||
break;
|
||||
}
|
||||
Location ekf_origin {};
|
||||
ekf_origin.lat = packet.latitude;
|
||||
ekf_origin.lng = packet.longitude;
|
||||
ekf_origin.alt = packet.altitude / 10;
|
||||
rover.set_ekf_origin(ekf_origin);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
||||
{
|
||||
handle_request_data_stream(msg, true);
|
||||
@ -829,6 +846,10 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
case MAV_CMD_GET_HOME_POSITION:
|
||||
if (rover.home_is_set != HOME_UNSET) {
|
||||
send_home(rover.ahrs.get_home());
|
||||
Location ekf_origin;
|
||||
if (rover.ahrs.get_origin(ekf_origin)) {
|
||||
send_ekf_origin(ekf_origin);
|
||||
}
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
result = MAV_RESULT_FAILED;
|
||||
|
@ -451,6 +451,7 @@ private:
|
||||
void update_home_from_EKF();
|
||||
bool set_home_to_current_location(bool lock);
|
||||
bool set_home(const Location& loc, bool lock);
|
||||
void set_ekf_origin(const Location& loc);
|
||||
void set_system_time_from_GPS();
|
||||
void update_home();
|
||||
|
||||
|
@ -35,10 +35,10 @@ bool Rover::set_home(const Location& loc, bool lock)
|
||||
return false;
|
||||
}
|
||||
|
||||
// set EKF origin to home if it hasn't been set yet
|
||||
// check if EKF origin has been set
|
||||
Location ekf_origin;
|
||||
if (!ahrs.get_origin(ekf_origin)) {
|
||||
ahrs.set_origin(loc);
|
||||
return false;
|
||||
}
|
||||
|
||||
// set ahrs home
|
||||
@ -69,8 +69,9 @@ bool Rover::set_home(const Location& loc, bool lock)
|
||||
// log ahrs home and ekf origin dataflash
|
||||
Log_Write_Home_And_Origin();
|
||||
|
||||
// send new home location to GCS
|
||||
// send new home and ekf origin to GCS
|
||||
gcs().send_home(loc);
|
||||
gcs().send_ekf_origin(loc);
|
||||
|
||||
// send text of home position to ground stations
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %.2fm",
|
||||
@ -82,6 +83,32 @@ bool Rover::set_home(const Location& loc, bool lock)
|
||||
return true;
|
||||
}
|
||||
|
||||
// sets ekf_origin if it has not been set.
|
||||
// should only be used when there is no GPS to provide an absolute position
|
||||
void Rover::set_ekf_origin(const Location& loc)
|
||||
{
|
||||
// check location is valid
|
||||
if (!check_latlng(loc)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check if EKF origin has already been set
|
||||
Location ekf_origin;
|
||||
if (ahrs.get_origin(ekf_origin)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!ahrs.set_origin(loc)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// log ahrs home and ekf origin dataflash
|
||||
Log_Write_Home_And_Origin();
|
||||
|
||||
// send ekf origin to GCS
|
||||
gcs().send_ekf_origin(loc);
|
||||
}
|
||||
|
||||
// checks if we should update ahrs/RTL home position from GPS
|
||||
void Rover::set_system_time_from_GPS()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user