I want to increase stream rate of HIGHRES_IMU
message to 200 Hz for streaming to companion board via telem2 connecting to odroid via USB FTDI, and use a sample code from c_uart_interface_example.
I have done with editing mavlink_main.cpp
in Firmware as follow
case MAVLINK_MODE_ONBOARD:
configure_stream("SYS_STATUS", 5.0f);
configure_stream("EXTENDED_SYS_STATE", 5.0f);
configure_stream("HIGHRES_IMU",200.0f); //Default is 50.0f
configure_stream("ATTITUDE", 50.0f); //Default is 250.0f
configure_stream("ATTITUDE_QUATERNION", 50.0f);
configure_stream("RC_CHANNELS", 20.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 10.0f);
configure_stream("ALTITUDE", 10.0f);
configure_stream("GPS_RAW_INT", 5.0f);
configure_stream("ADSB_VEHICLE", 10.0f);
configure_stream("COLLISION", 10.0f);
configure_stream("DISTANCE_SENSOR", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("VISION_POSITION_ESTIMATE", 10.0f);
configure_stream("ESTIMATOR_STATUS", 1.0f);
configure_stream("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream("GLOBAL_POSITION_INT", 50.0f);
configure_stream("LOCAL_POSITION_NED", 30.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
configure_stream("ATTITUDE_TARGET", 10.0f);
configure_stream("HOME_POSITION", 0.5f);
configure_stream("NAMED_VALUE_FLOAT", 10.0f);
configure_stream("VFR_HUD", 10.0f);
configure_stream("WIND_COV", 10.0f);
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("TIMESYNC", 10.0f);
configure_stream("CAMERA_CAPTURE", 2.0f);
//camera trigger is rate limited at the source, do not limit here
configure_stream("CAMERA_TRIGGER", 50.0f);
configure_stream("CAMERA_IMAGE_CAPTURED", 5.0f);
configure_stream("ACTUATOR_CONTROL_TARGET0", 10.0f);
break;
First, I changed only value for HIGHRES_IMU but leave the other as default.
configure_stream("HIGHRES_IMU",200.0f); //Default is 50.0f
configure_stream("ATTITUDE", 250.0f);
it result to higher streaming rate of HIGHRES_IMU
(result is only 10 Hz)
Then I reduce the value of ATTITUDE
(I assume that there is no space left to increase imu message) but the result is the same (10 Hz).
configure_stream("HIGHRES_IMU",200.0f); //Default is 50.0f
configure_stream("ATTITUDE", 50.0f); //Default is 250.0f
I have tried with MAV_CMD_SET_MESSAGE_INTERVAL
, but nothing change, I still not able to get 200 Hz at this point.
mavlink_command_long_t com;
com.target_system = system_id;
com.target_component = autopilot_id;
com.command = MAV_CMD_SET_MESSAGE_INTERVAL;
com.confirmation = 0;
com.param1 = MAVLINK_MSG_ID_HIGHRES_IMU;
com.param2 = 5000;
// Encode
mavlink_message_t message;
mavlink_msg_command_long_encode(system_id, companion_id, &message, &com);
// Send the message
int len = serial_port->write_message(message);
Does anyone know how to increase stream rate of a message (especially HIGHRES_IMU
) please help me. or If there is a limitation please advice me.
Thank you,