aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/PreflightCheck.cpp
blob: 873f2c28906212b34bd26ec85e7d59018f820461 (plain) (blame)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
/****************************************************************************
 *
 *   Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

/**
 * @file PreflightCheck.cpp
 *
 * Preflight check for main system components
 *
 * @author Lorenz Meier <lorenz@px4.io>
 * @author Johan Jansen <jnsn.johan@gmail.com>
 */

#include <nuttx/config.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <fcntl.h>
#include <errno.h>
#include <math.h>

#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/rc_check.h>

#include <drivers/drv_hrt.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_baro.h>

#include <mavlink/mavlink_log.h>

#include "PreflightCheck.h"

namespace Commander
{
    static bool magnometerCheck(int mavlink_fd)
    {
        int fd = open(MAG0_DEVICE_PATH, 0);
        if (fd < 0) {
            warn("failed to open magnetometer - start with 'hmc5883 start' or 'lsm303d start'");
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: NO MAG");
            return false;
        }

        int calibration_devid;
        int devid = ioctl(fd, DEVIOCGDEVICEID,0);
        param_get(param_find("CAL_MAG0_ID"), &(calibration_devid));
        if (devid != calibration_devid){
            warnx("magnetometer calibration is for a different device - calibrate magnetometer first (dev: %d vs cal: %d)", devid, calibration_devid);
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: MAG CAL ID");
            return false;
        }

        int ret = ioctl(fd, MAGIOCSELFTEST, 0);
        if (ret != OK) {
            warnx("magnetometer calibration missing or bad - calibrate magnetometer first");
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: MAG CHECK/CAL");
            return false;
        }
        close(fd);
        return true;
    }

    static bool accelerometerCheck(int mavlink_fd)
    {
        int fd = open(ACCEL0_DEVICE_PATH, O_RDONLY);
        int ret = ioctl(fd, ACCELIOCSELFTEST, 0);

        int calibration_devid;
        int devid = ioctl(fd, DEVIOCGDEVICEID,0);
        param_get(param_find("CAL_ACC0_ID"), &(calibration_devid));
        if (devid != calibration_devid){
            warnx("accelerometer calibration is for a different device - calibrate accelerometer first");
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: ACC CAL ID");
            return false;
        }
        
        if (ret != OK) {
            warnx("accel self test failed");
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: ACCEL CHECK/CAL");
            return false;
        }

        // check measurement result range
        struct accel_report acc;
        ret = read(fd, &acc, sizeof(acc));

        if (ret == sizeof(acc)) {
            // evaluate values
            float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z);

            // evaluate values
            if (accel_magnitude > 30.0f) { //m/s^2
                warnx("accel with spurious values");
                mavlink_log_critical(mavlink_fd, "SENSOR FAIL: |ACCEL| > 30 m/s^2");
                //this is frickin' fatal
                return false;
            }
        } else {
            warnx("accel read failed");
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: ACCEL READ");
            //this is frickin' fatal
            return false;
        }

        close(fd);
        return true;
    }

    static bool gyroCheck(int mavlink_fd)
    {
        int fd = open(GYRO0_DEVICE_PATH, 0);
            
        int calibration_devid;
        int devid = ioctl(fd, DEVIOCGDEVICEID,0);
        param_get(param_find("CAL_GYRO0_ID"), &(calibration_devid));
        if (devid != calibration_devid){
            warnx("gyro calibration is for a different device - calibrate gyro first");
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: GYRO CAL ID");
            return false;
        }        

        int ret = ioctl(fd, GYROIOCSELFTEST, 0);

        if (ret != OK) {
            warnx("gyro self test failed");
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: GYRO CHECK/CAL");
            return false;
        }

        close(fd);
        return true;
    }

    static bool baroCheck(int mavlink_fd)
    {
        int fd = open(BARO0_DEVICE_PATH, 0);
        if(fd < 0) {
            mavlink_log_critical(mavlink_fd, "SENSOR FAIL: Barometer");
            return false;        
        }

        close(fd);
        return true;
    }

    bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro, bool checkBaro, bool checkRC)
    {
        //give the system some time to sample the sensors in the background
        usleep(150000);

        //Magnetometer
        if(checkMag) {
            if(!magnometerCheck(mavlink_fd)) {
                return false;
            }            
        }

        //Accelerometer
        if(checkAcc) {
            if(!accelerometerCheck(mavlink_fd)) {
                return false;
            }            
        }

        // ---- GYRO ----
        if(checkGyro) {
            if(!gyroCheck(mavlink_fd)) {
                return false;
            }            
        }

        // ---- BARO ----
        if(checkBaro) {
            if(!baroCheck(mavlink_fd)) {
                return false;
            }
        }

        // ---- RC CALIBRATION ----
        if(checkRC) {
            if(rc_calibration_check(mavlink_fd) != OK) {
                return false;
            }
        }

        //All is good!
        return true;
    }
}