simulator_mavlink: send MAV_CMD_SET_MESSAGE_INTERVAL to enable ground truth

This commit is contained in:
Beat Küng 2016-10-20 16:06:35 +02:00 committed by Lorenz Meier
parent 7415d94e12
commit 7ed81e5edb

View File

@ -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) {