forked from Archive/PX4-Autopilot
use open/close instead of px4_open/px4_close for parameter file
This commit is contained in:
parent
7cde53597c
commit
f4a25097c1
|
@ -202,7 +202,7 @@ static int
|
|||
do_save(const char *param_file_name)
|
||||
{
|
||||
/* create the file */
|
||||
int fd = px4_open(param_file_name, O_WRONLY | O_CREAT, 0x777);
|
||||
int fd = open(param_file_name, O_WRONLY | O_CREAT, 0x777);
|
||||
|
||||
if (fd < 0) {
|
||||
warn("opening '%s' failed", param_file_name);
|
||||
|
@ -210,7 +210,7 @@ do_save(const char *param_file_name)
|
|||
}
|
||||
|
||||
int result = param_export(fd, false);
|
||||
px4_close(fd);
|
||||
close(fd);
|
||||
|
||||
if (result < 0) {
|
||||
(void)unlink(param_file_name);
|
||||
|
@ -224,7 +224,7 @@ do_save(const char *param_file_name)
|
|||
static int
|
||||
do_load(const char *param_file_name)
|
||||
{
|
||||
int fd = px4_open(param_file_name, O_RDONLY);
|
||||
int fd = open(param_file_name, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
warn("open '%s'", param_file_name);
|
||||
|
@ -232,7 +232,7 @@ do_load(const char *param_file_name)
|
|||
}
|
||||
|
||||
int result = param_load(fd);
|
||||
px4_close(fd);
|
||||
close(fd);
|
||||
|
||||
if (result < 0) {
|
||||
warnx("error importing from '%s'", param_file_name);
|
||||
|
@ -245,7 +245,7 @@ do_load(const char *param_file_name)
|
|||
static int
|
||||
do_import(const char *param_file_name)
|
||||
{
|
||||
int fd = px4_open(param_file_name, O_RDONLY);
|
||||
int fd = open(param_file_name, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
warn("open '%s'", param_file_name);
|
||||
|
@ -253,7 +253,7 @@ do_import(const char *param_file_name)
|
|||
}
|
||||
|
||||
int result = param_import(fd);
|
||||
px4_close(fd);
|
||||
close(fd);
|
||||
|
||||
if (result < 0) {
|
||||
warnx("error importing from '%s'", param_file_name);
|
||||
|
|
Loading…
Reference in New Issue