mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: Add solo shot message fixes
This commit is contained in:
parent
1d627a23ed
commit
59926f99b9
@ -1173,7 +1173,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
roi_loc.lat = packet.x;
|
roi_loc.lat = packet.x;
|
||||||
roi_loc.lng = packet.y;
|
roi_loc.lng = packet.y;
|
||||||
roi_loc.alt = (int32_t)(packet.z * 100.0f);
|
roi_loc.alt = (int32_t)(packet.z * 100.0f);
|
||||||
copter.set_auto_yaw_roi(roi_loc);
|
sub.set_auto_yaw_roi(roi_loc);
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -1724,11 +1724,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// check for supported coordinate frames
|
// check for supported coordinate frames
|
||||||
if (packet.coordinate_frame != MAV_FRAME_GLOBAL_INT &&
|
if (packet.coordinate_frame != MAV_FRAME_GLOBAL_INT &&
|
||||||
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT && // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
|
||||||
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
|
||||||
break;
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
||||||
}
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
||||||
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
|
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
|
||||||
@ -1749,6 +1750,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
loc.lng = packet.lon_int;
|
loc.lng = packet.lon_int;
|
||||||
loc.alt = packet.alt*100;
|
loc.alt = packet.alt*100;
|
||||||
switch (packet.coordinate_frame) {
|
switch (packet.coordinate_frame) {
|
||||||
|
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
|
||||||
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
|
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
|
||||||
loc.flags.relative_alt = true;
|
loc.flags.relative_alt = true;
|
||||||
loc.flags.terrain_alt = false;
|
loc.flags.terrain_alt = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user