diff --git a/Makefile b/Makefile index e9ab6f06e1657e2e61af1874b8438e7d54b13a78..6f9fb0f7066955b0be550a234f7672e3c6dd0e12 100644 --- a/Makefile +++ b/Makefile @@ -170,6 +170,9 @@ qurt_eagle_default: posix_eagle_default: $(call cmake-build,$@) + +posix_rpi2_default: + $(call cmake-build,$@) posix: posix_sitl_default diff --git a/cmake/configs/posix_rpi2_default.cmake b/cmake/configs/posix_rpi2_default.cmake new file mode 100644 index 0000000000000000000000000000000000000000..45aefdbf646dba7364b255f070d5a957f6f6eb04 --- /dev/null +++ b/cmake/configs/posix_rpi2_default.cmake @@ -0,0 +1,28 @@ +include(posix/px4_impl_posix) + +set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake) + +set(config_module_list + drivers/device + + systemcmds/param + systemcmds/ver + + modules/mavlink + + modules/param + modules/systemlib + modules/uORB + modules/dataman + + lib/mathlib + lib/mathlib/math/filter + lib/geo + lib/geo_lookup + lib/conversion + + platforms/common + platforms/posix/px4_layer + platforms/posix/work_queue + +) diff --git a/posix-configs/rpi2/init/rcS_navio b/posix-configs/rpi2/init/rcS_navio new file mode 100644 index 0000000000000000000000000000000000000000..6fd1d59db110c35c9d8c966cb889b75cd9675904 --- /dev/null +++ b/posix-configs/rpi2/init/rcS_navio @@ -0,0 +1,71 @@ +uorb start +simulator start -s +param load +param set MAV_TYPE 2 +param set MC_PITCHRATE_P 0.15 +param set MC_PITCH_P 7 +param set MC_ROLL_P 7 +param set MC_ROLLRATE_P 0.15 +param set MC_YAW_P 2.8 +param set MC_YAWRATE_P 0.35 +param set SYS_AUTOSTART 4010 +param set SYS_RESTART_TYPE 2 +dataman start +param set CAL_GYRO0_ID 2293768 +param set CAL_ACC0_ID 1376264 +param set CAL_ACC1_ID 1310728 +param set CAL_MAG0_ID 196616 +param set CAL_GYRO0_XOFF 0.01 +param set CAL_ACC0_XOFF 0.01 +param set CAL_ACC0_YOFF -0.01 +param set CAL_ACC0_ZOFF 0.01 +param set CAL_ACC0_XSCALE 1.01 +param set CAL_ACC0_YSCALE 1.01 +param set CAL_ACC0_ZSCALE 1.01 +param set CAL_ACC1_XOFF 0.01 +param set CAL_MAG0_XOFF 0.01 +param set MPC_XY_P 0.4 +param set MPC_XY_VEL_P 0.2 +param set MPC_XY_VEL_D 0.005 +param set SENS_BOARD_ROT 0 +param set COM_RC_IN_MODE 1 +param set NAV_ACC_RAD 2.0 +param set RTL_RETURN_ALT 30.0 +param set RTL_DESCEND_ALT 10.0 +param set MIS_TAKEOFF_ALT 5.0 +param set MPC_HOLD_MAX_Z 2.0 +param set MPC_HOLD_XY_DZ 0.1 +param set MPC_HOLD_Z_DZ 0.1 +param set MPC_Z_VEL_MAX 2.0 +param set MPC_Z_VEL_P 0.4 +rgbledsim start +tone_alarm start +gyrosim start +accelsim start +barosim start +adcsim start +gpssim start +pwm_out_sim mode_pwm +sleep 1 +sensors start +commander start +land_detector start multicopter +navigator start +attitude_estimator_q start +position_estimator_inav start +mc_pos_control start +mc_att_control start +mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix +mavlink start -u 14556 -r 2000000 +mavlink start -u 14557 -r 2000000 -m onboard +mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556 +mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556 +mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556 +mavlink stream -r 80 -s ATTITUDE -u 14556 +mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556 +mavlink stream -r 20 -s RC_CHANNELS -u 14556 +mavlink stream -r 250 -s HIGHRES_IMU -u 14556 +mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556 +mavlink stream -r 20 -s MANUAL_CONTROL -u 14556 +mavlink boot_complete +sdlog2 start -r 100 -e -t -a diff --git a/src/lib/version/version.h b/src/lib/version/version.h index 9492cec90f4ba741cacf849d892b7fd78c20189f..9c1caf8e8315ef79031ff8a28274d88fb22d974e 100644 --- a/src/lib/version/version.h +++ b/src/lib/version/version.h @@ -66,7 +66,12 @@ #ifdef CONFIG_ARCH_BOARD_SITL #define HW_ARCH "LINUXTEST" #endif + #ifdef CONFIG_ARCH_BOARD_EAGLE #define HW_ARCH "LINUXTEST" #endif + +#ifdef CONFIG_ARCH_BOARD_RPI2 +#define HW_ARCH "LINUXTEST" +#endif #endif /* VERSION_H_ */