mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 14:27:35 +08:00
Fixed bug with fd leak in rc_calibration_check
This commit is contained in:
@@ -47,14 +47,12 @@
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#include <uORB/topics/rc_channels.h>
|
||||
|
||||
int rc_calibration_check(void) {
|
||||
int rc_calibration_check(int mavlink_fd) {
|
||||
|
||||
char nbuf[20];
|
||||
param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
|
||||
_parameter_handles_rev, _parameter_handles_dz;
|
||||
|
||||
int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
|
||||
float param_min, param_max, param_trim, param_rev, param_dz;
|
||||
|
||||
/* first check channel mappings */
|
||||
|
||||
@@ -47,6 +47,6 @@
|
||||
* @return 0 / OK if RC calibration is ok, index + 1 of the first
|
||||
* channel that failed else (so 1 == first channel failed)
|
||||
*/
|
||||
__EXPORT int rc_calibration_check(void);
|
||||
__EXPORT int rc_calibration_check(int mavlink_fd);
|
||||
|
||||
__END_DECLS
|
||||
|
||||
Reference in New Issue
Block a user