From 9d152ddc9daceb45e3c715433b9a1dd347adef54 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 22 Oct 2012 23:31:33 +0200 Subject: [PATCH] Huge step towards usability goals: Graphic vehicle configuration in a first (ugly) sketch --- files/px4/hexarotor/widgets/px4_calibration.qgw | 50 -- files/px4/quadrotor/widgets/px4_calibration.qgw | 50 -- files/px4/widgets/px4_calibration.qgw | 50 ++ files/px4/widgets/px4_fw_attitude_pid_params.qgw | 8 + files/px4/widgets/px4_fw_position_pid_params.qgw | 8 + files/px4/widgets/px4_mc_attitude_pid_params.qgw | 62 ++ src/uas/UAS.h | 3 + src/ui/MainWindow.cc | 16 +- src/ui/QGCRemoteControlView.cc | 24 +- src/ui/QGCVehicleConfig.cc | 298 +++++++- src/ui/QGCVehicleConfig.h | 14 + src/ui/QGCVehicleConfig.ui | 934 +++++++++++++++-------- 12 files changed, 1088 insertions(+), 429 deletions(-) delete mode 100644 files/px4/hexarotor/widgets/px4_calibration.qgw delete mode 100644 files/px4/quadrotor/widgets/px4_calibration.qgw create mode 100644 files/px4/widgets/px4_calibration.qgw create mode 100644 files/px4/widgets/px4_fw_attitude_pid_params.qgw create mode 100644 files/px4/widgets/px4_fw_position_pid_params.qgw create mode 100644 files/px4/widgets/px4_mc_attitude_pid_params.qgw diff --git a/files/px4/hexarotor/widgets/px4_calibration.qgw b/files/px4/hexarotor/widgets/px4_calibration.qgw deleted file mode 100644 index dd81822..0000000 --- a/files/px4/hexarotor/widgets/px4_calibration.qgw +++ /dev/null @@ -1,50 +0,0 @@ -[PX4%20Calibration%20Tool] -QGC_TOOL_WIDGET_ITEMS\1\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=Reboot (only in standby) -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_BUTTONTEXT=REBOOT -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_COMMANDID=246 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM1=1 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM1=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM2=1 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=1 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\4\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_BUTTONTEXT=GYRO -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM1=1 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\size=4 diff --git a/files/px4/quadrotor/widgets/px4_calibration.qgw b/files/px4/quadrotor/widgets/px4_calibration.qgw deleted file mode 100644 index dd81822..0000000 --- a/files/px4/quadrotor/widgets/px4_calibration.qgw +++ /dev/null @@ -1,50 +0,0 @@ -[PX4%20Calibration%20Tool] -QGC_TOOL_WIDGET_ITEMS\1\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=Reboot (only in standby) -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_BUTTONTEXT=REBOOT -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_COMMANDID=246 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM1=1 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM1=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM2=1 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=1 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\4\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_BUTTONTEXT=GYRO -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM1=1 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\size=4 diff --git a/files/px4/widgets/px4_calibration.qgw b/files/px4/widgets/px4_calibration.qgw new file mode 100644 index 0000000..cd75167 --- /dev/null +++ b/files/px4/widgets/px4_calibration.qgw @@ -0,0 +1,50 @@ +[PX4%20Calibration%20Tool] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=COMMANDBUTTON +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=Reboot (only in standby) +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_BUTTONTEXT=REBOOT +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_COMMANDID=246 +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM1=1 +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM2=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM3=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM4=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0 +QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Magnetometer calibration +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241 +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM1=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM2=1 +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM3=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM4=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM5=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM6=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM7=0 +QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241 +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=1 +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0 +QGC_TOOL_WIDGET_ITEMS\4\TYPE=COMMANDBUTTON +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_BUTTONTEXT=GYRO +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_COMMANDID=241 +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM1=1 +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM2=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM3=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM4=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM5=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM6=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM7=0 +QGC_TOOL_WIDGET_ITEMS\size=4 diff --git a/files/px4/widgets/px4_fw_attitude_pid_params.qgw b/files/px4/widgets/px4_fw_attitude_pid_params.qgw new file mode 100644 index 0000000..6f3186e --- /dev/null +++ b/files/px4/widgets/px4_fw_attitude_pid_params.qgw @@ -0,0 +1,8 @@ +[PX4%20Fixed%20Wing%20Attitude%20Control] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Roll Rate P Gain +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=FW_ROLLRATE_P +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=2 +QGC_TOOL_WIDGET_ITEMS\size=1 diff --git a/files/px4/widgets/px4_fw_position_pid_params.qgw b/files/px4/widgets/px4_fw_position_pid_params.qgw new file mode 100644 index 0000000..e99f989 --- /dev/null +++ b/files/px4/widgets/px4_fw_position_pid_params.qgw @@ -0,0 +1,8 @@ +[PX4%20Fixed%20Wing%20Position%20Control] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Heading P Gain +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=FW_HEADING_P +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=2 +QGC_TOOL_WIDGET_ITEMS\size=1 diff --git a/files/px4/widgets/px4_mc_attitude_pid_params.qgw b/files/px4/widgets/px4_mc_attitude_pid_params.qgw new file mode 100644 index 0000000..a7f8871 --- /dev/null +++ b/files/px4/widgets/px4_mc_attitude_pid_params.qgw @@ -0,0 +1,62 @@ +[PX4%20Multirotor%20Attitude%20Control] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Attitude P Gain +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=MC_ATT_P +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=1.5 +QGC_TOOL_WIDGET_ITEMS\2\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DESCRIPTION=Attitude I Gain +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_PARAMID=MC_ATT_I +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\3\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DESCRIPTION=Attitude D Gain +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_PARAMID=MC_ATT_D +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Anti-Windup +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=MC_ATT_AWU +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\5\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Output Limit +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_PARAMID=MC_ATT_LIM +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MAX=3 +QGC_TOOL_WIDGET_ITEMS\6\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw P Gain +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_P +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MAX=1.2 +QGC_TOOL_WIDGET_ITEMS\7\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw D Gain +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_D +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\8\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate P Gain +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_P +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MAX=1.5 +QGC_TOOL_WIDGET_ITEMS\9\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate D Gain +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_D +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MAX=0.3 +QGC_TOOL_WIDGET_ITEMS\10\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_DESCRIPTION=Yaw Rate P Gain +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_PARAMID=MC_YAWRATE_P +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\size=10 diff --git a/src/uas/UAS.h b/src/uas/UAS.h index fe37b2c..8ab0b96 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -478,6 +478,9 @@ public: case MAV_AUTOPILOT_FP: return "FP"; break; + case MAV_AUTOPILOT_PX4: + return "PX4"; + break; default: return ""; break; diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 75e53ba..573df8a 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -564,11 +564,11 @@ void MainWindow::buildCommonWidgets() addCentralWidget(hudWidget, tr("Head Up Display")); } -// if (!configWidget) -// { -// configWidget = new QGCVehicleConfig(this); -// addCentralWidget(configWidget, tr("Vehicle Configuration")); -// } + if (!configWidget) + { + configWidget = new QGCVehicleConfig(this); + addCentralWidget(configWidget, tr("Vehicle Configuration")); + } if (!dataplotWidget) { @@ -724,10 +724,14 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) void MainWindow::loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType) { - QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; + QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/widgets/"; + QString platformDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; QDir widgets(defaultsDir); QStringList files = widgets.entryList(); + QDir platformWidgets(platformDir); + files.append(platformWidgets.entryList()); + if (files.count() == 0) { qDebug() << "No default custom widgets for system " << systemType << "autopilot" << autopilotType << " found"; diff --git a/src/ui/QGCRemoteControlView.cc b/src/ui/QGCRemoteControlView.cc index 7efc315..bfef68e 100644 --- a/src/ui/QGCRemoteControlView.cc +++ b/src/ui/QGCRemoteControlView.cc @@ -55,13 +55,13 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) : this->setVisible(false); //setVisible(false); - calibrate = new QPushButton(tr("Calibrate"), this); - QHBoxLayout *calibrateButtonLayout = new QHBoxLayout(); - calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter); - layout->addItem(calibrateButtonLayout, 3, 0, 1, 2); +// calibrate = new QPushButton(tr("Calibrate"), this); +// QHBoxLayout *calibrateButtonLayout = new QHBoxLayout(); +// calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter); +// layout->addItem(calibrateButtonLayout, 3, 0, 1, 2); - calibrationWindow = new RadioCalibrationWindow(this); - connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show())); +// calibrationWindow = new RadioCalibrationWindow(this); +// connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show())); connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int))); @@ -91,8 +91,8 @@ void QGCRemoteControlView::setUASId(int id) // The UAS exists, disconnect any existing connections disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float))); disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float))); - disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); - disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); + //disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); + //disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float))); } } @@ -124,15 +124,15 @@ void QGCRemoteControlView::setUASId(int id) { // New UAS exists, connect nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName())); - calibrationWindow->setUASId(id); - connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); + //calibrationWindow->setUASId(id); + //connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float))); connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float))); connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float))); // only connect raw channels to calibration window widget - connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); + //connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); } } @@ -178,7 +178,7 @@ void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized) void QGCRemoteControlView::appendChannelWidget(int channelId) { // Create new layout - QHBoxLayout* layout = new QHBoxLayout(this); + QHBoxLayout* layout = new QHBoxLayout(); // Add content layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this)); QLabel* raw = new QLabel(this); diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index 3f6565e..c0f08fa 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -5,12 +5,22 @@ #include "QGCVehicleConfig.h" #include "UASManager.h" #include "QGC.h" +#include "QGCToolWidget.h" #include "ui_QGCVehicleConfig.h" QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : QWidget(parent), mav(NULL), changed(true), + rc_mode(RC_MODE_2), + rcRoll(0.0f), + rcPitch(0.0f), + rcYaw(0.0f), + rcThrottle(0.0f), + rcMode(0.0f), + rcAux1(0.0f), + rcAux2(0.0f), + rcAux3(0.0f), ui(new Ui::QGCVehicleConfig) { setObjectName("QGC_VEHICLECONFIG"); @@ -19,8 +29,11 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : requestCalibrationRC(); if (mav) mav->requestParameter(0, "RC_TYPE"); + ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1); + connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool))); connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters())); + connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); @@ -41,6 +54,14 @@ QGCVehicleConfig::~QGCVehicleConfig() delete ui; } +void QGCVehicleConfig::setRCModeIndex(int newRcMode) +{ + if (newRcMode > 0 && newRcMode < 5) + { + rc_mode = (enum RC_MODE) (newRcMode+1); + changed = true; + } +} void QGCVehicleConfig::toggleCalibrationRC(bool enabled) { @@ -57,12 +78,14 @@ void QGCVehicleConfig::toggleCalibrationRC(bool enabled) void QGCVehicleConfig::startCalibrationRC() { ui->rcTypeComboBox->setEnabled(false); + ui->rcCalibrationButton->setText(tr("Stop RC Calibration")); resetCalibrationRC(); } void QGCVehicleConfig::stopCalibrationRC() { ui->rcTypeComboBox->setEnabled(true); + ui->rcCalibrationButton->setText(tr("Start RC Calibration")); } void QGCVehicleConfig::setActiveUAS(UASInterface* active) @@ -77,15 +100,69 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) SLOT(remoteControlChannelRawChanged(int,float))); disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); - resetCalibrationRC(); + + foreach (QGCToolWidget* tool, toolWidgets) + { + delete tool; + } } + // Reset current state + resetCalibrationRC(); + // Connect new system mav = active; connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(remoteControlChannelRawChanged(int,float))); connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); + + mav->requestParameters(); + + QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/"; + + QGCToolWidget* tool; + + // Load calibration + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_calibration.qgw", false)) + { + toolWidgets.append(tool); + ui->sensorLayout->addWidget(tool); + } + // Load multirotor attitude pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_mc_attitude_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->multiRotorAttitudeLayout->addWidget(tool); + } + + // Load multirotor position pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_mc_position_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->multiRotorPositionLayout->addWidget(tool); + } + + // Load fixed wing attitude pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_fw_attitude_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->fixedWingAttitudeLayout->addWidget(tool); + } + + // Load fixed wing position pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_fw_position_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->fixedWingPositionLayout->addWidget(tool); + } + + updateStatus(QString("Reading from system %1").arg(mav->getUASName())); } void QGCVehicleConfig::resetCalibrationRC() @@ -177,6 +254,16 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) if (chan < 0 || static_cast(chan) >= chanMax) return; + if (val < rcMin[chan]) + { + rcMin[chan] = val; + } + + if (val > rcMax[chan]) + { + rcMax[chan] = val; + } + if (chan == rcMapping[0]) { // ROLL @@ -252,16 +339,19 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) { // AUX1 rcAux1 = val; + rcValue[5] = val; } else if (chan == rcMapping[6]) { // AUX2 rcAux2 = val; + rcValue[6] = val; } else if (chan == rcMapping[7]) { // AUX3 rcAux3 = val; + rcValue[7] = val; } changed = true; @@ -273,6 +363,91 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete { Q_UNUSED(uas); Q_UNUSED(component); + + // Channel calibration values + QRegExp minTpl("RC?_MIN"); + minTpl.setPatternSyntax(QRegExp::Wildcard); + QRegExp maxTpl("RC?_MAX"); + maxTpl.setPatternSyntax(QRegExp::Wildcard); + QRegExp trimTpl("RC?_TRIM"); + trimTpl.setPatternSyntax(QRegExp::Wildcard); + QRegExp revTpl("RC?_REV"); + revTpl.setPatternSyntax(QRegExp::Wildcard); + + // Do not write the RC type, as these values depend on this + // active onboard parameter + + if (minTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcMin[index] = value.toInt(); + } + } + + if (maxTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcMax[index] = value.toInt(); + } + } + + if (trimTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcTrim[index] = value.toInt(); + } + } + + if (revTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcRev[index] = (value.toInt() == -1) ? true : false; + + unsigned int mapindex = rcMapping[index]; + + switch (mapindex) + { + case 0: + ui->invertCheckBox->setChecked(rcRev[index]); + break; + case 1: + ui->invertCheckBox_2->setChecked(rcRev[index]); + break; + case 2: + ui->invertCheckBox_3->setChecked(rcRev[index]); + break; + case 3: + ui->invertCheckBox_4->setChecked(rcRev[index]); + break; + case 4: + ui->invertCheckBox_5->setChecked(rcRev[index]); + break; + case 5: + ui->invertCheckBox_6->setChecked(rcRev[index]); + break; + case 6: + ui->invertCheckBox_7->setChecked(rcRev[index]); + break; + case 7: + ui->invertCheckBox_8->setChecked(rcRev[index]); + break; + } + } + } + +// mav->setParameter(0, trimTpl.arg(i), rcTrim[i]); +// mav->setParameter(0, maxTpl.arg(i), rcMax[i]); +// mav->setParameter(0, revTpl.arg(i), (rcRev[i]) ? -1 : 1); +// } + if (rcTypeUpdateRequested > 0 && parameterName == QString("RC_TYPE")) { rcTypeUpdateRequested = 0; @@ -281,6 +456,82 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete // Request all other parameters as well requestCalibrationRC(); } + + // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3 + + if (parameterName.contains("RC_MAP_ROLL")) { + rcMapping[0] = value.toInt(); + ui->rollSpinBox->setValue(rcMapping[0]); + } + + if (parameterName.contains("RC_MAP_PITCH")) { + rcMapping[1] = value.toInt(); + ui->pitchSpinBox->setValue(rcMapping[1]); + } + + if (parameterName.contains("RC_MAP_YAW")) { + rcMapping[2] = value.toInt(); + ui->yawSpinBox->setValue(rcMapping[2]); + } + + if (parameterName.contains("RC_MAP_THROTTLE")) { + rcMapping[3] = value.toInt(); + ui->throttleSpinBox->setValue(rcMapping[3]); + } + + if (parameterName.contains("RC_MAP_MODE_SW")) { + rcMapping[4] = value.toInt(); + ui->modeSpinBox->setValue(rcMapping[4]); + } + + if (parameterName.contains("RC_MAP_AUX1")) { + rcMapping[5] = value.toInt(); + ui->aux1SpinBox->setValue(rcMapping[5]); + } + + if (parameterName.contains("RC_MAP_AUX2")) { + rcMapping[6] = value.toInt(); + ui->aux1SpinBox->setValue(rcMapping[6]); + } + + if (parameterName.contains("RC_MAP_AUX3")) { + rcMapping[7] = value.toInt(); + ui->aux1SpinBox->setValue(rcMapping[7]); + } + + // Scaling + + if (parameterName.contains("RC_SCALE_ROLL")) { + rcScaling[0] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_PITCH")) { + rcScaling[1] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_YAW")) { + rcScaling[2] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_THROTTLE")) { + rcScaling[3] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_MODE_SW")) { + rcScaling[4] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_AUX1")) { + rcScaling[5] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_AUX2")) { + rcScaling[6] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_AUX3")) { + rcScaling[7] = value.toInt(); + } } void QGCVehicleConfig::updateStatus(const QString& str) @@ -321,10 +572,47 @@ void QGCVehicleConfig::updateView() { if (changed) { - ui->rollSlider->setValue(rcValue[0]); - ui->pitchSlider->setValue(rcValue[1]); - ui->yawSlider->setValue(rcValue[2]); - ui->throttleSlider->setValue(rcValue[3]); + if (rc_mode == RC_MODE_1) + { + ui->rollSlider->setValue(rcRoll); + ui->pitchSlider->setValue(rcThrottle); + ui->yawSlider->setValue(rcYaw); + ui->throttleSlider->setValue(rcPitch); + } + else if (rc_mode == RC_MODE_2) + { + ui->rollSlider->setValue(rcRoll); + ui->pitchSlider->setValue(rcPitch); + ui->yawSlider->setValue(rcYaw); + ui->throttleSlider->setValue(rcThrottle); + } + else if (rc_mode == RC_MODE_3) + { + ui->rollSlider->setValue(rcYaw); + ui->pitchSlider->setValue(rcThrottle); + ui->yawSlider->setValue(rcRoll); + ui->throttleSlider->setValue(rcPitch); + } + else if (rc_mode == RC_MODE_4) + { + ui->rollSlider->setValue(rcYaw); + ui->pitchSlider->setValue(rcPitch); + ui->yawSlider->setValue(rcRoll); + ui->throttleSlider->setValue(rcThrottle); + } + + ui->chanLabel->setText(QString("%1/%2").arg(rcValue[0]).arg(rcRoll)); + ui->chanLabel_2->setText(QString("%1/%2").arg(rcValue[1]).arg(rcPitch)); + ui->chanLabel_3->setText(QString("%1/%2").arg(rcValue[2]).arg(rcYaw)); + ui->chanLabel_4->setText(QString("%1/%2").arg(rcValue[3]).arg(rcThrottle)); + ui->modeSwitchSlider->setValue(rcMode); + ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[4]).arg(rcMode)); + ui->aux1Slider->setValue(rcAux1); + ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[5]).arg(rcAux1)); + ui->aux2Slider->setValue(rcAux2); + ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[6]).arg(rcAux2)); + ui->aux3Slider->setValue(rcAux3); + ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[7]).arg(rcAux3)); changed = false; } } diff --git a/src/ui/QGCVehicleConfig.h b/src/ui/QGCVehicleConfig.h index a9b09f8..caec352 100644 --- a/src/ui/QGCVehicleConfig.h +++ b/src/ui/QGCVehicleConfig.h @@ -3,7 +3,9 @@ #include #include +#include +#include "QGCToolWidget.h" #include "UASInterface.h" namespace Ui { @@ -18,6 +20,13 @@ public: explicit QGCVehicleConfig(QWidget *parent = 0); ~QGCVehicleConfig(); + enum RC_MODE { + RC_MODE_1 = 1, + RC_MODE_2 = 2, + RC_MODE_3 = 3, + RC_MODE_4 = 4 + }; + public slots: /** Set the MAV currently being calibrated */ void setActiveUAS(UASInterface* active); @@ -28,6 +37,8 @@ public slots: void stopCalibrationRC(); /** Start/stop the RC calibration routine */ void toggleCalibrationRC(bool enabled); + /** Change the mode setting of the control inputs */ + void setRCModeIndex(int newRcMode); /** Render the data updated */ void updateView(); @@ -60,6 +71,7 @@ protected: int rcMax[chanMax]; ///< Maximum values int rcTrim[chanMax]; ///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle) int rcMapping[chanMax]; ///< PWM to function mappings + float rcScaling[chanMax]; ///< Scaling of channel input to control commands bool rcRev[chanMax]; ///< Channel reverse int rcValue[chanMax]; ///< Last values float rcRoll; ///< PPM input channel used as roll control input @@ -73,6 +85,8 @@ protected: bool rcCalChanged; ///< Set if the calibration changes (and needs to be written) bool changed; ///< Set if any of the input data changed QTimer updateTimer; ///< Controls update intervals + enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention + QList toolWidgets; ///< Configurable widgets private: Ui::QGCVehicleConfig *ui; diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui index 85ac487..5290a8e 100644 --- a/src/ui/QGCVehicleConfig.ui +++ b/src/ui/QGCVehicleConfig.ui @@ -6,7 +6,7 @@ 0 0 - 658 + 717 586 @@ -23,6 +23,20 @@ 6 + + + + Store to EEPROM + + + + + + + No pending changes + + + @@ -32,36 +46,114 @@ RC Calibration - - - + + + + + -1 + + + 1 + + + 0 + Qt::Vertical - - - - + + + + -1 - - :/files/images/rc_stick.svg + + 1 - - true + + 0 + + + Qt::Vertical - - + + + + + + false + + + false + + + + Select transmitter model + + + + + + + + true + + + + Mode 1 + + + + + Mode 2 + + + + + Mode 3 + + + + + Mode 4 + + + + + + + + Qt::Vertical + + + 598 + 5 + + + + + + + + + - - + + + + + + + + + Qt::Horizontal @@ -73,93 +165,409 @@ - - + + + + + + Aux 3 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Pitch / Elevator + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Aux 2 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Invert + + + + + + + 1 + + + 8 + + + + + + + 1 + + + 8 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Throttle + + + + + + + Invert + + + + + + + 1 + + + 8 + + + + + + + 1 + + + 8 + + + + + + + Mode Switch + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 1 + + + 8 + + + + + + + 1 + + + 8 + + + + + + + Aux 1 + + + + + + + 1 + + + 8 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 1 + + + 8 + + + + + + + Roll / Ailerons + + + + + + + Invert + + + + + + + Invert + + + + + + + Invert + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Invert + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Yaw / Rudder + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Invert + + + + + + + Invert + + + + + + + + + Qt::Horizontal + + + + 22 + 122 + + + + + + Qt::Vertical - 5 - 5 + 598 + 17 - - + + - - - - - - 800 - - - 2200 - - - 1500 + + :/files/images/rc_stick.svg - - Qt::Horizontal + + true - - - - false + + + + Qt::Horizontal - - - Select control mode - - - - - - - - - Select transmitter model - - - - - - - + - 100 - 100 + 40 + 20 + + + + + + + 1 + 1 + + - 50 - 50 + 10 + 10 - 50 - 50 + 100 + 100 - - - - - - - :/files/images/rc_stick.svg @@ -168,74 +576,128 @@ - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + -1 + + + 1 + + + 0 + + + Qt::Horizontal + + + + - 800 + -1 - 2200 + 1 - 1500 + 0 Qt::Horizontal - - + + - + Start Calibration - - + + + + Qt::Vertical + + + QSizePolicy::MinimumExpanding + + + + 20 + 10 + + + + + + - 800 + -1 - 2200 - - - 1500 + 1 Qt::Vertical - - + + + + -1 + + + 1 + Qt::Vertical - - + + + + -1 + + + 1 + Qt::Vertical - - + + - 800 + -1 - 2200 + 1 Qt::Vertical - - + + Qt::Horizontal @@ -247,248 +709,108 @@ - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Start Calibration - - - Sensor Calibration - - - - 30 - 20 - 161 - 32 - - - - Gyro Calibration - - - - - - 30 - 80 - 161 - 32 - - - - Accel Calibration - - - - - - 30 - 140 - 161 - 32 - - - - Mag Calibration - - + + + + + - Multirotor Attitude Control + Multirotor Control - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - Set Gains - - + + - - + + Load Platform Defaults - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - + + + + + + + Attitude + + + + + + + + + + + + Position + + + + + + + + + - - - - Qt::Horizontal - + + + + + Fixed Wing Control + + + + + + Attitude + + + + + + - - + + - - - - Qt::Horizontal + + + + Load Platform Defaults - - - - - - - Qt::Horizontal + + + + Position + + + + + - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - No pending changes - - - - - - - Store to EEPROM - - -