mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
SITL: Sim_Ship: label global_position_int and attitude packet fields
This commit is contained in:
parent
28488cbfd6
commit
b30bdb7dd3
@ -210,15 +210,15 @@ void ShipSim::send_report(void)
|
|||||||
vel.rotate(radians(ship.heading_deg));
|
vel.rotate(radians(ship.heading_deg));
|
||||||
|
|
||||||
const mavlink_global_position_int_t global_position_int{
|
const mavlink_global_position_int_t global_position_int{
|
||||||
now,
|
time_boot_ms: now,
|
||||||
loc.lat,
|
lat: loc.lat,
|
||||||
loc.lng,
|
lon: loc.lng,
|
||||||
alt_mm,
|
alt: alt_mm,
|
||||||
0,
|
relative_alt: 0,
|
||||||
int16_t(vel.x*100),
|
vx: int16_t(vel.x*100),
|
||||||
int16_t(vel.y*100),
|
vy: int16_t(vel.y*100),
|
||||||
0,
|
vz: 0,
|
||||||
uint16_t(ship.heading_deg*100)
|
hdg: uint16_t(ship.heading_deg*100)
|
||||||
};
|
};
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
mavlink_msg_global_position_int_encode_status(
|
mavlink_msg_global_position_int_encode_status(
|
||||||
@ -236,9 +236,13 @@ void ShipSim::send_report(void)
|
|||||||
|
|
||||||
{ // also set ATTITUDE so MissionPlanner can display ship orientation
|
{ // also set ATTITUDE so MissionPlanner can display ship orientation
|
||||||
const mavlink_attitude_t attitude{
|
const mavlink_attitude_t attitude{
|
||||||
now,
|
time_boot_ms: now,
|
||||||
0, 0, float(radians(ship.heading_deg)),
|
roll: 0,
|
||||||
0, 0, ship.yaw_rate
|
pitch: 0,
|
||||||
|
yaw: float(radians(ship.heading_deg)),
|
||||||
|
rollspeed: 0,
|
||||||
|
pitchspeed: 0,
|
||||||
|
yawspeed: ship.yaw_rate
|
||||||
};
|
};
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
mavlink_msg_attitude_encode_status(
|
mavlink_msg_attitude_encode_status(
|
||||||
|
Loading…
Reference in New Issue
Block a user