diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2015-04-27 22:33:32 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2015-04-27 22:33:32 +0200 |
commit | f56efaf149807cbdc559a88df1abcf9bb13b9364 (patch) | |
tree | 7bf56e57c71bcfedc47a7af9be4bab290beb21da /src/modules/mavlink | |
parent | 8595c734e646f22226672e0e06b6c38e0d80cb20 (diff) | |
parent | bd1c3363df44170523c68fd87ee19f2582a5e8fc (diff) | |
download | px4-firmware-stable.tar.gz px4-firmware-stable.tar.bz2 px4-firmware-stable.zip |
Merge branch 'master' into stablestable
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r-- | src/modules/mavlink/mavlink_main.cpp | 2 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink_messages.cpp | 2 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink_messages.h | 2 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink_parameters.cpp | 5 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink_receiver.cpp | 2 |
5 files changed, 7 insertions, 6 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index ba049bac4..22ff3edf6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -90,7 +90,7 @@ static const int ERROR = -1; #define DEFAULT_DEVICE_NAME "/dev/ttyS1" -#define MAX_DATA_RATE 20000 ///< max data rate in bytes/s +#define MAX_DATA_RATE 60000 ///< max data rate in bytes/s #define MAIN_LOOP_DELAY 10000 ///< 100 Hz @ 1000 bytes/s data rate #define FLOW_CONTROL_DISABLE_THRESHOLD 40 ///< picked so that some messages still would fit it. diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 276035aa2..7ddc52fd1 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -2231,7 +2231,7 @@ protected: }; -StreamListItem *streams_list[] = { +const StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static), new StreamListItem(&MavlinkStreamStatustext::new_instance, &MavlinkStreamStatustext::get_name_static), new StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static), diff --git a/src/modules/mavlink/mavlink_messages.h b/src/modules/mavlink/mavlink_messages.h index 7e4416609..5b6b9d633 100644 --- a/src/modules/mavlink/mavlink_messages.h +++ b/src/modules/mavlink/mavlink_messages.h @@ -56,6 +56,6 @@ public: ~StreamListItem() {}; }; -extern StreamListItem *streams_list[]; +extern const StreamListItem *streams_list[]; #endif /* MAVLINK_MESSAGES_H_ */ diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index 20d7cfdbb..9c8794017 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -130,7 +130,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) } else { /* when index is >= 0, send this parameter again */ - send_param(param_for_index(req_read.param_index)); + send_param(param_for_used_index(req_read.param_index)); } } break; @@ -192,6 +192,7 @@ MavlinkParametersManager::send(const hrt_abstime t) /* look for the first parameter which is used */ param_t p; do { + /* walk through all parameters, including unused ones */ p = param_for_index(_send_all_index); _send_all_index++; } while (p != PARAM_INVALID && !param_used(p)); @@ -200,7 +201,7 @@ MavlinkParametersManager::send(const hrt_abstime t) send_param(p); } - if (_send_all_index >= (int) param_count()) { + if ((p == PARAM_INVALID) || (_send_all_index >= (int) param_count())) { _send_all_index = -1; } } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index faede15cb..c4e332bf1 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -822,7 +822,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) /* Publish attitude setpoint if attitude and thrust ignore bits are not set */ if (!(_offboard_control_mode.ignore_attitude)) { - static struct vehicle_attitude_setpoint_s att_sp = {}; + struct vehicle_attitude_setpoint_s att_sp = {}; att_sp.timestamp = hrt_absolute_time(); mavlink_quaternion_to_euler(set_attitude_target.q, &att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body); |