From d81d20ff0e3a8a5592c57951be1a2b2c7cb7bc29 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 19 Jun 2015 11:51:37 -0700 Subject: [PATCH 1/3] VDev: Add missing break --- src/drivers/device/vdev.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/drivers/device/vdev.cpp b/src/drivers/device/vdev.cpp index 89a3da3e0a..d992851309 100644 --- a/src/drivers/device/vdev.cpp +++ b/src/drivers/device/vdev.cpp @@ -324,6 +324,7 @@ VDev::ioctl(file_t *filep, int cmd, unsigned long arg) case DEVIOCGDEVICEID: ret = (int)_device_id.devid; PX4_INFO("IOCTL DEVIOCGDEVICEID %d", ret); + break; default: break; } From 27cec4a977cdf19c02f8ad9e03d0eaa8aa4149a1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 19 Jun 2015 11:52:07 -0700 Subject: [PATCH 2/3] VDev POSIX: Fix non-POSIX conformant return value handling --- src/drivers/device/vdev_posix.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/device/vdev_posix.cpp b/src/drivers/device/vdev_posix.cpp index 727b92a1ed..975700d4e8 100644 --- a/src/drivers/device/vdev_posix.cpp +++ b/src/drivers/device/vdev_posix.cpp @@ -201,7 +201,7 @@ int px4_ioctl(int fd, int cmd, unsigned long arg) px4_errno = -ret; } - return (ret == 0) ? PX4_OK : PX4_ERROR; + return ret; } int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout) From 3627456dd6c8668927ab9838b96f4dab3e5d1892 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 19 Jun 2015 12:01:48 -0700 Subject: [PATCH 3/3] POSIX config: Fix order of dev IDs --- posix-configs/SITL/init/rcS | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/posix-configs/SITL/init/rcS b/posix-configs/SITL/init/rcS index c89714c02c..319cf4214d 100644 --- a/posix-configs/SITL/init/rcS +++ b/posix-configs/SITL/init/rcS @@ -7,8 +7,8 @@ dataman start mavlink start -u 14556 -r 60000 simulator start -s param set CAL_GYRO0_ID 2293760 -param set CAL_ACC0_ID 1310720 -param set CAL_ACC1_ID 1376256 +param set CAL_ACC0_ID 1376256 +param set CAL_ACC1_ID 1310720 param set CAL_MAG0_ID 196608 param set CAL_GYRO0_XOFF 0.01 param set CAL_ACC0_XOFF 0.01