mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Jenkins add VTOL tiltrotor mission test
This commit is contained in:
parent
7fa91ad3dd
commit
7538ea44e3
33
Jenkinsfile
vendored
33
Jenkinsfile
vendored
@ -240,7 +240,7 @@ pipeline {
|
||||
}
|
||||
}
|
||||
|
||||
stage('ROS vtol standard mission new 1') {
|
||||
stage('ROS vtol standard mission') {
|
||||
agent {
|
||||
docker {
|
||||
image 'px4io/px4-dev-ros:2018-03-30'
|
||||
@ -302,6 +302,37 @@ pipeline {
|
||||
}
|
||||
}
|
||||
|
||||
stage('ROS vtol tiltrotor mission') {
|
||||
agent {
|
||||
docker {
|
||||
image 'px4io/px4-dev-ros:2018-03-30'
|
||||
args '-e CCACHE_BASEDIR=$WORKSPACE -v ${CCACHE_DIR}:${CCACHE_DIR}:rw -e HOME=$WORKSPACE'
|
||||
}
|
||||
}
|
||||
steps {
|
||||
sh 'export'
|
||||
sh 'make distclean; rm -rf .ros; rm -rf .gazebo'
|
||||
sh 'git fetch --tags'
|
||||
sh 'make posix_sitl_default'
|
||||
sh 'make posix_sitl_default sitl_gazebo'
|
||||
sh './test/rostest_px4_run.sh mavros_posix_test_mission.test mission:=vtol_new_1 vehicle:=tiltrotor'
|
||||
sh './Tools/ecl_ekf/process_logdata_ekf.py `find . -name *.ulg -print -quit`'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './Tools/upload_log.py -q --description "${JOB_NAME}: ${STAGE_NAME}" --feedback "${JOB_NAME} ${CHANGE_TITLE} ${CHANGE_URL}" --source CI .ros/rootfs/fs/microsd/log/*/*.ulg'
|
||||
archiveArtifacts '.ros/**/*.pdf'
|
||||
archiveArtifacts '.ros/**/*.csv'
|
||||
sh 'make distclean'
|
||||
}
|
||||
failure {
|
||||
archiveArtifacts '.ros/**/*.ulg'
|
||||
archiveArtifacts '.ros/**/rosunit-*.xml'
|
||||
archiveArtifacts '.ros/**/rostest-*.log'
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
stage('ROS vtol mission new 2') {
|
||||
agent {
|
||||
docker {
|
||||
|
||||
@ -1,7 +1,9 @@
|
||||
uorb start
|
||||
param load
|
||||
dataman start
|
||||
|
||||
param set BAT_N_CELLS 3
|
||||
|
||||
param set CAL_ACC0_ID 1376264
|
||||
param set CAL_ACC0_XOFF 0.01
|
||||
param set CAL_ACC0_XSCALE 1.01
|
||||
@ -15,24 +17,31 @@ param set CAL_GYRO0_ID 2293768
|
||||
param set CAL_GYRO0_XOFF 0.01
|
||||
param set CAL_MAG0_ID 196616
|
||||
param set CAL_MAG0_XOFF 0.01
|
||||
|
||||
param set COM_DISARM_LAND 5
|
||||
param set COM_RC_IN_MODE 1
|
||||
|
||||
param set EKF2_AID_MASK 1
|
||||
param set EKF2_ANGERR_INIT 0.01
|
||||
param set EKF2_GBIAS_INIT 0.01
|
||||
param set EKF2_HGT_MODE 0
|
||||
param set EKF2_MAG_TYPE 1
|
||||
|
||||
param set FW_AIRSPD_MAX 25
|
||||
param set FW_AIRSPD_MIN 14
|
||||
param set FW_AIRSPD_TRIM 16
|
||||
|
||||
param set MAV_TYPE 21
|
||||
|
||||
param set MC_PITCH_P 6
|
||||
param set MC_PITCHRATE_P 0.2
|
||||
param set MC_ROLL_P 6
|
||||
param set MC_ROLLRATE_P 0.3
|
||||
|
||||
param set MIS_LTRMIN_ALT 10
|
||||
param set MIS_TAKEOFF_ALT 10
|
||||
param set MIS_YAW_TMT 10
|
||||
|
||||
param set MPC_ACC_HOR_MAX 2
|
||||
param set MPC_ACC_HOR_MAX 2.0
|
||||
param set MPC_TKO_SPEED 1.0
|
||||
@ -43,24 +52,31 @@ param set MPC_XY_VEL_P 0.15
|
||||
param set MPC_Z_VEL_I 0.15
|
||||
param set MPC_Z_VEL_MAX_DN 1.5
|
||||
param set MPC_Z_VEL_P 0.6
|
||||
|
||||
param set NAV_ACC_RAD 5.0
|
||||
param set NAV_DLL_ACT 2
|
||||
param set NAV_LOITER_RAD 80
|
||||
|
||||
param set RTL_DESCEND_ALT 10.0
|
||||
param set RTL_LAND_DELAY 0
|
||||
param set RTL_RETURN_ALT 30.0
|
||||
|
||||
param set SDLOG_DIRS_MAX 7
|
||||
|
||||
param set SENS_BOARD_ROT 0
|
||||
param set SENS_BOARD_X_OFF 0.000001
|
||||
param set SENS_DPRES_OFF 0.001
|
||||
param set SYS_AUTOSTART 13006
|
||||
|
||||
param set SYS_AUTOSTART 13012
|
||||
param set SYS_MC_EST_GROUP 2
|
||||
param set SYS_RESTART_TYPE 2
|
||||
|
||||
param set VT_MOT_COUNT 4
|
||||
param set VT_F_TRANS_THR 0.75
|
||||
param set VT_TYPE 1
|
||||
param set VT_TILT_FW 3.1415
|
||||
param set VT_TILT_TRANS 1.2
|
||||
|
||||
replay tryapplyparams
|
||||
simulator start -s
|
||||
tone_alarm start
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user