diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-10-07 22:49:27 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-10-07 22:49:27 +0200 |
commit | 4a8d20e2e562b69f3d2272d3e40db2b7a3e5152a (patch) | |
tree | 05bb8ef2f9443110c0dfa0e3915ecc391dadf5c6 /src/modules/mavlink/mavlink_main.cpp | |
parent | 8c6c08dcb5ce87e613cbf867571f219a60e1b813 (diff) | |
parent | 91b4d85b46f1d4514fe1ce45553753eb011918c1 (diff) | |
download | px4-firmware-4a8d20e2e562b69f3d2272d3e40db2b7a3e5152a.tar.gz px4-firmware-4a8d20e2e562b69f3d2272d3e40db2b7a3e5152a.tar.bz2 px4-firmware-4a8d20e2e562b69f3d2272d3e40db2b7a3e5152a.zip |
Merged master into st24
Diffstat (limited to 'src/modules/mavlink/mavlink_main.cpp')
-rw-r--r-- | src/modules/mavlink/mavlink_main.cpp | 12 |
1 files changed, 11 insertions, 1 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 940e64144..0d932d20a 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -123,6 +123,7 @@ Mavlink::Mavlink() : _task_running(false), _hil_enabled(false), _use_hil_gps(false), + _forward_externalsp(false), _is_usb_uart(false), _wait_to_transmit(false), _received_messages(false), @@ -483,6 +484,7 @@ void Mavlink::mavlink_update_system(void) _param_component_id = param_find("MAV_COMP_ID"); _param_system_type = param_find("MAV_TYPE"); _param_use_hil_gps = param_find("MAV_USEHILGPS"); + _param_forward_externalsp = param_find("MAV_FWDEXTSP"); } /* update system and component id */ @@ -529,6 +531,11 @@ void Mavlink::mavlink_update_system(void) param_get(_param_use_hil_gps, &use_hil_gps); _use_hil_gps = (bool)use_hil_gps; + + int32_t forward_externalsp; + param_get(_param_forward_externalsp, &forward_externalsp); + + _forward_externalsp = (bool)forward_externalsp; } int Mavlink::get_system_id() @@ -1396,7 +1403,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f); configure_stream("ATTITUDE_TARGET", 3.0f); configure_stream("DISTANCE_SENSOR", 0.5f); - configure_stream("OPTICAL_FLOW", 20.0f); + configure_stream("OPTICAL_FLOW", 5.0f); break; case MAVLINK_MODE_ONBOARD: @@ -1404,6 +1411,9 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("ATTITUDE", 50.0f); configure_stream("GLOBAL_POSITION_INT", 50.0f); configure_stream("CAMERA_CAPTURE", 2.0f); + configure_stream("ATTITUDE_TARGET", 10.0f); + configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f); + configure_stream("VFR_HUD", 10.0f); break; default: |