mirror of https://github.com/ArduPilot/ardupilot
Rover: MAV_CMD_DO_SET_HOME support in APMRover2
This commit is contained in:
parent
981f5a132e
commit
ff74792fd4
|
@ -1100,6 +1100,41 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case MAV_CMD_DO_SET_HOME:
|
||||||
|
{
|
||||||
|
// param1 : use current (1=use current location, 0=use specified location)
|
||||||
|
// param5 : latitude
|
||||||
|
// param6 : longitude
|
||||||
|
// param7 : altitude
|
||||||
|
result = MAV_RESULT_FAILED; // assume failure
|
||||||
|
if (is_equal(packet.param1,1.0f)) {
|
||||||
|
rover.init_home();
|
||||||
|
} else {
|
||||||
|
if (is_zero(packet.param5) && is_zero(packet.param6) && is_zero(packet.param7)) {
|
||||||
|
// don't allow the 0,0 position
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// sanity check location
|
||||||
|
if (fabsf(packet.param5) > 90.0f || fabsf(packet.param6) > 180.0f) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
Location new_home_loc {};
|
||||||
|
new_home_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
|
||||||
|
new_home_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
|
||||||
|
new_home_loc.alt = (int32_t)(packet.param7 * 100.0f);
|
||||||
|
rover.ahrs.set_home(new_home_loc);
|
||||||
|
rover.home_is_set = HOME_SET_NOT_LOCKED;
|
||||||
|
rover.Log_Write_Home_And_Origin();
|
||||||
|
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
rover.gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um",
|
||||||
|
(double)(new_home_loc.lat*1.0e-7f),
|
||||||
|
(double)(new_home_loc.lng*1.0e-7f),
|
||||||
|
(uint32_t)(new_home_loc.alt*0.01f));
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
case MAV_CMD_DO_START_MAG_CAL:
|
case MAV_CMD_DO_START_MAG_CAL:
|
||||||
case MAV_CMD_DO_ACCEPT_MAG_CAL:
|
case MAV_CMD_DO_ACCEPT_MAG_CAL:
|
||||||
case MAV_CMD_DO_CANCEL_MAG_CAL:
|
case MAV_CMD_DO_CANCEL_MAG_CAL:
|
||||||
|
|
Loading…
Reference in New Issue