MAVLink: Allow data rate updates

This commit is contained in:
Lorenz Meier
2016-06-21 16:38:53 +02:00
parent 1869ffd15f
commit 2f113a4ce3
3 changed files with 14 additions and 3 deletions
+3
View File
@@ -417,6 +417,9 @@ public:
void set_logging_enabled(bool logging) { _logging_enabled = logging; }
int get_data_rate() { return _datarate; }
void set_data_rate(int rate) { if (rate > 0) _datarate = rate; }
protected:
Mavlink *next;
+6 -2
View File
@@ -360,7 +360,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
_mavlink->configure_stream_threadsafe("HOME_POSITION", 0.5f);
} else if (cmd_mavlink.command == MAV_CMD_SET_MESSAGE_INTERVAL) {
set_message_interval((int)cmd_mavlink.param1, cmd_mavlink.param2);
set_message_interval((int)(cmd_mavlink.param1 + 0.5f), cmd_mavlink.param2, cmd_mavlink.param3);
} else if (cmd_mavlink.command == MAV_CMD_GET_MESSAGE_INTERVAL) {
get_message_interval((int)cmd_mavlink.param1);
@@ -1402,8 +1402,12 @@ MavlinkReceiver::handle_message_request_data_stream(mavlink_message_t *msg)
}
void
MavlinkReceiver::set_message_interval(int msgId, float interval)
MavlinkReceiver::set_message_interval(int msgId, float interval, int data_rate)
{
if (data_rate > 0) {
_mavlink->set_data_rate(data_rate);
}
// configure_stream wants a rate (msgs/second), so convert here.
float rate = 0;
+5 -1
View File
@@ -148,8 +148,12 @@ private:
/**
* Set the interval at which the given message stream is published.
* The rate is the number of messages per second.
*
* @param msgId the message ID of to change the interval of
* @param interval the interval in us to send the message at
* @param data_rate the total link data rate in bytes per second
*/
void set_message_interval(int msgId, float rate);
void set_message_interval(int msgId, float interval, int data_rate=-1);
void get_message_interval(int msgId);
/**