RPi: just use RPI instead of RPI2.

The reason for this change is that RPi2 and RPi3 are compatible, and
hopefully all differences coming up can be resolved without ifdefs but
at runtime.
This commit is contained in:
Julian Oes 2016-07-14 17:34:41 +02:00
parent 2bf40efe8b
commit fa614a3cc1
14 changed files with 31 additions and 58 deletions

View File

@ -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:

View File

@ -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
)

View File

@ -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)

View File

@ -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)

View File

@ -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")

View File

@ -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

View File

@ -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)

@ -1 +1 @@
Subproject commit dab303d7992c9a3bbc39509b13eddf2b65d382b8
Subproject commit 458b726027ec9d67099e744dd8e0af7208ea64a5

View File

@ -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"

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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

View File

@ -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.