forked from Archive/PX4-Autopilot
changes to rpi2 configs
This commit is contained in:
parent
4351eb147c
commit
37ffb61afd
3
Makefile
3
Makefile
|
@ -174,6 +174,9 @@ posix_eagle_default:
|
|||
posix_rpi2_default:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_rpi2_release:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix: posix_sitl_default
|
||||
|
||||
sitl_deprecation:
|
||||
|
|
|
@ -4,25 +4,44 @@ set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.c
|
|||
|
||||
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
|
||||
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
systemcmds/topic_listener
|
||||
systemcmds/perf
|
||||
modules/uORB
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/sensors
|
||||
modules/mavlink
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/navigator
|
||||
modules/vtol_att_control
|
||||
modules/mc_pos_control
|
||||
modules/mc_att_control
|
||||
modules/land_detector
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/commander
|
||||
modules/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
)
|
||||
|
|
|
@ -0,0 +1,47 @@
|
|||
include(posix/px4_impl_posix)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
|
||||
|
||||
set(config_module_list
|
||||
drivers/device
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
systemcmds/topic_listener
|
||||
systemcmds/perf
|
||||
modules/uORB
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/sensors
|
||||
modules/mavlink
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/navigator
|
||||
modules/vtol_att_control
|
||||
modules/mc_pos_control
|
||||
modules/mc_att_control
|
||||
modules/land_detector
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/commander
|
||||
modules/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
)
|
|
@ -1,71 +0,0 @@
|
|||
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
|
Loading…
Reference in New Issue