diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp
index cf3748d21d5e6fd7a05fc43777aefd4cf336a3a4..25066b6e49b56eb0f50cfa1ce5fb98f38c5fde03 100644
--- a/src/drivers/batt_smbus/batt_smbus.cpp
+++ b/src/drivers/batt_smbus/batt_smbus.cpp
@@ -44,6 +44,7 @@
 #include <float.h>
 #include <stdio.h>
 #include <string.h>
+#include <ecl/geo/geo.h>
 
 #include <drivers/device/i2c.h>
 #include <drivers/device/ringbuffer.h>
@@ -555,7 +556,7 @@ BATT_SMBUS::cycle()
 
 		// read battery temperature and covert to Celsius
 		if (read_reg(BATT_SMBUS_TEMP, tmp) == OK) {
-			new_report.temperature = (float)(((float)tmp / 10.0f) - 273.15f);
+			new_report.temperature = (float)(((float)tmp / 10.0f) + CONSTANTS_ABSOLUTE_NULL_CELSIUS);
 		}
 
 		//Check if remaining % is out of range
diff --git a/src/drivers/imu/adis16448/adis16448.cpp b/src/drivers/imu/adis16448/adis16448.cpp
index 7763002a5bb964e66cb2034f35696e9b9db85aa4..b8b33b018bb594f619a0342bd0c4e0a83126e1c4 100644
--- a/src/drivers/imu/adis16448/adis16448.cpp
+++ b/src/drivers/imu/adis16448/adis16448.cpp
@@ -44,7 +44,7 @@
  */
 
 #include <px4_config.h>
-
+#include <ecl/geo/geo.h>
 #include <sys/types.h>
 #include <stdint.h>
 #include <stdbool.h>
@@ -171,8 +171,6 @@
 #define ADIS16448_ACCEL_MAX_OUTPUT_RATE              1221
 #define ADIS16448_GYRO_MAX_OUTPUT_RATE               1221
 
-#define ADIS16448_ONE_G								9.80665f
-
 #define FW_FILTER									false
 
 #define SPI_BUS_SPEED								1000000
@@ -733,8 +731,8 @@ int ADIS16448::reset()
 	/* Set IMU sample rate */
 	_set_sample_rate(_sample_rate);
 
-	_accel_range_scale = ADIS16448_ONE_G * ACCELINITIALSENSITIVITY;
-	_accel_range_m_s2  = ADIS16448_ONE_G * ACCELDYNAMICRANGE;
+	_accel_range_scale = CONSTANTS_ONE_G * ACCELINITIALSENSITIVITY;
+	_accel_range_m_s2  = CONSTANTS_ONE_G * ACCELDYNAMICRANGE;
 	_mag_range_scale   = MAGINITIALSENSITIVITY;
 	_mag_range_mgauss  = MAGDYNAMICRANGE;
 
@@ -1140,7 +1138,7 @@ ADIS16448::ioctl(struct file *filp, int cmd, unsigned long arg)
 		return -EINVAL;
 
 	case ACCELIOCGRANGE:
-		return (unsigned long)((_accel_range_m_s2) / ADIS16448_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCSELFTEST:
 		return accel_self_test();
diff --git a/src/drivers/imu/bma180/bma180.cpp b/src/drivers/imu/bma180/bma180.cpp
index d33056be459bd97987519d3ad31d46a86b715d04..0b2aa75b08a111894c4706aee4b21a3ca2dcfaea 100644
--- a/src/drivers/imu/bma180/bma180.cpp
+++ b/src/drivers/imu/bma180/bma180.cpp
@@ -38,6 +38,7 @@
 
 #include <px4_config.h>
 #include <px4_defines.h>
+#include <ecl/geo/geo.h>
 
 #include <sys/types.h>
 #include <stdint.h>
@@ -575,7 +576,7 @@ BMA180::set_range(unsigned max_g)
 	}
 
 	/* set new range scaling factor */
-	_accel_range_m_s2 = _current_range * 9.80665f;
+	_accel_range_m_s2 = _current_range * CONSTANTS_ONE_G;
 	_accel_range_scale = _accel_range_m_s2 / 8192.0f;
 
 	/* enable writing to chip config */
diff --git a/src/drivers/imu/bmi055/bmi055.hpp b/src/drivers/imu/bmi055/bmi055.hpp
index 999957748ca63be781751747338364d0ee3051d9..bad674f5feebb176ea4262e6f44620453ea2768b 100644
--- a/src/drivers/imu/bmi055/bmi055.hpp
+++ b/src/drivers/imu/bmi055/bmi055.hpp
@@ -239,8 +239,6 @@
 
 #define BMI055_GYRO_DEFAULT_DRIVER_FILTER_FREQ  50
 
-#define BMI055_ONE_G                       9.80665f
-
 #define BMI055_BUS_SPEED				10*1000*1000
 
 #define BMI055_TIMER_REDUCTION				200
diff --git a/src/drivers/imu/bmi055/bmi055_accel.cpp b/src/drivers/imu/bmi055/bmi055_accel.cpp
index 40cb61fb3dde781b185e91372729b6d48ddd4928..14c4c08ffeb279cf3fb5674ab1c641c85e0827f8 100644
--- a/src/drivers/imu/bmi055/bmi055_accel.cpp
+++ b/src/drivers/imu/bmi055/bmi055_accel.cpp
@@ -1,5 +1,5 @@
 #include "bmi055.hpp"
-
+#include <ecl/geo/geo.h>
 
 /*
   list of registers that will be checked in check_registers(). Note
@@ -463,7 +463,7 @@ BMI055_accel::ioctl(struct file *filp, int cmd, unsigned long arg)
 		return set_accel_range(arg);
 
 	case ACCELIOCGRANGE:
-		return (unsigned long)((_accel_range_m_s2) / BMI055_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCSELFTEST:
 		return accel_self_test();
@@ -535,8 +535,8 @@ BMI055_accel::set_accel_range(unsigned max_g)
 		return -EINVAL;
 	}
 
-	_accel_range_scale = (BMI055_ONE_G / lsb_per_g);
-	_accel_range_m_s2 = max_accel_g * BMI055_ONE_G;
+	_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
+	_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
 
 	modify_reg(BMI055_ACC_RANGE, clearbits, setbits);
 
diff --git a/src/drivers/imu/bmi160/bmi160.cpp b/src/drivers/imu/bmi160/bmi160.cpp
index 3b97eeb7902fb47fc5614ecba652a065331df4bf..df2ed343a057ee80d80232bed8383615f89dd15f 100644
--- a/src/drivers/imu/bmi160/bmi160.cpp
+++ b/src/drivers/imu/bmi160/bmi160.cpp
@@ -1,6 +1,6 @@
 #include "bmi160.hpp"
 #include "bmi160_gyro.hpp"
-
+#include <ecl/geo/geo.h>
 
 /*
   list of registers that will be checked in check_registers(). Note
@@ -743,7 +743,7 @@ BMI160::ioctl(struct file *filp, int cmd, unsigned long arg)
 		return set_accel_range(arg);
 
 	case ACCELIOCGRANGE:
-		return (unsigned long)((_accel_range_m_s2) / BMI160_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCSELFTEST:
 		return accel_self_test();
@@ -905,8 +905,8 @@ BMI160::set_accel_range(unsigned max_g)
 		return -EINVAL;
 	}
 
-	_accel_range_scale = (BMI160_ONE_G / lsb_per_g);
-	_accel_range_m_s2 = max_accel_g * BMI160_ONE_G;
+	_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
+	_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
 
 	modify_reg(BMIREG_ACC_RANGE, clearbits, setbits);
 
diff --git a/src/drivers/imu/bmi160/bmi160.hpp b/src/drivers/imu/bmi160/bmi160.hpp
index b63529e6d6432182a8a2b90e671b216f151d091e..2f5dfa4dd5d73445b86dfb74aa9260e7cff226cd 100644
--- a/src/drivers/imu/bmi160/bmi160.hpp
+++ b/src/drivers/imu/bmi160/bmi160.hpp
@@ -238,8 +238,6 @@
 #define BMI160_GYRO_DEFAULT_ONCHIP_FILTER_FREQ	254.6f
 #define BMI160_GYRO_DEFAULT_DRIVER_FILTER_FREQ	50
 
-#define BMI160_ONE_G                       9.80665f
-
 #define BMI160_BUS_SPEED				10*1000*1000
 
 #define BMI160_TIMER_REDUCTION				200
diff --git a/src/drivers/imu/fxos8701cq/fxos8701cq.cpp b/src/drivers/imu/fxos8701cq/fxos8701cq.cpp
index 2c01bf5b17cc00de42182ab19ea51d0e379403e6..8ec72c7f39d7c377b6cee56502b5137ff36aecc5 100644
--- a/src/drivers/imu/fxos8701cq/fxos8701cq.cpp
+++ b/src/drivers/imu/fxos8701cq/fxos8701cq.cpp
@@ -39,6 +39,7 @@
 
 #include <px4_config.h>
 #include <px4_defines.h>
+#include <ecl/geo/geo.h>
 
 #include <sys/types.h>
 #include <sys/stat.h>
@@ -137,7 +138,6 @@
 
 #define FXOS8701C_MAG_DEFAULT_RANGE_GA               12 /* It is fixed at 12 G */
 #define FXOS8701C_MAG_DEFAULT_RATE                   100
-#define FXOS8701C_ONE_G                              9.80665f
 
 /*
   we set the timer interrupt to run a bit faster than the desired
@@ -877,7 +877,7 @@ FXOS8701CQ::ioctl(struct file *filp, int cmd, unsigned long arg)
 
 	case ACCELIOCGRANGE:
 		/* convert to m/s^2 and return rounded in G */
-		return (unsigned long)((_accel_range_m_s2) / FXOS8701C_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCGSCALE:
 		/* copy scale out */
@@ -1135,8 +1135,8 @@ FXOS8701CQ::accel_set_range(unsigned max_g)
 		max_accel_g = 2;
 	}
 
-	_accel_range_scale = (FXOS8701C_ONE_G / lsb_per_g);
-	_accel_range_m_s2 = max_accel_g * FXOS8701C_ONE_G;
+	_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
+	_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
 
 
 	modify_reg(FXOS8701CQ_XYZ_DATA_CFG, XYZ_DATA_CFG_FS_MASK, setbits);
diff --git a/src/drivers/imu/lsm303d/lsm303d.cpp b/src/drivers/imu/lsm303d/lsm303d.cpp
index 90c3c2aa3b10e2aa8ce7271347d8ba3553ce0374..adfdb40e9aefdaf01e85edb23a347a73999c3411 100644
--- a/src/drivers/imu/lsm303d/lsm303d.cpp
+++ b/src/drivers/imu/lsm303d/lsm303d.cpp
@@ -38,6 +38,7 @@
 
 #include <px4_config.h>
 #include <px4_defines.h>
+#include <ecl/geo/geo.h>
 
 #include <sys/types.h>
 #include <sys/stat.h>
@@ -206,8 +207,6 @@
 #define LSM303D_MAG_DEFAULT_RANGE_GA			2
 #define LSM303D_MAG_DEFAULT_RATE			100
 
-#define LSM303D_ONE_G					9.80665f
-
 /*
   we set the timer interrupt to run a bit faster than the desired
   sample rate and then throw away duplicates using the data ready bit.
@@ -946,7 +945,7 @@ LSM303D::ioctl(struct file *filp, int cmd, unsigned long arg)
 
 	case ACCELIOCGRANGE:
 		/* convert to m/s^2 and return rounded in G */
-		return (unsigned long)((_accel_range_m_s2) / LSM303D_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCGSCALE:
 		/* copy scale out */
@@ -1178,27 +1177,27 @@ LSM303D::accel_set_range(unsigned max_g)
 	}
 
 	if (max_g <= 2) {
-		_accel_range_m_s2 = 2.0f * LSM303D_ONE_G;
+		_accel_range_m_s2 = 2.0f * CONSTANTS_ONE_G;
 		setbits |= REG2_FULL_SCALE_2G_A;
 		new_scale_g_digit = 0.061e-3f;
 
 	} else if (max_g <= 4) {
-		_accel_range_m_s2 = 4.0f * LSM303D_ONE_G;
+		_accel_range_m_s2 = 4.0f * CONSTANTS_ONE_G;
 		setbits |= REG2_FULL_SCALE_4G_A;
 		new_scale_g_digit = 0.122e-3f;
 
 	} else if (max_g <= 6) {
-		_accel_range_m_s2 = 6.0f * LSM303D_ONE_G;
+		_accel_range_m_s2 = 6.0f * CONSTANTS_ONE_G;
 		setbits |= REG2_FULL_SCALE_6G_A;
 		new_scale_g_digit = 0.183e-3f;
 
 	} else if (max_g <= 8) {
-		_accel_range_m_s2 = 8.0f * LSM303D_ONE_G;
+		_accel_range_m_s2 = 8.0f * CONSTANTS_ONE_G;
 		setbits |= REG2_FULL_SCALE_8G_A;
 		new_scale_g_digit = 0.244e-3f;
 
 	} else if (max_g <= 16) {
-		_accel_range_m_s2 = 16.0f * LSM303D_ONE_G;
+		_accel_range_m_s2 = 16.0f * CONSTANTS_ONE_G;
 		setbits |= REG2_FULL_SCALE_16G_A;
 		new_scale_g_digit = 0.732e-3f;
 
@@ -1206,7 +1205,7 @@ LSM303D::accel_set_range(unsigned max_g)
 		return -EINVAL;
 	}
 
-	_accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
+	_accel_range_scale = new_scale_g_digit * CONSTANTS_ONE_G;
 
 
 	modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
diff --git a/src/drivers/imu/mpu6000/mpu6000.cpp b/src/drivers/imu/mpu6000/mpu6000.cpp
index df0d5a9a467f61b3a0e255a5f3e0663590ef84ae..eba3c372ea5881bef02d03145f07075ce8f1d2e6 100644
--- a/src/drivers/imu/mpu6000/mpu6000.cpp
+++ b/src/drivers/imu/mpu6000/mpu6000.cpp
@@ -56,6 +56,7 @@
  */
 
 #include <px4_config.h>
+#include <ecl/geo/geo.h>
 
 #include <sys/types.h>
 #include <stdint.h>
@@ -1505,7 +1506,7 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
 		return set_accel_range(arg);
 
 	case ACCELIOCGRANGE:
-		return (unsigned long)((_accel_range_m_s2) / MPU6000_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCSELFTEST:
 		return accel_self_test();
@@ -1645,8 +1646,8 @@ MPU6000::set_accel_range(unsigned max_g_in)
 		case MPU6000_REV_C4:
 		case MPU6000_REV_C5:
 			write_checked_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
-			_accel_range_scale = (MPU6000_ONE_G / 4096.0f);
-			_accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
+			_accel_range_scale = (CONSTANTS_ONE_G / 4096.0f);
+			_accel_range_m_s2 = 8.0f * CONSTANTS_ONE_G;
 			return OK;
 		}
 	}
@@ -1677,8 +1678,8 @@ MPU6000::set_accel_range(unsigned max_g_in)
 	}
 
 	write_checked_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
-	_accel_range_scale = (MPU6000_ONE_G / lsb_per_g);
-	_accel_range_m_s2 = max_accel_g * MPU6000_ONE_G;
+	_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
+	_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
 
 	return OK;
 }
diff --git a/src/drivers/imu/mpu6000/mpu6000.h b/src/drivers/imu/mpu6000/mpu6000.h
index 11c13009b7879210728f5e69b619a17d86517e3d..6af00b27f71d460ccc3e717c19a768a47da4d562 100644
--- a/src/drivers/imu/mpu6000/mpu6000.h
+++ b/src/drivers/imu/mpu6000/mpu6000.h
@@ -212,8 +212,6 @@
 
 #define MPU6000_DEFAULT_ONCHIP_FILTER_FREQ			42
 
-#define MPU6000_ONE_G					9.80665f
-
 #ifdef PX4_SPI_BUS_EXT
 #define EXTERNAL_BUS PX4_SPI_BUS_EXT
 #else
diff --git a/src/drivers/imu/mpu9250/mpu9250.cpp b/src/drivers/imu/mpu9250/mpu9250.cpp
index 97bb7ddf111daf47d0305da7ba95ccd0b40fd9e9..af5bc1e7130991998420a64a96d69f2146ce0417 100644
--- a/src/drivers/imu/mpu9250/mpu9250.cpp
+++ b/src/drivers/imu/mpu9250/mpu9250.cpp
@@ -42,6 +42,7 @@
  */
 
 #include <px4_config.h>
+#include <ecl/geo/geo.h>
 
 #include <sys/types.h>
 #include <stdint.h>
@@ -918,7 +919,7 @@ MPU9250::ioctl(struct file *filp, int cmd, unsigned long arg)
 		return set_accel_range(arg);
 
 	case ACCELIOCGRANGE:
-		return (unsigned long)((_accel_range_m_s2) / MPU9250_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCSELFTEST:
 		return accel_self_test();
@@ -1086,8 +1087,8 @@ MPU9250::set_accel_range(unsigned max_g_in)
 	}
 
 	write_checked_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
-	_accel_range_scale = (MPU9250_ONE_G / lsb_per_g);
-	_accel_range_m_s2 = max_accel_g * MPU9250_ONE_G;
+	_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
+	_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
 
 	return OK;
 }
diff --git a/src/drivers/imu/mpu9250/mpu9250.h b/src/drivers/imu/mpu9250/mpu9250.h
index 7ee1cc3976fe28b19f33d6aa9420645ba2f39dbd..cd546c4f4d725d67ab478a2c9ff294a79c834a26 100644
--- a/src/drivers/imu/mpu9250/mpu9250.h
+++ b/src/drivers/imu/mpu9250/mpu9250.h
@@ -190,8 +190,6 @@
 
 #define MPU9250_DEFAULT_ONCHIP_FILTER_FREQ	41
 
-#define MPU9250_ONE_G					9.80665f
-
 #define MPUIOCGIS_I2C	(unsigned)(DEVIOCGDEVICEID+100)
 
 
diff --git a/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt b/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt
index 6f2293ffc925a6f8f35d265c9d0b0d4a838719ce..b6a303f4eecb19e5ee7cb9e75a15460d9a8967a6 100644
--- a/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt
+++ b/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt
@@ -36,9 +36,9 @@ px4_add_module(
 	STACK_MAIN 1200
 	COMPILE_FLAGS
 	SRCS
-		frsky_data.c
-		sPort_data.c
-		frsky_telemetry.c
+		frsky_data.cpp
+		sPort_data.cpp
+		frsky_telemetry.cpp
 	DEPENDS
 		platforms__common
 	)
diff --git a/src/drivers/telemetry/frsky_telemetry/frsky_data.c b/src/drivers/telemetry/frsky_telemetry/frsky_data.cpp
similarity index 99%
rename from src/drivers/telemetry/frsky_telemetry/frsky_data.c
rename to src/drivers/telemetry/frsky_telemetry/frsky_data.cpp
index 63116c43b7f63e597b7be73adf773252e1c33168..85ab413b41430ffb30e1269917b0027746aed302 100644
--- a/src/drivers/telemetry/frsky_telemetry/frsky_data.c
+++ b/src/drivers/telemetry/frsky_telemetry/frsky_data.cpp
@@ -47,9 +47,9 @@
 #include <stdio.h>
 #include <string.h>
 #include <stdbool.h>
-#include <arch/math.h>
 #include <lib/ecl/geo/geo.h>
 #include <stdbool.h>
+#include <math.h>
 
 #include <uORB/topics/battery_status.h>
 #include <uORB/topics/sensor_combined.h>
diff --git a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.c b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp
similarity index 99%
rename from src/drivers/telemetry/frsky_telemetry/frsky_telemetry.c
rename to src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp
index 41d5022aa0f161065729f822965021f5e08e6ef5..34c5dd9bb3b02d12e148d4cd996a5ff39dc24bb4 100644
--- a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp
@@ -79,8 +79,8 @@ static int sPort_open_uart(const char *uart_name, struct termios *uart_config, s
 static int set_uart_speed(int uart, struct termios *uart_config, speed_t speed);
 static void usage(void);
 static int frsky_telemetry_thread_main(int argc, char *argv[]);
-__EXPORT int frsky_telemetry_main(int argc, char *argv[]);
 
+extern "C" __EXPORT int frsky_telemetry_main(int argc, char *argv[]);
 
 uint16_t get_telemetry_flight_mode(int px4_flight_mode)
 {
diff --git a/src/drivers/telemetry/frsky_telemetry/sPort_data.c b/src/drivers/telemetry/frsky_telemetry/sPort_data.cpp
similarity index 99%
rename from src/drivers/telemetry/frsky_telemetry/sPort_data.c
rename to src/drivers/telemetry/frsky_telemetry/sPort_data.cpp
index b2910d92061e81ca2289ca2ad20d5f4789f82e7a..ae5e5f0c40ffc3c4a95151788f663e6fc6e325f2 100644
--- a/src/drivers/telemetry/frsky_telemetry/sPort_data.c
+++ b/src/drivers/telemetry/frsky_telemetry/sPort_data.cpp
@@ -47,7 +47,8 @@
 #include <stdlib.h>
 #include <stdio.h>
 #include <string.h>
-#include <arch/math.h>
+#include <math.h>
+
 #include <lib/ecl/geo/geo.h>
 
 #include <uORB/topics/battery_status.h>
diff --git a/src/lib/ecl b/src/lib/ecl
index 02e319431b948f660f8548707849489d6c822fad..8678cc42ba6c87b3ae0724af2becb62b71bf6683 160000
--- a/src/lib/ecl
+++ b/src/lib/ecl
@@ -1 +1 @@
-Subproject commit 02e319431b948f660f8548707849489d6c822fad
+Subproject commit 8678cc42ba6c87b3ae0724af2becb62b71bf6683
diff --git a/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp b/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp
index 45796ac151890ebeb4419d5bac9edd4404b54afe..9f167f5a91b5a0f4c625c56c45b3c0b63c927fee 100644
--- a/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp
+++ b/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp
@@ -1918,7 +1918,7 @@ FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float airspee
 		if (orb_copy(ORB_ID(sensor_baro), _sensor_baro_sub, &baro) == PX4_OK) {
 			if (PX4_ISFINITE(baro.pressure) && PX4_ISFINITE(_parameters.throttle_alt_scale)) {
 				// scale throttle as a function of sqrt(p0/p) (~ EAS -> TAS at low speeds and altitudes ignoring temperature)
-				const float eas2tas = sqrtf(MSL_PRESSURE_MILLIBAR / baro.pressure);
+				const float eas2tas = sqrtf(CONSTANTS_STD_PRESSURE_MBAR / baro.pressure);
 				const float scale = constrain((eas2tas - 1.0f) * _parameters.throttle_alt_scale + 1.0f, 1.0f, 2.0f);
 
 				throttle_max = constrain(throttle_max * scale, throttle_min, 1.0f);
diff --git a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp
index f53e9c29298104eb2b2f55ad4c1960f434d27b6e..1706e1b8252f919615c66937998c9ecd8ba18203 100644
--- a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp
+++ b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp
@@ -103,8 +103,6 @@ static constexpr float MANUAL_THROTTLE_CLIMBOUT_THRESH =
 	0.85f; ///< a throttle / pitch input above this value leads to the system switching to climbout mode
 static constexpr float ALTHOLD_EPV_RESET_THRESH = 5.0f;
 
-static constexpr float MSL_PRESSURE_MILLIBAR = 1013.25f; ///< standard atmospheric pressure in millibar
-
 using math::constrain;
 using math::max;
 using math::min;
diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp
index fc8bd1ea86ae012a7c11305c0aa851afdde157a7..e306ec36ae94aa32fd9547c27044981a5040c3a0 100644
--- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp
+++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp
@@ -775,7 +775,7 @@ void BlockLocalPositionEstimator::predict()
 	Vector3f a(_sub_sensor.get().accelerometer_m_s2);
 	// note, bias is removed in dynamics function
 	_u = _R_att * a;
-	_u(U_az) += 9.81f;	// add g
+	_u(U_az) += CONSTANTS_ONE_G;	// add g
 
 	// update state space based on new states
 	updateSSStates();
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index e4db48f069951e44bad4e27d803bce252880cd4c..a4a10b585daf2562ff9610fa797fc9c00376718b 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -90,8 +90,6 @@
 #include "mavlink_main.h"
 #include "mavlink_command_sender.h"
 
-static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
-
 MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
 	_mavlink(parent),
 	_mission_manager(nullptr),
@@ -1922,9 +1920,9 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
 		struct accel_report accel = {};
 
 		accel.timestamp = timestamp;
-		accel.x_raw = imu.xacc / mg2ms2;
-		accel.y_raw = imu.yacc / mg2ms2;
-		accel.z_raw = imu.zacc / mg2ms2;
+		accel.x_raw = imu.xacc / (CONSTANTS_ONE_G / 1000.0f);
+		accel.y_raw = imu.yacc / (CONSTANTS_ONE_G / 1000.0f);
+		accel.z_raw = imu.zacc / (CONSTANTS_ONE_G / 1000.0f);
 		accel.x = imu.xacc;
 		accel.y = imu.yacc;
 		accel.z = imu.zacc;
diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp
index 30b2f84ba7d1099b68c9db3284ad5b6c0d909e49..4bbb291251abaf8fae8f62321badb06a310bd8f4 100644
--- a/src/modules/simulator/simulator_mavlink.cpp
+++ b/src/modules/simulator/simulator_mavlink.cpp
@@ -52,11 +52,6 @@ extern "C" __EXPORT hrt_abstime hrt_reset(void);
 #define SEND_INTERVAL 	20
 #define UDP_PORT 	14560
 
-#define PRESS_GROUND 101325.0f
-#define DENSITY 1.2041f
-
-static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
-
 #ifdef ENABLE_UART_RC_INPUT
 #ifndef B460800
 #define B460800 460800
@@ -632,12 +627,12 @@ void Simulator::initializeSensorData()
 {
 	// write sensor data to memory so that drivers can copy data from there
 	RawMPUData mpu = {};
-	mpu.accel_z = 9.81f;
+	mpu.accel_z = CONSTANTS_ONE_G;
 
 	write_MPU_data(&mpu);
 
 	RawAccelData accel = {};
-	accel.z = 9.81f;
+	accel.z = CONSTANTS_ONE_G;
 
 	write_accel_data(&accel);
 
@@ -1036,9 +1031,9 @@ int Simulator::publish_sensor_topics(mavlink_hil_sensor_t *imu)
 		struct accel_report accel = {};
 
 		accel.timestamp = timestamp;
-		accel.x_raw = imu->xacc / mg2ms2;
-		accel.y_raw = imu->yacc / mg2ms2;
-		accel.z_raw = imu->zacc / mg2ms2;
+		accel.x_raw = imu->xacc / (CONSTANTS_ONE_G / 1000.0f);
+		accel.y_raw = imu->yacc / (CONSTANTS_ONE_G / 1000.0f);
+		accel.z_raw = imu->zacc / (CONSTANTS_ONE_G / 1000.0f);
 		accel.x = imu->xacc;
 		accel.y = imu->yacc;
 		accel.z = imu->zacc;
diff --git a/src/modules/systemlib/CMakeLists.txt b/src/modules/systemlib/CMakeLists.txt
index 5a77779734cd1a5d609d39a7dd6bc86ad911b059..1f67c29aad9e81fe7323966a3dc2d3d95d86d04c 100644
--- a/src/modules/systemlib/CMakeLists.txt
+++ b/src/modules/systemlib/CMakeLists.txt
@@ -32,7 +32,7 @@
 ############################################################################
 
 set(SRCS
-	airspeed.c
+	airspeed.cpp
 	battery.cpp
 	board_serial.c
 	bson/tinybson.c
diff --git a/src/modules/systemlib/airspeed.c b/src/modules/systemlib/airspeed.cpp
similarity index 99%
rename from src/modules/systemlib/airspeed.c
rename to src/modules/systemlib/airspeed.cpp
index 23b36a299bf1c24067f524dc4d99a38ceca878f4..fbf06df6e7e385eaf081e6f49cd299738617a14e 100644
--- a/src/modules/systemlib/airspeed.c
+++ b/src/modules/systemlib/airspeed.cpp
@@ -236,7 +236,7 @@ float calc_true_airspeed(float total_pressure, float static_pressure, float temp
 {
 	float density = get_air_density(static_pressure, temperature_celsius);
 
-	if (density < 0.0001f || !isfinite(density)) {
+	if (density < 0.0001f || !PX4_ISFINITE(density)) {
 		density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C;
 	}
 
diff --git a/src/platforms/posix/drivers/accelsim/accelsim.cpp b/src/platforms/posix/drivers/accelsim/accelsim.cpp
index ca8deaa85f2a45900589d6833940823b10a176a0..c852dc54176cc1ac9c480a241745b9d0e22461d2 100644
--- a/src/platforms/posix/drivers/accelsim/accelsim.cpp
+++ b/src/platforms/posix/drivers/accelsim/accelsim.cpp
@@ -71,7 +71,6 @@
 
 #define ACCELSIM_ACCEL_DEFAULT_RATE			250
 #define ACCELSIM_ACCEL_DEFAULT_DRIVER_FILTER_FREQ	30
-#define ACCELSIM_ONE_G					9.80665f
 
 #define DIR_READ				(1<<7)
 #define DIR_WRITE				(0<<7)
@@ -595,7 +594,7 @@ ACCELSIM::devIOCTL(unsigned long cmd, unsigned long arg)
 
 	case ACCELIOCGRANGE:
 		/* convert to m/s^2 and return rounded in G */
-		return (unsigned long)((_accel_range_m_s2) / ACCELSIM_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCGSCALE:
 		/* copy scale out */
@@ -732,7 +731,7 @@ ACCELSIM::accel_set_range(unsigned max_g)
 {
 	float new_scale_g_digit = 0.732e-3f;
 
-	_accel_range_scale = new_scale_g_digit * ACCELSIM_ONE_G;
+	_accel_range_scale = new_scale_g_digit * CONSTANTS_ONE_G;
 
 	return OK;
 }
diff --git a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp
index 3722b1532d1a6868e285bc3118b65309ce77811a..82dec6f9610fe2468d01580219317830359966fb 100644
--- a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp
+++ b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp
@@ -103,8 +103,6 @@ using namespace DriverFramework;
 
 #define GYROSIM_GYRO_DEFAULT_RATE	400
 
-#define GYROSIM_ONE_G			9.80665f
-
 #ifdef PX4_SPI_BUS_EXT
 #define EXTERNAL_BUS PX4_SPI_BUS_EXT
 #else
@@ -819,7 +817,7 @@ GYROSIM::devIOCTL(unsigned long cmd, unsigned long arg)
 		return set_accel_range(arg);
 
 	case ACCELIOCGRANGE:
-		return (unsigned long)((_accel_range_m_s2) / GYROSIM_ONE_G + 0.5f);
+		return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
 
 	case ACCELIOCSELFTEST:
 		return accel_self_test();
@@ -920,8 +918,8 @@ GYROSIM::set_accel_range(unsigned max_g_in)
 	switch (_product) {
 	case GYROSIMES_REV_C4:
 		write_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
-		_accel_range_scale = (GYROSIM_ONE_G / 4096.0f);
-		_accel_range_m_s2 = 8.0f * GYROSIM_ONE_G;
+		_accel_range_scale = (CONSTANTS_ONE_G / 4096.0f);
+		_accel_range_m_s2 = 8.0f * CONSTANTS_ONE_G;
 		return OK;
 	}
 
@@ -951,8 +949,8 @@ GYROSIM::set_accel_range(unsigned max_g_in)
 	}
 
 	write_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
-	_accel_range_scale = (GYROSIM_ONE_G / lsb_per_g);
-	_accel_range_m_s2 = max_accel_g * GYROSIM_ONE_G;
+	_accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g);
+	_accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G;
 
 	return OK;
 }
@@ -1334,7 +1332,7 @@ test()
 	PX4_INFO("acc  y:  \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
 	PX4_INFO("acc  z:  \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
 	PX4_INFO("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
-		 (double)(a_report.range_m_s2 / GYROSIM_ONE_G));
+		 (double)(a_report.range_m_s2 / CONSTANTS_ONE_G));
 
 	/* do a simple demand read */
 	sz = h_gyro.read(&g_report, sizeof(g_report));