mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: PREFLIGHT_SET_SENSOR_OFFSETS used to set compass offsets
replaces ardupilot specific SET_MAG_OFFSETS message
This commit is contained in:
parent
208a2de777
commit
b17125e261
@ -1065,6 +1065,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
|
||||
if (packet.param1 == 2) {
|
||||
// save first compass's offsets
|
||||
compass.set_and_save_offsets(0, packet.param2, packet.param3, packet.param4);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
if (packet.param1 == 5) {
|
||||
// save secondary compass's offsets
|
||||
compass.set_and_save_offsets(1, packet.param2, packet.param3, packet.param4);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
||||
if (packet.param1 == 1.0f) {
|
||||
// run pre_arm_checks and arm_checks and display failures
|
||||
@ -1288,17 +1301,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef MAVLINK_MSG_ID_SET_MAG_OFFSETS
|
||||
case MAVLINK_MSG_ID_SET_MAG_OFFSETS:
|
||||
{
|
||||
mavlink_set_mag_offsets_t packet;
|
||||
mavlink_msg_set_mag_offsets_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
compass.set_offsets(Vector3f(packet.mag_ofs_x, packet.mag_ofs_y, packet.mag_ofs_z));
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
// GCS has sent us a command from GCS, store to EEPROM
|
||||
case MAVLINK_MSG_ID_MISSION_ITEM:
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user