Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
414a947c
Commit
414a947c
authored
Dec 03, 2010
by
Mariano Lizarraga
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'experimental' of
git://github.com/tecnosapiens/qgroundcontrol
into mergeRemote
parents
ee9cbf32
5a8a8b2b
Changes
7
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
391 additions
and
57 deletions
+391
-57
SlugsMAV.cc
src/uas/SlugsMAV.cc
+15
-1
SlugsMAV.h
src/uas/SlugsMAV.h
+6
-1
MainWindow.cc
src/ui/MainWindow.cc
+1
-1
SlugsPIDControl.cpp
src/ui/SlugsPIDControl.cpp
+279
-15
SlugsPIDControl.h
src/ui/SlugsPIDControl.h
+57
-0
SlugsPIDControl.ui
src/ui/SlugsPIDControl.ui
+32
-32
SlugsVideoCamControl.h
src/ui/SlugsVideoCamControl.h
+1
-7
No files found.
src/uas/SlugsMAV.cc
View file @
414a947c
...
@@ -39,6 +39,7 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
...
@@ -39,6 +39,7 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
memset
(
&
mlActionAck
,
0
,
sizeof
(
mavlink_action_ack_t
));
memset
(
&
mlActionAck
,
0
,
sizeof
(
mavlink_action_ack_t
));
memset
(
&
mlAction
,
0
,
sizeof
(
mavlink_slugs_action_t
));
memset
(
&
mlAction
,
0
,
sizeof
(
mavlink_slugs_action_t
));
updateRoundRobin
=
0
;
updateRoundRobin
=
0
;
...
@@ -134,6 +135,12 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -134,6 +135,12 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break
;
break
;
case
MAVLINK_MSG_ID_PID
:
//182
case
MAVLINK_MSG_ID_PID
:
//182
memset
(
&
mlSinglePid
,
0
,
sizeof
(
mavlink_pid_t
));
mavlink_msg_pid_decode
(
&
message
,
&
mlSinglePid
);
qDebug
()
<<
"
\n
SLUGS RECEIVED PID Message = "
<<
mlSinglePid
.
idx
;
emit
slugsPidValues
(
uasId
,
mlSinglePid
);
break
;
break
;
...
@@ -177,7 +184,7 @@ void SlugsMAV::emitSignals (void){
...
@@ -177,7 +184,7 @@ void SlugsMAV::emitSignals (void){
case
5
:
case
5
:
emit
slugsFilteredData
(
uasId
,
mlFilteredData
);
emit
slugsFilteredData
(
uasId
,
mlFilteredData
);
emit
slugsGPSDateTime
(
uasId
,
mlGpsDateTime
);
emit
slugsGPSDateTime
(
uasId
,
mlGpsDateTime
);
break
;
break
;
case
6
:
case
6
:
emit
slugsActionAck
(
uasId
,
mlActionAck
);
emit
slugsActionAck
(
uasId
,
mlActionAck
);
...
@@ -221,4 +228,11 @@ void SlugsMAV::emitGpsSignals (void){
...
@@ -221,4 +228,11 @@ void SlugsMAV::emitGpsSignals (void){
}
}
}
}
void
SlugsMAV
::
emitPidSignal
()
{
qDebug
()
<<
"
\n
SLUGS RECEIVED PID Message"
;
emit
slugsPidValues
(
uasId
,
mlSinglePid
);
}
#endif // MAVLINK_ENABLED_SLUGS
#endif // MAVLINK_ENABLED_SLUGS
src/uas/SlugsMAV.h
View file @
414a947c
...
@@ -62,6 +62,8 @@ signals:
...
@@ -62,6 +62,8 @@ signals:
void
slugsGPSDateTime
(
int
systemId
,
const
mavlink_gps_date_time_t
&
gpsDateTime
);
void
slugsGPSDateTime
(
int
systemId
,
const
mavlink_gps_date_time_t
&
gpsDateTime
);
void
slugsActionAck
(
int
systemId
,
const
mavlink_action_ack_t
&
actionAck
);
void
slugsActionAck
(
int
systemId
,
const
mavlink_action_ack_t
&
actionAck
);
void
slugsPidValues
(
int
systemId
,
const
mavlink_pid_t
&
pidValues
);
void
slugsBootMsg
(
int
uasId
,
mavlink_boot_t
&
boot
);
void
slugsBootMsg
(
int
uasId
,
mavlink_boot_t
&
boot
);
void
slugsAttitude
(
int
uasId
,
mavlink_attitude_t
&
attitude
);
void
slugsAttitude
(
int
uasId
,
mavlink_attitude_t
&
attitude
);
...
@@ -96,7 +98,7 @@ protected:
...
@@ -96,7 +98,7 @@ protected:
mavlink_set_mode_t
mlApMode
;
mavlink_set_mode_t
mlApMode
;
mavlink_pwm_commands_t
mlPwmCommands
;
mavlink_pwm_commands_t
mlPwmCommands
;
mavlink_pid_values_t
mlPidValues
;
mavlink_pid_values_t
mlPidValues
;
mavlink_pid_t
mlSinglePid
;
mavlink_pid_t
mlSinglePid
;
mavlink_slugs_navigation_t
mlNavigation
;
mavlink_slugs_navigation_t
mlNavigation
;
mavlink_data_log_t
mlDataLog
;
mavlink_data_log_t
mlDataLog
;
...
@@ -106,11 +108,14 @@ protected:
...
@@ -106,11 +108,14 @@ protected:
mavlink_slugs_action_t
mlAction
;
mavlink_slugs_action_t
mlAction
;
// Standart messages MAVLINK used by SLUGS
// Standart messages MAVLINK used by SLUGS
private:
private:
void
emitGpsSignals
(
void
);
void
emitGpsSignals
(
void
);
void
emitPidSignal
(
void
);
int
uasId
;
int
uasId
;
...
...
src/ui/MainWindow.cc
View file @
414a947c
...
@@ -943,7 +943,7 @@ void MainWindow::loadGlobalOperatorView()
...
@@ -943,7 +943,7 @@ void MainWindow::loadGlobalOperatorView()
if
(
slugsCamControlWidget
)
if
(
slugsCamControlWidget
)
{
{
addDockWidget
(
Qt
::
Right
DockWidgetArea
,
slugsCamControlWidget
);
addDockWidget
(
Qt
::
Bottom
DockWidgetArea
,
slugsCamControlWidget
);
slugsCamControlWidget
->
show
();
slugsCamControlWidget
->
show
();
}
}
...
...
src/ui/SlugsPIDControl.cpp
View file @
414a947c
This diff is collapsed.
Click to expand it.
src/ui/SlugsPIDControl.h
View file @
414a947c
...
@@ -48,6 +48,13 @@ public slots:
...
@@ -48,6 +48,13 @@ public slots:
*/
*/
void
connect_set_pushButtons
();
void
connect_set_pushButtons
();
/**
* @brief Connect Set pushButtons to change the color GroupBox
*
* @param
*/
void
connect_get_pushButtons
();
/**
/**
* @brief Connect Edition Lines for PID Values
* @brief Connect Edition Lines for PID Values
*
*
...
@@ -55,6 +62,13 @@ public slots:
...
@@ -55,6 +62,13 @@ public slots:
*/
*/
void
connect_editLinesPDIvalues
();
void
connect_editLinesPDIvalues
();
/**
* @brief send a PDI request message to UAS
*
* @param
*/
void
sendMessagePIDStatus
(
int
PIDtype
);
// Fuctions for Air Speed GroupBox
// Fuctions for Air Speed GroupBox
/**
/**
* @brief Change color style to red when PID values of Air Speed are edited
* @brief Change color style to red when PID values of Air Speed are edited
...
@@ -75,6 +89,13 @@ public slots:
...
@@ -75,6 +89,13 @@ public slots:
* @param
* @param
*/
*/
void
connect_AirSpeed_LineEdit
();
void
connect_AirSpeed_LineEdit
();
/**
* @brief get message PID Air Speed(loop index = 0) from UAS
*
* @param
*/
void
get_AirSpeed_PID
();
// Functions for Pitch Followei GroupBox
// Functions for Pitch Followei GroupBox
/**
/**
...
@@ -96,6 +117,13 @@ public slots:
...
@@ -96,6 +117,13 @@ public slots:
* @param
* @param
*/
*/
void
connect_PitchFollowei_LineEdit
();
void
connect_PitchFollowei_LineEdit
();
/**
* @brief get message PID Pitch Followei(loop index = 2) from UAS
*
* @param
*/
void
get_PitchFollowei_PID
();
// Functions for Roll Control GroupBox
// Functions for Roll Control GroupBox
/**
/**
...
@@ -117,6 +145,13 @@ public slots:
...
@@ -117,6 +145,13 @@ public slots:
* @param
* @param
*/
*/
void
connect_RollControl_LineEdit
();
void
connect_RollControl_LineEdit
();
/**
* @brief get message PID Roll Control(loop index = 4) from UAS
*
* @param
*/
void
get_RollControl_PID
();
// Functions for Heigth Error GroupBox
// Functions for Heigth Error GroupBox
/**
/**
...
@@ -138,6 +173,12 @@ public slots:
...
@@ -138,6 +173,12 @@ public slots:
* @param
* @param
*/
*/
void
connect_HeigthError_LineEdit
();
void
connect_HeigthError_LineEdit
();
/**
* @brief get message PID Heigth Error(loop index = 1) from UAS
*
* @param
*/
void
get_HeigthError_PID
();
// Functions for Yaw Damper GroupBox
// Functions for Yaw Damper GroupBox
/**
/**
...
@@ -159,6 +200,14 @@ public slots:
...
@@ -159,6 +200,14 @@ public slots:
* @param
* @param
*/
*/
void
connect_YawDamper_LineEdit
();
void
connect_YawDamper_LineEdit
();
/**
* @brief get message PID Yaw Damper(loop index = 3) from UAS
*
* @param
*/
void
get_YawDamper_PID
();
// Functions for Pitch to dT GroupBox
// Functions for Pitch to dT GroupBox
/**
/**
...
@@ -180,6 +229,12 @@ public slots:
...
@@ -180,6 +229,12 @@ public slots:
* @param
* @param
*/
*/
void
connect_Pitch2dT_LineEdit
();
void
connect_Pitch2dT_LineEdit
();
/**
* @brief get message PID Pitch2dT(loop index = 8) from UAS
*
* @param
*/
void
get_Pitch2dT_PID
();
//Create, send and get Messages PID
//Create, send and get Messages PID
...
@@ -187,6 +242,7 @@ public slots:
...
@@ -187,6 +242,7 @@ public slots:
#ifdef MAVLINK_ENABLED_SLUGS
#ifdef MAVLINK_ENABLED_SLUGS
void
recibeMensaje
(
int
systemId
,
const
mavlink_action_ack_t
&
action
);
void
recibeMensaje
(
int
systemId
,
const
mavlink_action_ack_t
&
action
);
void
receivePidValues
(
int
systemId
,
const
mavlink_pid_t
&
pidValues
);
#endif // MAVLINK_ENABLED_SLUG
#endif // MAVLINK_ENABLED_SLUG
...
@@ -206,6 +262,7 @@ private:
...
@@ -206,6 +262,7 @@ private:
//SlugsMav Message
//SlugsMav Message
mavlink_pid_t
pidMessage
;
mavlink_pid_t
pidMessage
;
mavlink_slugs_action_t
actionSlugs
;
};
};
#endif // SLUGSPIDCONTROL_H
#endif // SLUGSPIDCONTROL_H
src/ui/SlugsPIDControl.ui
View file @
414a947c
...
@@ -72,14 +72,14 @@
...
@@ -72,14 +72,14 @@
<item
row=
"0"
column=
"1"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dT_P_set"
>
<widget
class=
"QLineEdit"
name=
"dT_P_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dT_P_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"0"
column=
"2"
>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dT_P_get"
>
<widget
class=
"QLineEdit"
name=
"dT_P_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dT_P_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -89,14 +89,14 @@
...
@@ -89,14 +89,14 @@
<item
row=
"1"
column=
"1"
>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dT_I_set"
>
<widget
class=
"QLineEdit"
name=
"dT_I_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dT_I_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"1"
column=
"2"
>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dT_I_get"
>
<widget
class=
"QLineEdit"
name=
"dT_I_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dT_I_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -106,14 +106,14 @@
...
@@ -106,14 +106,14 @@
<item
row=
"2"
column=
"1"
>
<item
row=
"2"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dT_D_set"
>
<widget
class=
"QLineEdit"
name=
"dT_D_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dT_D_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"2"
column=
"2"
>
<item
row=
"2"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dT_D_get"
>
<widget
class=
"QLineEdit"
name=
"dT_D_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dT_D_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -242,14 +242,14 @@
...
@@ -242,14 +242,14 @@
<item
row=
"0"
column=
"1"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dE_P_set"
>
<widget
class=
"QLineEdit"
name=
"dE_P_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dE_P_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"0"
column=
"2"
>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dE_P_get"
>
<widget
class=
"QLineEdit"
name=
"dE_P_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dE_P_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -259,14 +259,14 @@
...
@@ -259,14 +259,14 @@
<item
row=
"1"
column=
"1"
>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dE_I_set"
>
<widget
class=
"QLineEdit"
name=
"dE_I_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dE_I_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"1"
column=
"2"
>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dE_I_get"
>
<widget
class=
"QLineEdit"
name=
"dE_I_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dE_I_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -276,14 +276,14 @@
...
@@ -276,14 +276,14 @@
<item
row=
"2"
column=
"1"
>
<item
row=
"2"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dE_D_set"
>
<widget
class=
"QLineEdit"
name=
"dE_D_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dE_D_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"2"
column=
"2"
>
<item
row=
"2"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dE_D_get"
>
<widget
class=
"QLineEdit"
name=
"dE_D_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dE_D_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -405,14 +405,14 @@
...
@@ -405,14 +405,14 @@
<item
row=
"0"
column=
"1"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dA_P_set"
>
<widget
class=
"QLineEdit"
name=
"dA_P_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dA_P_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"0"
column=
"2"
>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dA_P_get"
>
<widget
class=
"QLineEdit"
name=
"dA_P_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dA_P_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -422,14 +422,14 @@
...
@@ -422,14 +422,14 @@
<item
row=
"1"
column=
"1"
>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dA_I_set"
>
<widget
class=
"QLineEdit"
name=
"dA_I_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dA_I_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"1"
column=
"2"
>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dA_I_get"
>
<widget
class=
"QLineEdit"
name=
"dA_I_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dA_I_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -439,14 +439,14 @@
...
@@ -439,14 +439,14 @@
<item
row=
"2"
column=
"1"
>
<item
row=
"2"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dA_D_set"
>
<widget
class=
"QLineEdit"
name=
"dA_D_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dA_D_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"2"
column=
"2"
>
<item
row=
"2"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dA_D_get"
>
<widget
class=
"QLineEdit"
name=
"dA_D_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dA_D_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -545,14 +545,14 @@
...
@@ -545,14 +545,14 @@
<item
row=
"0"
column=
"1"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_P_set"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_P_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
HELPComm_P_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"0"
column=
"2"
>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_P_get"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_P_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
HELPComm_P_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -562,14 +562,14 @@
...
@@ -562,14 +562,14 @@
<item
row=
"1"
column=
"1"
>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_I_set"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_I_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
HELPComm_I_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"1"
column=
"2"
>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_I_get"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_I_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
HELPComm_I_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -646,14 +646,14 @@
...
@@ -646,14 +646,14 @@
<item
row=
"0"
column=
"1"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_FF_set"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_FF_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
HELPComm_FF_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"0"
column=
"2"
>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_FF_get"
>
<widget
class=
"QLineEdit"
name=
"HELPComm_FF_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
HELPComm_FF_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -775,14 +775,14 @@
...
@@ -775,14 +775,14 @@
<item
row=
"0"
column=
"1"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dR_P_set"
>
<widget
class=
"QLineEdit"
name=
"dR_P_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dR_P_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"0"
column=
"2"
>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dR_P_get"
>
<widget
class=
"QLineEdit"
name=
"dR_P_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dR_P_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -792,14 +792,14 @@
...
@@ -792,14 +792,14 @@
<item
row=
"1"
column=
"1"
>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dR_I_set"
>
<widget
class=
"QLineEdit"
name=
"dR_I_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dR_I_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"1"
column=
"2"
>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dR_I_get"
>
<widget
class=
"QLineEdit"
name=
"dR_I_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dR_I_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -809,14 +809,14 @@
...
@@ -809,14 +809,14 @@
<item
row=
"2"
column=
"1"
>
<item
row=
"2"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"dR_D_set"
>
<widget
class=
"QLineEdit"
name=
"dR_D_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dR_D_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"2"
column=
"2"
>
<item
row=
"2"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"dR_D_get"
>
<widget
class=
"QLineEdit"
name=
"dR_D_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
dR_D_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -910,14 +910,14 @@
...
@@ -910,14 +910,14 @@
<item
row=
"0"
column=
"1"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLineEdit"
name=
"P2dT_FF_set"
>
<widget
class=
"QLineEdit"
name=
"P2dT_FF_set"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
P2dT_FF_set
</string>
<string>
0.0
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
<item
row=
"0"
column=
"2"
>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLineEdit"
name=
"P2dT_FF_get"
>
<widget
class=
"QLineEdit"
name=
"P2dT_FF_get"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
P2dT_FF_get
</string>
<string>
0.0
</string>
</property>
</property>
<property
name=
"readOnly"
>
<property
name=
"readOnly"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
...
src/ui/SlugsVideoCamControl.h
View file @
414a947c
...
@@ -23,13 +23,7 @@ public:
...
@@ -23,13 +23,7 @@ public:
protected:
protected:
virtual
void
mousePressEvent
(
QMouseEvent
*
event
);
virtual
void
mousePressEvent
(
QMouseEvent
*
event
);
virtual
void
mouseReleaseEvent
(
QMouseEvent
*
event
);
virtual
void
mouseReleaseEvent
(
QMouseEvent
*
event
);
//void mouseMoveEvent(QMouseEvent* event);
void
mouseMoveEvent
(
QMouseEvent
*
event
);
void
mouseMoveEvent
(
QMouseEvent
*
event
);
// virtual void wheelEvent(QWheelEvent* event);
//virtual void resizeEvent(QResizeEvent* event);
private:
private:
Ui
::
SlugsVideoCamControl
*
ui
;
Ui
::
SlugsVideoCamControl
*
ui
;
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment