mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-22 12:27:34 +08:00
Increased param rate, fixed wrong usage of MAVLink chan.
This commit is contained in:
@@ -661,7 +661,7 @@ int Mavlink::mavlink_pm_send_param(param_t param)
|
||||
|
||||
mavlink_msg_param_value_pack_chan(mavlink_system.sysid,
|
||||
mavlink_system.compid,
|
||||
MAVLINK_COMM_0,
|
||||
_channel,
|
||||
&tx_msg,
|
||||
name_buf,
|
||||
val_buf,
|
||||
@@ -1561,7 +1561,6 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
int ch;
|
||||
_baudrate = 57600;
|
||||
_datarate = 0;
|
||||
_channel = MAVLINK_COMM_0;
|
||||
|
||||
_mode = MODE_OFFBOARD;
|
||||
|
||||
@@ -1776,7 +1775,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
_mavlink_param_queue_index = param_count();
|
||||
|
||||
MavlinkRateLimiter slow_rate_limiter(2000000.0f / rate_mult);
|
||||
MavlinkRateLimiter fast_rate_limiter(100000.0f / rate_mult);
|
||||
MavlinkRateLimiter fast_rate_limiter(20000.0f / rate_mult);
|
||||
|
||||
/* set main loop delay depending on data rate to minimize CPU overhead */
|
||||
_main_loop_delay = MAIN_LOOP_DELAY / rate_mult;
|
||||
|
||||
@@ -912,7 +912,7 @@ MavlinkReceiver::receive_thread(void *arg)
|
||||
_mavlink->mavlink_wpm_message_handler(&msg);
|
||||
|
||||
/* handle packet with parameter component */
|
||||
_mavlink->mavlink_pm_message_handler(MAVLINK_COMM_0, &msg);
|
||||
_mavlink->mavlink_pm_message_handler(_mavlink->get_channel(), &msg);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user