diff --git a/Makefile b/Makefile
index 4d7529b61c00eb4d7d67decaa4cd07343eec8c23..5435ef7c70cd602312bcc7c8b0fb9d2bbec649b3 100644
--- a/Makefile
+++ b/Makefile
@@ -212,10 +212,10 @@ posix_excelsior_default:
 
 excelsior_default: posix_excelsior_default qurt_excelsior_default
 
-posix_rpi2_native:
+posix_rpi_native:
 	$(call cmake-build,$@)
 
-posix_rpi2_cross:
+posix_rpi_cross:
 	$(call cmake-build,$@)
 
 posix_bebop_default:
diff --git a/cmake/configs/posix_rpi2_common.cmake b/cmake/configs/posix_rpi_common.cmake
similarity index 94%
rename from cmake/configs/posix_rpi2_common.cmake
rename to cmake/configs/posix_rpi_common.cmake
index b6437879a80838f3066f2dbcedf1ea74b09b75d0..a22565640b883d40b472552752e3337506dc1dd4 100644
--- a/cmake/configs/posix_rpi2_common.cmake
+++ b/cmake/configs/posix_rpi_common.cmake
@@ -1,12 +1,12 @@
-# This file is shared between posix_rpi2_native.cmake
-# and posix_rpi2_cross.cmake.
+# This file is shared between posix_rpi_native.cmake
+# and posix_rpi_cross.cmake.
 
 include(posix/px4_impl_posix)
 
 # This definition allows to differentiate if this just the usual POSIX build
 # or if it is for the RPi.
 add_definitions(
-	-D__PX4_POSIX_RPI2
+	-D__PX4_POSIX_RPI
 	-D__LINUX
 )
 
diff --git a/cmake/configs/posix_rpi2_cross.cmake b/cmake/configs/posix_rpi_cross.cmake
similarity index 86%
rename from cmake/configs/posix_rpi2_cross.cmake
rename to cmake/configs/posix_rpi_cross.cmake
index d17ef5cec3dbee8bda5017369707284346ac6a08..46243fc361e83a3fcf78f7120c53dcf4f88c2fc7 100644
--- a/cmake/configs/posix_rpi2_cross.cmake
+++ b/cmake/configs/posix_rpi_cross.cmake
@@ -1,4 +1,4 @@
-include(configs/posix_rpi2_common)
+include(configs/posix_rpi_common)
 
 set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake)
 
diff --git a/cmake/configs/posix_rpi2_native.cmake b/cmake/configs/posix_rpi_native.cmake
similarity index 71%
rename from cmake/configs/posix_rpi2_native.cmake
rename to cmake/configs/posix_rpi_native.cmake
index 9b0f45c718a7903488b91ce74d682723902b471f..e58f37028227b2855640e368e2a79467705f58f7 100644
--- a/cmake/configs/posix_rpi2_native.cmake
+++ b/cmake/configs/posix_rpi_native.cmake
@@ -1,3 +1,3 @@
-include(configs/posix_rpi2_common)
+include(configs/posix_rpi_common)
 
 set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
diff --git a/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake b/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake
index 0a9d2b4f3bd07c14d17ead6b34e60ad59cb83e63..4806222740dd54c9830f866443a867b422c3eb9e 100644
--- a/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake
+++ b/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake
@@ -71,7 +71,7 @@ foreach(tool echo grep rm mkdir nm cp touch make unzip)
 endforeach()
 
 add_definitions(
-	-D __RPI2
+	-D __RPI
 	)
 
 set(LINKER_FLAGS "-Wl,-gc-sections")
diff --git a/posix-configs/rpi2/mainapp.config b/posix-configs/rpi2/mainapp.config
deleted file mode 100644
index 003fb52c44cf7fbe7ee2786230b197597c48539a..0000000000000000000000000000000000000000
--- a/posix-configs/rpi2/mainapp.config
+++ /dev/null
@@ -1,27 +0,0 @@
-uorb start
-param set SYS_AUTOSTART 4001
-param set MAV_BROADCAST 1
-sleep 1
-param set MAV_TYPE 2
-df_lsm9ds1_wrapper start -R 4
-#df_mpu9250_wrapper start -R 10
-#df_hmc5883_wrapper start
-df_ms5611_wrapper start
-gps start -d /dev/pts/0
-sensors start
-commander start
-attitude_estimator_q start
-position_estimator_inav start
-land_detector start multicopter
-mc_pos_control start
-mc_att_control start
-mavlink start -u 14556 -r 1000000
-sleep 1
-mavlink stream -u 14556 -s HIGHRES_IMU -r 50
-mavlink stream -u 14556 -s ATTITUDE -r 50
-mavlink start -d /dev/ttyUSB0
-mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
-mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
-navio_sysfs_rc_in start
-navio_sysfs_pwm_out start
-mavlink boot_complete
\ No newline at end of file
diff --git a/src/firmware/posix/CMakeLists.txt b/src/firmware/posix/CMakeLists.txt
index 74d4025a7a2043f5c8420879cc60ccba6a3c2e94..ff348c9b45a57c47c26939aba625bbe98300378a 100644
--- a/src/firmware/posix/CMakeLists.txt
+++ b/src/firmware/posix/CMakeLists.txt
@@ -37,7 +37,7 @@ if ("${BOARD}" STREQUAL "eagle" OR ("${BOARD}" STREQUAL "excelsior"))
 			 DEPENDS mainapp
 			 DEST /home/linaro)
 
-elseif ("${BOARD}" STREQUAL "rpi2")
+elseif ("${BOARD}" STREQUAL "rpi")
 
 	add_executable(mainapp
 		${CMAKE_SOURCE_DIR}/src/platforms/posix/main.cpp
@@ -57,7 +57,7 @@ elseif ("${BOARD}" STREQUAL "rpi2")
 			 OS ${OS}
 			 BOARD ${BOARD}
 			 FILES ${CMAKE_CURRENT_BINARY_DIR}/mainapp
-				 ${CMAKE_SOURCE_DIR}/posix-configs/rpi2/mainapp.config
+				 ${CMAKE_SOURCE_DIR}/posix-configs/rpi/mainapp.config
 			 DEPENDS mainapp
 			 DEST /home/pi)
 
diff --git a/src/lib/DriverFramework b/src/lib/DriverFramework
index dab303d7992c9a3bbc39509b13eddf2b65d382b8..458b726027ec9d67099e744dd8e0af7208ea64a5 160000
--- a/src/lib/DriverFramework
+++ b/src/lib/DriverFramework
@@ -1 +1 @@
-Subproject commit dab303d7992c9a3bbc39509b13eddf2b65d382b8
+Subproject commit 458b726027ec9d67099e744dd8e0af7208ea64a5
diff --git a/src/lib/version/version.h b/src/lib/version/version.h
index a78be4fda78a9433ae0461460b720d1572e9cf69..b524cb287874a1f68060e7e845bdcbf06cf277c3 100644
--- a/src/lib/version/version.h
+++ b/src/lib/version/version.h
@@ -59,7 +59,7 @@ __END_DECLS
 #  define	HW_ARCH "EAGLE"
 #elif defined(CONFIG_ARCH_BOARD_EXCELSIOR)
 #  define HW_ARCH "EXCELSIOR"
-#elif defined(CONFIG_ARCH_BOARD_RPI2) || defined(CONFIG_ARCH_BOARD_NAVIO2)
+#elif defined(CONFIG_ARCH_BOARD_RPI) || defined(CONFIG_ARCH_BOARD_NAVIO2)
 #  define	HW_ARCH "RPI"
 #elif defined(CONFIG_ARCH_BOARD_BEBOP)
 #  define	HW_ARCH "BEBOP"
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index bdb18eaab9a9dc8688d43035ef2eae7396d00c8d..7b3cae8d3f273ab03ab7c92811fc0b05297c084e 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -175,7 +175,7 @@ typedef struct  {
 
 int do_accel_calibration(orb_advert_t *mavlink_log_pub)
 {
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
 	int fd;
 #endif
 
@@ -195,7 +195,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
 
 	/* reset all sensors */
 	for (unsigned s = 0; s < max_accel_sens; s++) {
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
 		sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s);
 		/* reset all offsets to zero and all scales to one */
 		fd = px4_open(str, 0);
@@ -329,7 +329,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
 			return ERROR;
 		}
 
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
 		sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, i);
 		fd = px4_open(str, 0);
 
@@ -419,7 +419,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub
 			break;
 		}
 
-#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI2)
+#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI)
 		// For QURT respectively the driver framework, we need to get the device ID by copying one report.
 		struct accel_report	accel_report;
 		orb_copy(ORB_ID(sensor_accel), worker_data.subs[i], &accel_report);
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 9a48866ab561ed24051d6a10d52c3ec9297ddf04..945935e38d19ec656149473a76b4b284146be0c1 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -185,7 +185,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
 
 		// Reset all offsets to 0 and scales to 1
 		(void)memcpy(&worker_data.gyro_scale[s], &gyro_scale_zero, sizeof(gyro_scale_zero));
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
 		sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, s);
 		int fd = px4_open(str, 0);
 		if (fd >= 0) {
@@ -238,7 +238,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
 	for (unsigned s = 0; s < gyro_count; s++) {
 
 		worker_data.gyro_sensor_sub[s] = orb_subscribe_multi(ORB_ID(sensor_gyro), s);
-#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI2)
+#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI)
 		// For QURT respectively the driver framework, we need to get the device ID by copying one report.
 		struct gyro_report gyro_report;
 		orb_copy(ORB_ID(sensor_gyro), worker_data.gyro_sensor_sub[s], &gyro_report);
@@ -336,7 +336,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
 				(void)sprintf(str, "CAL_GYRO%u_ID", s);
 				failed |= (OK != param_set_no_notification(param_find(str), &(worker_data.device_id[s])));
 
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
 				/* apply new scaling and offsets */
 				(void)sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, s);
 				int fd = px4_open(str, 0);
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 4d02260b401f9bf7d6032a37a1ecf5966af1c2eb..10f1c5510d3d985c3f76dd4ee92f2fd31409bbbc 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -124,7 +124,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub)
 	_last_mag_progress = 0;
 
 	for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) {
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 		// Reset mag id to mag not available
 		(void)sprintf(str, "CAL_MAG%u_ID", cur_mag);
 		result = param_set_no_notification(param_find(str), &(device_ids[cur_mag]));
@@ -166,7 +166,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub)
 #endif
 
 /* for calibration, commander will run on apps, so orb messages are used to get info from dsp */
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 		// Attempt to open mag
 		(void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag);
 		int fd = px4_open(str, O_RDONLY);
@@ -508,7 +508,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
 			// Mag in this slot is available
 			worker_data.sub_mag[cur_mag] = orb_subscribe_multi(ORB_ID(sensor_mag), cur_mag);
 
-#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI2)
+#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI)
 			// For QURT respectively the driver framework, we need to get the device ID by copying one report.
 			struct mag_report	mag_report;
 			orb_copy(ORB_ID(sensor_mag), worker_data.sub_mag[cur_mag], &mag_report);
@@ -664,7 +664,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
 		for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) {
 			if (device_ids[cur_mag] != 0) {
 				struct mag_calibration_s mscale;
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 				int fd_mag = -1;
 
 				// Set new scale
@@ -688,7 +688,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
 					mscale.y_offset = sphere_y[cur_mag];
 					mscale.z_offset = sphere_z[cur_mag];
 
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 					if (px4_ioctl(fd_mag, MAGIOCSSCALE, (long unsigned int)&mscale) != OK) {
 						calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG, cur_mag);
 						result = calibrate_return_error;
@@ -696,7 +696,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
 #endif
 				}
 
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 				// Mag device no longer needed
 				if (fd_mag >= 0) {
 					px4_close(fd_mag);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 1d69e03cfd3f85b56dfc50624d6731ee497c7733..b9dc1ca382a3ad6644fc56919bfdfaef393f3a8d 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1017,7 +1017,7 @@ Sensors::parameters_update()
 	DevHandle h_baro;
 	DevMgr::getHandle(BARO0_DEVICE_PATH, h_baro);
 
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 
 	// TODO: this needs fixing for QURT and Raspberry Pi
 	if (!h_baro.isValid()) {
@@ -1671,7 +1671,7 @@ Sensors::parameter_update_poll(bool forced)
 bool
 Sensors::apply_gyro_calibration(DevHandle &h, const struct gyro_calibration_s *gcal, const int device_id)
 {
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 
 	/* On most systems, we can just use the IOCTL call to set the calibration params. */
 	return !h.ioctl(GYROIOCSSCALE, (long unsigned int)gcal);
@@ -1685,7 +1685,7 @@ Sensors::apply_gyro_calibration(DevHandle &h, const struct gyro_calibration_s *g
 bool
 Sensors::apply_accel_calibration(DevHandle &h, const struct accel_calibration_s *acal, const int device_id)
 {
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 
 	/* On most systems, we can just use the IOCTL call to set the calibration params. */
 	return !h.ioctl(ACCELIOCSSCALE, (long unsigned int)acal);
@@ -1699,7 +1699,7 @@ Sensors::apply_accel_calibration(DevHandle &h, const struct accel_calibration_s
 bool
 Sensors::apply_mag_calibration(DevHandle &h, const struct mag_calibration_s *mcal, const int device_id)
 {
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 
 	/* On most systems, we can just use the IOCTL call to set the calibration params. */
 	return !h.ioctl(MAGIOCSSCALE, (long unsigned int)mcal);
@@ -2253,7 +2253,7 @@ Sensors::task_main()
 	/* This calls a sensors_init which can have different implementations on NuttX, POSIX, QURT. */
 	ret = sensors_init();
 
-#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI2)
+#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
 	// TODO: move adc_init into the sensors_init call.
 	ret = ret || adc_init();
 #endif
diff --git a/src/modules/sensors/sensors_init.cpp b/src/modules/sensors/sensors_init.cpp
index 93742333bda0277ff6c1c623393a130f3ce2ca20..561ee06e2765836b93a61a90ab36db2ff2b2b767 100644
--- a/src/modules/sensors/sensors_init.cpp
+++ b/src/modules/sensors/sensors_init.cpp
@@ -52,7 +52,7 @@
 
 using namespace DriverFramework;
 
-#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI2)
+#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI)
 
 // Sensor initialization is performed automatically when the QuRT sensor drivers
 // are loaded.