Skip to content

Commit

Permalink
GCS_MAVLink: count parameters in param thread
Browse files Browse the repository at this point in the history
This helps avoid counting parameters on the main thread,
avoiding long-loops
  • Loading branch information
peterbarker authored and tridge committed May 10, 2017
1 parent 92f88e9 commit b18c185
Showing 1 changed file with 10 additions and 7 deletions.
17 changes: 10 additions & 7 deletions libraries/GCS_MAVLink/GCS_Param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,14 +233,8 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg)

// queue it for processing by io timer
param_requests.push(req);

if (!param_timer_registered) {
param_timer_registered = true;
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::param_io_timer, void));
}

}

void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class *DataFlash)
{
mavlink_param_set_t packet;
Expand Down Expand Up @@ -355,6 +349,11 @@ void GCS_MAVLINK::send_parameter_value_all(const char *param_name, ap_var_type p
*/
void GCS_MAVLINK::send_queued_parameters(void)
{
if (!param_timer_registered) {
param_timer_registered = true;
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::param_io_timer, void));
}

if (_queued_parameter == nullptr &&
param_replies.empty()) {
return;
Expand All @@ -375,6 +374,10 @@ void GCS_MAVLINK::param_io_timer(void)
{
struct pending_param_request req;

// this is mostly a no-op, but doing this here means we won't
// block the main thread counting parameters (~30ms on PH)
AP_Param::count_parameters();

if (param_replies.space() == 0) {
// no room
return;
Expand Down

0 comments on commit b18c185

Please sign in to comment.