aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lorenz@px4.io>2015-01-20 12:24:42 +0100
committerLorenz Meier <lorenz@px4.io>2015-01-20 12:24:42 +0100
commitf3dcde39935766626155be70a88a89f4962af30a (patch)
treee8b8783ef0ecd64a1a321dad25d6078caf3d8eb9
parent9b10395e94497ef16c99390460808409e08d468f (diff)
parent65915e5d01cd0b1b8aed95c827a4886f3a57e545 (diff)
downloadpx4-firmware-f3dcde39935766626155be70a88a89f4962af30a.tar.gz
px4-firmware-f3dcde39935766626155be70a88a89f4962af30a.tar.bz2
px4-firmware-f3dcde39935766626155be70a88a89f4962af30a.zip
Merge pull request #1671 from PX4/ekf_fix
Critical coverity fixes.
-rw-r--r--src/drivers/px4fmu/fmu.cpp9
-rw-r--r--src/modules/commander/commander.cpp2
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_22states.cpp15
-rw-r--r--src/modules/uORB/uORB.cpp4
4 files changed, 18 insertions, 12 deletions
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 436672040..d3fee1626 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -1637,12 +1637,15 @@ sensor_reset(int ms)
fd = open(PX4FMU_DEVICE_PATH, O_RDWR);
- if (fd < 0)
+ if (fd < 0) {
errx(1, "open fail");
+ }
- if (ioctl(fd, GPIO_SENSOR_RAIL_RESET, ms) < 0)
- err(1, "servo arm failed");
+ if (ioctl(fd, GPIO_SENSOR_RAIL_RESET, ms) < 0) {
+ warnx("sensor rail reset failed");
+ }
+ close(fd);
}
void
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 3c71195fb..adf1b0950 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1340,7 +1340,7 @@ int commander_thread_main(int argc, char *argv[])
status.vtol_fw_permanent_stab = vtol_status.fw_permanent_stab;
/* Make sure that this is only adjusted if vehicle realy is of type vtol*/
- if (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR || VEHICLE_TYPE_VTOL_QUADROTOR) {
+ if ((status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR) || (status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR)) {
status.is_rotary_wing = vtol_status.vtol_in_rw_mode;
}
}
diff --git a/src/modules/ekf_att_pos_estimator/estimator_22states.cpp b/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
index b062097fb..6cff4b948 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
@@ -181,9 +181,12 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
correctedDelAng.x = dAngIMU.x - states[10];
correctedDelAng.y = dAngIMU.y - states[11];
correctedDelAng.z = dAngIMU.z - states[12];
- dVelIMU.x = dVelIMU.x;
- dVelIMU.y = dVelIMU.y;
- dVelIMU.z = dVelIMU.z - states[13];
+
+ Vector3f dVelIMURel;
+
+ dVelIMURel.x = dVelIMU.x;
+ dVelIMURel.y = dVelIMU.y;
+ dVelIMURel.z = dVelIMU.z - states[13];
delAngTotal.x += correctedDelAng.x;
delAngTotal.y += correctedDelAng.y;
@@ -263,9 +266,9 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
// transform body delta velocities to delta velocities in the nav frame
// * and + operators have been overloaded
//delVelNav = Tbn*dVelIMU + gravityNED*dtIMU;
- delVelNav.x = Tbn.x.x*dVelIMU.x + Tbn.x.y*dVelIMU.y + Tbn.x.z*dVelIMU.z + gravityNED.x*dtIMU;
- delVelNav.y = Tbn.y.x*dVelIMU.x + Tbn.y.y*dVelIMU.y + Tbn.y.z*dVelIMU.z + gravityNED.y*dtIMU;
- delVelNav.z = Tbn.z.x*dVelIMU.x + Tbn.z.y*dVelIMU.y + Tbn.z.z*dVelIMU.z + gravityNED.z*dtIMU;
+ delVelNav.x = Tbn.x.x*dVelIMURel.x + Tbn.x.y*dVelIMURel.y + Tbn.x.z*dVelIMURel.z + gravityNED.x*dtIMU;
+ delVelNav.y = Tbn.y.x*dVelIMURel.x + Tbn.y.y*dVelIMURel.y + Tbn.y.z*dVelIMURel.z + gravityNED.y*dtIMU;
+ delVelNav.z = Tbn.z.x*dVelIMURel.x + Tbn.z.y*dVelIMURel.y + Tbn.z.z*dVelIMURel.z + gravityNED.z*dtIMU;
// calculate the magnitude of the nav acceleration (required for GPS
// variance estimation)
diff --git a/src/modules/uORB/uORB.cpp b/src/modules/uORB/uORB.cpp
index 149b8f6d2..cc6617aea 100644
--- a/src/modules/uORB/uORB.cpp
+++ b/src/modules/uORB/uORB.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (Cc) 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
@@ -230,7 +230,7 @@ ORBDevNode::open(struct file *filp)
ret = CDev::open(filp);
if (ret != OK)
- free(sd);
+ delete sd;
return ret;
}