Posix: make simulated devices always pass self tests

To facilitate testing, the simulated devices always return OK for
self tests.

rc.S was also upated to set CAL_XXXY_ID to the devid so tests pass the
calibration check.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois
2015-04-21 23:29:07 -07:00
parent 36a9f7a818
commit 93dea668dc
3 changed files with 13 additions and 0 deletions
+4
View File
@@ -4,6 +4,10 @@ barosim start
adcsim start
accelsim start
gyrosim start
param set CAL_GYRO0_ID 2293760
param set CAL_ACC0_ID 1310720
param set CAL_ACC1_ID 1376256
param set CAL_MAG0_ID 196608
rgbled start
mavlink start
sensors start
@@ -707,6 +707,9 @@ ACCELSIM::ioctl(device::px4_dev_handle_t *handlep, int cmd, unsigned long arg)
memcpy((struct accel_scale *) arg, &_accel_scale, sizeof(_accel_scale));
return OK;
case ACCELIOCSELFTEST:
return OK;
default:
/* give it to the superclass */
return VDev::ioctl(handlep, cmd, arg);
@@ -824,6 +827,8 @@ ACCELSIM::mag_ioctl(device::px4_dev_handle_t *handlep, int cmd, unsigned long ar
*/
return 0;
case MAGIOCSELFTEST:
return OK;
default:
/* give it to the superclass */
return VDev::ioctl(handlep, cmd, arg);
@@ -782,6 +782,8 @@ GYROSIM::self_test()
int
GYROSIM::accel_self_test()
{
return OK;
if (self_test())
return 1;
@@ -807,6 +809,8 @@ GYROSIM::accel_self_test()
int
GYROSIM::gyro_self_test()
{
return OK;
if (self_test())
return 1;