forked from Archive/PX4-Autopilot
Add iris_rplidar model (#6558)
* Whitespace cleanup and add config for rplidar. * Add rplidar target. * Disable gps for rplidar.
This commit is contained in:
parent
36f3befec8
commit
955749ed6f
|
@ -329,7 +329,7 @@ then
|
|||
if lis3mdl -R 0 start
|
||||
then
|
||||
fi
|
||||
|
||||
|
||||
# Possible external compasses
|
||||
if hmc5883 -X start
|
||||
then
|
||||
|
|
|
@ -77,7 +77,7 @@ verifypx4test() {
|
|||
echo -e "[WARNING] Skipping string checks for 8x96 platform"
|
||||
return
|
||||
fi
|
||||
|
||||
|
||||
echo -e "Verifying test results..."
|
||||
|
||||
# verify the presence of expected stings in the apps proc console log
|
||||
|
|
|
@ -60,4 +60,4 @@ if __name__ == "__main__":
|
|||
args = arg_parser.parse_args()
|
||||
generate(xml_file=args.xml, modules=args.modules, dest=args.dest)
|
||||
|
||||
# vim: set et fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :
|
||||
# vim: set et fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :
|
||||
|
|
|
@ -0,0 +1,79 @@
|
|||
uorb start
|
||||
param load
|
||||
param set MAV_TYPE 2
|
||||
param set SYS_AUTOSTART 4010
|
||||
param set SYS_RESTART_TYPE 2
|
||||
param set SYS_MC_EST_GROUP 1
|
||||
dataman start
|
||||
param set BAT_N_CELLS 3
|
||||
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 SENS_BOARD_ROT 0
|
||||
param set SENS_BOARD_X_OFF 0.000001
|
||||
param set COM_RC_IN_MODE 1
|
||||
param set NAV_DLL_ACT 2
|
||||
param set COM_DISARM_LAND 3
|
||||
param set NAV_ACC_RAD 2.0
|
||||
param set COM_OF_LOSS_T 5
|
||||
param set COM_OBL_ACT 2
|
||||
param set COM_OBL_RC_ACT 0
|
||||
param set RTL_RETURN_ALT 30.0
|
||||
param set RTL_DESCEND_ALT 5.0
|
||||
param set RTL_LAND_DELAY 5
|
||||
param set MIS_TAKEOFF_ALT 2.5
|
||||
param set MC_ROLLRATE_P 0.2
|
||||
param set MC_PITCHRATE_P 0.2
|
||||
param set MC_PITCH_P 6
|
||||
param set MC_ROLL_P 6
|
||||
param set MPC_HOLD_MAX_Z 2.0
|
||||
param set MPC_HOLD_XY_DZ 0.1
|
||||
param set MPC_Z_VEL_P 0.6
|
||||
param set MPC_Z_VEL_I 0.15
|
||||
param set LPE_FUSION 242
|
||||
|
||||
replay tryapplyparams
|
||||
simulator start -s
|
||||
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
|
||||
local_position_estimator start
|
||||
mc_pos_control start
|
||||
mc_att_control start
|
||||
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_dc.main.mix
|
||||
mavlink start -u 14556 -r 4000000
|
||||
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
|
||||
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
|
||||
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
|
||||
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
|
||||
mavlink stream -r 50 -s ATTITUDE -u 14556
|
||||
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
|
||||
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
|
||||
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -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
|
||||
logger start -e -t
|
||||
mavlink boot_complete
|
||||
replay trystart
|
|
@ -74,7 +74,8 @@ ExternalProject_Add_Step(sitl_gazebo forceconfigure
|
|||
# create targets for each viewer/model/debugger combination
|
||||
set(viewers none jmavsim gazebo replay)
|
||||
set(debuggers none ide gdb lldb ddd valgrind callgrind)
|
||||
set(models none iris iris_opt_flow standard_vtol plane solo tailsitter typhoon_h480 rover)
|
||||
set(models none iris iris_opt_flow iris_rplidar
|
||||
standard_vtol plane solo tailsitter typhoon_h480 rover)
|
||||
set(all_posix_vmd_make_targets)
|
||||
foreach(viewer ${viewers})
|
||||
foreach(debugger ${debuggers})
|
||||
|
|
Loading…
Reference in New Issue