mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 06:36:45 +08:00
simulator_mavlink: send MAV_CMD_SET_MESSAGE_INTERVAL to enable ground truth
This commit is contained in:
@@ -610,6 +610,13 @@ void Simulator::pollForMAVLinkMessages(bool publish, int udp_port)
|
||||
|
||||
const unsigned max_wait_ms = 6;
|
||||
|
||||
//send MAV_CMD_SET_MESSAGE_INTERVAL for HIL_STATE_QUATERNION ground truth
|
||||
mavlink_command_long_t cmd_long = {};
|
||||
cmd_long.command = MAV_CMD_SET_MESSAGE_INTERVAL;
|
||||
cmd_long.param1 = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
|
||||
cmd_long.param2 = 5e3;
|
||||
send_mavlink_message(MAVLINK_MSG_ID_COMMAND_LONG, &cmd_long, 200);
|
||||
|
||||
// wait for new mavlink messages to arrive
|
||||
while (true) {
|
||||
|
||||
|
||||
Reference in New Issue
Block a user