mirror of https://github.com/ArduPilot/ardupilot
SITL: fixed the vehicle type of the simulated ship
this was broken by https://github.com/ArduPilot/ardupilot/pull/23763 we need to look for other places where we have assumed the MAVLink field orderin in recent changes
This commit is contained in:
parent
252d133110
commit
5646cfbd57
|
@ -183,12 +183,11 @@ void ShipSim::send_report(void)
|
||||||
|
|
||||||
if (now - last_heartbeat_ms >= 1000) {
|
if (now - last_heartbeat_ms >= 1000) {
|
||||||
last_heartbeat_ms = now;
|
last_heartbeat_ms = now;
|
||||||
|
|
||||||
const mavlink_heartbeat_t heartbeat{
|
const mavlink_heartbeat_t heartbeat{
|
||||||
MAV_TYPE_SURFACE_BOAT,
|
type : MAV_TYPE_SURFACE_BOAT,
|
||||||
MAV_AUTOPILOT_INVALID,
|
autopilot : MAV_AUTOPILOT_INVALID};
|
||||||
0,
|
|
||||||
0,
|
|
||||||
0};
|
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
mavlink_msg_heartbeat_encode_status(
|
mavlink_msg_heartbeat_encode_status(
|
||||||
sys_id.get(),
|
sys_id.get(),
|
||||||
|
|
Loading…
Reference in New Issue