MAVLink: Start app using pre-configured streams to save some script execution overhead. Frees 1K during app startup, which should help FMUv1 considerably.

This commit is contained in:
Lorenz Meier
2015-08-22 20:31:45 +02:00
parent 86e2e7e2a6
commit e1aaaa1f18
3 changed files with 25 additions and 19 deletions

View File

@@ -1353,6 +1353,8 @@ Mavlink::task_main(int argc, char *argv[])
_mode = MAVLINK_MODE_ONBOARD;
} else if (strcmp(optarg, "osd") == 0) {
_mode = MAVLINK_MODE_OSD;
} else if (strcmp(optarg, "config") == 0) {
_mode = MAVLINK_MODE_CONFIG;
}
break;
@@ -1449,8 +1451,6 @@ Mavlink::task_main(int argc, char *argv[])
/* start the MAVLink receiver */
_receive_thread = MavlinkReceiver::receive_start(this);
_task_running = true;
MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update));
uint64_t param_time = 0;
MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status));
@@ -1537,6 +1537,23 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("RC_CHANNELS_RAW", 5.0f);
break;
case MAVLINK_MODE_CONFIG:
// Enable a number of interesting streams we want via USB
configure_stream("PARAM_VALUE", 300.0f);
configure_stream("MISSION_ITEM", 50.0f);
configure_stream("NAMED_VALUE_FLOAT", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("VFR_HUD", 20.0f);
configure_stream("ATTITUDE", 100.0f);
configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f);
configure_stream("RC_CHANNELS_RAW", 5.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 20.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
configure_stream("LOCAL_POSITION_NED", 30.0f);
configure_stream("MANUAL_CONTROL", 5.0f);
configure_stream("HIGHRES_IMU", 100.0f);
configure_stream("GPS_RAW_INT", 20.0f);
default:
break;
}
@@ -1703,6 +1720,9 @@ Mavlink::task_main(int argc, char *argv[])
}
perf_end(_loop_perf);
/* confirm task running only once fully initialized */
_task_running = true;
}
delete _subscribe_to_stream;