Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • authierj/dfall-system
1 result
Show changes
Commits on Source (425)
Showing
with 5947 additions and 456 deletions
pps_ws/build/
pps_ws/devel/
dfall_ws/build/
dfall_ws/devel/
pps_ws/src/d_fall_pps/lib/vicon/
pps_ws/src/d_fall_pps/include/DataStreamClient.h
dfall_ws/src/dfall_pkg/lib/vicon/
dfall_ws/src/dfall_pkg/include/DataStreamClient.h
dfall_ws/src/dfall_pkg/include/IDataStreamClientBase.h
dfall_ws/src/CMakeLists.txt
# Qt Project files with user preferences
*.pro.user
*.pro.user.*
*.pyc
*.orig
......@@ -11,4 +17,25 @@ pps_ws/src/d_fall_pps/include/DataStreamClient.h
TAGS
build-*
Crazyflie.db
# For LaTeX files in the wiki
wiki/latex/*
!wiki/latex/*.tex
# NOTES:
# > To keep track of configuration-type files that
# are part of the repository, BUT for whcih
# changes are NOT tracked.
# > These files are "skipped" from tracking using
# the following syntax:
# >> git update-index --skip-worktree <FILENAME>
# > The files that should be "skipped" are:
# >> dfall_ws/src/dfall_pkg/launch/Config.sh
# >> dfall_ws/src/dfall_pkg/param/Crazyflie.db
# > To return these files to normal tracking use
# the following syntax:
# >> git update-index --no-skip-worktree <FILENAME>
# > "Skipping" is a setting local to your copy of the
# repository because ".git ignoring" a file already
# in the repository does NOT stop changes from being
# tracked
The repository this patch was done from is this one:
# Instructions for Applying Firmware Patches
The repository that these patches are applicable for is:<br>
https://github.com/bitcraze/crazyflie-firmware
And the hash from the exact commit we pulled from:
However, it is easiest to locate the official realease versions of the firmware from here:<br>
https://github.com/bitcraze/crazyflie-release/releases
f4d21213d7ce37d7ed7338fad0f9a94a96cec191
The complete instructions for applying the patch are given separately for each firmware version (currently only one firmware version).
To apply the patch, just write the following commands:
`git clone https://github.com/bitcraze/crazyflie-firmware.git`<br>
`cd crazyflie-firmware`<br>
`git submodule init && git submodule update`<br>
`git checkout f4d21213d7ce37d7ed7338fad0f9a94a96cec191`<br>
`git apply <folder_to_D-FaLL-System_repository>/crazyflie_firmware/firmware_modifications.patch`<br>
Now the repository is ready to compile. To do it, first make sure that you have
installed the toolchain. To install it:<br>
## Install Compilation Toolchain
For compilation on Ubuntu 18.04, the toolchain is installed with the following commands:<br>
`sudo apt install gcc-arm-none-eabi`<br>
For compilation on Ubuntu 16.04, the toolchain is installed with the following commands:<br>
`sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa`<br>
`sudo apt-get update`<br>
`sudo apt-get install libnewlib-arm-none-eabi`<br>
Then, in the `crazyflie-firmware` folder where you applied the patch, do:<br>
`make PLATFORM=CF2`
## Firware Version 2020-02
The hash of the exact commit to which this patch applies is:<br>
`e27cd170b7eb8be7ed1cbbc9f5622b469d335d97`<br>
As commited on Mon Feb 3 15:04:52 2020 +0100
To apply the patch, use the following sequence of commands:
**Step 1:** Clone the repository and checkout the appropriate commit:<br>
`git clone --recursive https://github.com/bitcraze/crazyflie-firmware.git`<br>
`cd crazyflie-firmware`<br>
`git checkout e27cd170b7eb8be7ed1cbbc9f5622b469d335d97`<br>
Note that it is also possible to checkout this commit using the commit tag, i.e., using `git checkout 2020.02`
**Step 2:** Apply the patch:<br>
`git apply <folder_to_dfall-system_repository>/crazyflie_firmware/crazyflie-firmware-version-2020-20/firmware_modifications_for_version_2020-20.patch`<br>
Now the repository is ready to compile. To do this, first make sure that you have
installed the necessary toolchain as described above ([Install Compilation Toolchain](#install-compilation-toolchain)).
**Step 3:** In the `crazyflie-firmware` folder where you applied the patch, compile the firmware using the following command:<br>
`make PLATFORM=cf2`
If everything is successful, you will see something like this:<br>
<img src="./../pps_wiki/pics/success_building.png" style="width: 400px;"/> <br><br>
<img src="success_building_for_version_2020-02.png" style="width: 400px;"/> <br><br>
This should have created the binary file `cf2.bin`.
**Step 4:** upload the binary to the crazyflie processor by following the instructions given here:<br>
https://www.bitcraze.io/documentation/tutorials/getting-started-with-crazyflie-2-x/#update-fw<br>
Instructions are also given in the wiki of this repository under:
`/wiki/setup.md#firmware`
Now the binary file cf2.bin has been created, and can be directly uploaded to
the crazyflie
The pre-compiled binary files are already included in this repository. To update the firmware of just the main processor, select the file:
`<folder_to_dfall-system_repository>/crazyflie_firmware/crazyflie-firmware-version-2020-02/cf2-2020.02_withDfallPatch.bin`<br>
To update the firmware of both the main processor and the nrf processor, select the file:<br>
`<folder_to_dfall-system_repository>/crazyflie_firmware/crazyflie-firmware-version-2020-02/firmware-cf2-2020.02_withDfallPatch.zip`<br>
\ No newline at end of file
File added
diff --git a/src/modules/interface/attitude_controller.h b/src/modules/interface/attitude_controller.h
index fe25dc0..fd69bdc 100644
--- a/src/modules/interface/attitude_controller.h
+++ b/src/modules/interface/attitude_controller.h
@@ -63,6 +63,11 @@ void attitudeControllerResetRollAttitudePID(void);
*/
void attitudeControllerResetPitchAttitudePID(void);
+/**
+ * Reset controller yaw attitude PID
+ */
+void attitudeControllerResetYawAttitudePID(void);
+
/**
* Reset controller roll, pitch and yaw PID's.
*/
diff --git a/src/modules/interface/stabilizer_types.h b/src/modules/interface/stabilizer_types.h
index fc3e378..c51fdbd 100644
--- a/src/modules/interface/stabilizer_types.h
+++ b/src/modules/interface/stabilizer_types.h
@@ -159,6 +159,10 @@ typedef struct control_s {
int16_t pitch;
int16_t yaw;
float thrust;
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
} control_t;
typedef enum mode_e {
@@ -174,11 +178,17 @@ typedef struct setpoint_s {
attitude_t attitudeRate; // deg/s
quaternion_t attitudeQuaternion;
float thrust;
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
point_t position; // m
velocity_t velocity; // m/s
acc_t acceleration; // m/s^2
bool velocity_body; // true if velocity is given in body frame; false if velocity is given in world frame
+ bool useDfallAdjustmentsToControllerPID;
+
struct {
stab_mode_t x;
stab_mode_t y;
diff --git a/src/modules/src/attitude_pid_controller.c b/src/modules/src/attitude_pid_controller.c
index b7d707e..bcb02bc 100644
--- a/src/modules/src/attitude_pid_controller.c
+++ b/src/modules/src/attitude_pid_controller.c
@@ -145,6 +145,11 @@ void attitudeControllerResetPitchAttitudePID(void)
pidReset(&pidPitch);
}
+void attitudeControllerResetYawAttitudePID(void)
+{
+ pidReset(&pidYaw);
+}
+
void attitudeControllerResetAllPID(void)
{
pidReset(&pidRoll);
diff --git a/src/modules/src/controller_pid.c b/src/modules/src/controller_pid.c
index f4ecb75..673b5cc 100644
--- a/src/modules/src/controller_pid.c
+++ b/src/modules/src/controller_pid.c
@@ -132,6 +132,9 @@ void controllerPid(control_t *control, setpoint_t *setpoint,
control->thrust = actuatorThrust;
}
+ // The following "if (control->thrust == 0)" block is commented
+ // out because it is replaced with what follows after.
+ /*
if (control->thrust == 0)
{
control->thrust = 0;
@@ -150,6 +153,92 @@ void controllerPid(control_t *control, setpoint_t *setpoint,
// Reset the calculated YAW angle for rate control
attitudeDesired.yaw = state->attitude.yaw;
}
+ */
+
+ // The following "if:then:else" statements is used to
+ // specify the "control->cmd{1,2,3,4}" depending on
+ // the boolean:
+ // >> "setpoint->useDfallAdjustmentsToControllerPID"
+ if (setpoint->useDfallAdjustmentsToControllerPID)
+ {
+ // Set the {roll,pitch,yaw} commands to zero
+ // if indicated by the respective mode
+ if (setpoint->mode.roll == modeDisable)
+ {
+ control->roll = 0;
+ cmd_roll = 0.0;
+ }
+ if (setpoint->mode.pitch == modeDisable)
+ {
+ control->pitch = 0;
+ cmd_pitch = 0.0;
+ }
+ if (setpoint->mode.yaw == modeDisable)
+ {
+ control->yaw = 0;
+ cmd_yaw = 0.0;
+ }
+ // Apply the per-motor commands differently
+ // depending on the Z-controller mode
+ if (setpoint->mode.z == modeDisable)
+ {
+ // Copy across the per motor commands
+ control->cmd1 = setpoint->cmd1;
+ control->cmd2 = setpoint->cmd2;
+ control->cmd3 = setpoint->cmd3;
+ control->cmd4 = setpoint->cmd4;
+ }
+ else
+ {
+ // Add the setpoints on top of the
+ // "control thrust" computed by the
+ // PID controllers above
+ control->cmd1 = setpoint->cmd1 + control->thrust;
+ control->cmd2 = setpoint->cmd2 + control->thrust;
+ control->cmd3 = setpoint->cmd3 + control->thrust;
+ control->cmd4 = setpoint->cmd4 + control->thrust;
+ }
+ }
+ // Otherwise, "setpoint->useDfallAdjustmentsToControllerPID == false"
+ else
+ {
+ // Put the thrust value onto each motor
+ control->cmd1 = control->thrust;
+ control->cmd2 = control->thrust;
+ control->cmd3 = control->thrust;
+ control->cmd4 = control->thrust;
+ }
+
+ // If all control commands are zero, i.e., if:
+ // >> "control->cmd{1,2,3,4}==0"
+ // then set all commands to zero and to reset
+ // all PIDs.
+ bool isZeroThrust = ((control->cmd1 == 0 && control->cmd2 == 0 && control->cmd3 == 0 && control->cmd4 == 0));
+ if (isZeroThrust)
+ {
+ // Set all commands to zero
+ control->cmd1 = 0;
+ control->cmd2 = 0;
+ control->cmd3 = 0;
+ control->cmd4 = 0;
+ control->thrust = 0;
+ control->roll = 0;
+ control->pitch = 0;
+ control->yaw = 0;
+
+ // Reset all PIDs
+ attitudeControllerResetAllPID();
+ positionControllerResetAllPID();
+
+ // Reset the calculated YAW angle for rate control
+ attitudeDesired.yaw = state->attitude.yaw;
+
+ // Update also the log variables to reflect this
+ cmd_thrust = 0.0;
+ cmd_roll = 0.0;
+ cmd_pitch = 0.0;
+ cmd_yaw = 0.0;
+ }
}
diff --git a/src/modules/src/crtp_commander_generic.c b/src/modules/src/crtp_commander_generic.c
index 1662fe4..f6931a4 100644
--- a/src/modules/src/crtp_commander_generic.c
+++ b/src/modules/src/crtp_commander_generic.c
@@ -71,6 +71,7 @@ enum packet_type {
hoverType = 5,
fullStateType = 6,
positionType = 7,
+ dfallType = 8,
};
/* ---===== 2 - Decoding functions =====--- */
@@ -112,6 +113,9 @@ static void velocityDecoder(setpoint_t *setpoint, uint8_t type, const void *data
setpoint->mode.yaw = modeVelocity;
setpoint->attitudeRate.yaw = -values->yawrate;
+
+ // Turn off the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = false;
}
/* zDistanceDecoder
@@ -145,6 +149,9 @@ static void zDistanceDecoder(setpoint_t *setpoint, uint8_t type, const void *dat
setpoint->attitude.roll = values->roll;
setpoint->attitude.pitch = values->pitch;
+
+ // Turn off the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = false;
}
/* cppmEmuDecoder
@@ -230,6 +237,9 @@ static void cppmEmuDecoder(setpoint_t *setpoint, uint8_t type, const void *data,
{
setpoint->thrust = 0;
}
+
+ // Turn off the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = false;
}
/* altHoldDecoder
@@ -263,6 +273,9 @@ static void altHoldDecoder(setpoint_t *setpoint, uint8_t type, const void *data,
setpoint->attitude.roll = values->roll;
setpoint->attitude.pitch = values->pitch;
+
+ // Turn off the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = false;
}
/* hoverDecoder
@@ -294,6 +307,9 @@ static void hoverDecoder(setpoint_t *setpoint, uint8_t type, const void *data, s
setpoint->velocity.y = values->vy;
setpoint->velocity_body = true;
+
+ // Turn off the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = false;
}
struct fullStatePacket_s {
@@ -338,6 +354,9 @@ static void fullStateDecoder(setpoint_t *setpoint, uint8_t type, const void *dat
setpoint->mode.roll = modeDisable;
setpoint->mode.pitch = modeDisable;
setpoint->mode.yaw = modeDisable;
+
+ // Turn off the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = false;
}
/* positionDecoder
@@ -365,6 +384,313 @@ static void positionDecoder(setpoint_t *setpoint, uint8_t type, const void *data
setpoint->mode.yaw = modeAbs;
setpoint->attitude.yaw = values->yaw;
+
+ // Turn off the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = false;
+}
+
+/* dfall mode decoder
+ * set the mode of the onboard {x,y,z,roll,pitch,yaw}
+ * controllers based on the mode specification
+ * contained in the packet. A separate mode is
+ * specified for each of the four independent
+ * coordinates of {x,y,z,yaw}
+ */
+
+#define DFALL_CONTROLLER_MODE_OFF 0
+#define DFALL_CONTROLLER_MODE_ANGULAR_RATE 1
+#define DFALL_CONTROLLER_MODE_ANGLE 2
+#define DFALL_CONTROLLER_MODE_VELOCITY 3
+#define DFALL_CONTROLLER_MODE_POSITION 4
+
+struct dfallPacket_s {
+ uint16_t controllerModes;
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
+ float xControllerSetpoint;
+ float yControllerSetpoint;
+ float zControllerSetpoint;
+ float yawControllerSetpoint;
+} __attribute__((packed));
+
+static void dfallDecoder(setpoint_t *setpoint, uint8_t type, const void *data, size_t datalen)
+{
+ const struct dfallPacket_s *values = data;
+ ASSERT(datalen == sizeof(struct dfallPacket_s));
+
+ // DECODE THE 16-BIT INTEGER THAT ENCODES
+ // THE REQUESTED {x,y,z,yaw} CONTROLLER MODES
+ // > Each mode is encoded using 3 bits, stacked together as follows:
+ // ---------------------------------------------------------------
+ // |BIT | 15 14 13 12 | 11 10 9 | 8 7 6 | 5 4 3 | 2 1 0 |
+ // |DESC. | free bits | yaw_mode | z_mode | y_mode | x_mode |
+ // ---------------------------------------------------------------
+
+ uint16_t mode_selector_bits = 7;
+
+ // EXTRACT THE MODE FOR EACH CONTROLLER
+ uint8_t x_controller_mode = (values->controllerModes >> 0) & mode_selector_bits;
+ uint8_t y_controller_mode = (values->controllerModes >> 3) & mode_selector_bits;
+ uint8_t z_controller_mode = (values->controllerModes >> 6) & mode_selector_bits;
+ uint8_t yaw_controller_mode = (values->controllerModes >> 9) & mode_selector_bits;
+
+ // INITIALISE A BOOLEAN FOR TRACKING IF ANY
+ // OF THE CONTROLLER MODES ARE INVALID
+ bool invalid_controller_mode_requested = false;
+
+ // PROCESS THE X CONTROLLER
+ switch (x_controller_mode)
+ {
+ case DFALL_CONTROLLER_MODE_ANGULAR_RATE:
+ // Set the modes
+ setpoint->mode.x = modeDisable;
+ setpoint->mode.pitch = modeVelocity;
+ // Set the setpoint
+ setpoint->position.x = 0.0;
+ setpoint->velocity.x = 0.0;
+ setpoint->attitude.pitch = 0.0;
+ setpoint->attitudeRate.pitch = values->xControllerSetpoint;
+ break;
+
+ case DFALL_CONTROLLER_MODE_ANGLE:
+ // Set the modes
+ setpoint->mode.x = modeDisable;
+ setpoint->mode.pitch = modeAbs;
+ // Set the setpoints
+ setpoint->position.x = 0.0;
+ setpoint->velocity.x = 0.0;
+ setpoint->attitude.pitch = values->xControllerSetpoint;
+ setpoint->attitudeRate.pitch = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_VELOCITY:
+ // Set the modes
+ setpoint->mode.x = modeVelocity;
+ setpoint->mode.pitch = modeAbs;
+ // Set the setpoints
+ setpoint->position.x = 0.0;
+ setpoint->velocity.x = values->xControllerSetpoint;
+ setpoint->attitude.pitch = 0.0;
+ setpoint->attitudeRate.pitch = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_POSITION:
+ // Set the modes
+ setpoint->mode.x = modeAbs;
+ setpoint->mode.pitch = modeAbs;
+ // Set the setpoints
+ setpoint->position.x = values->xControllerSetpoint;
+ setpoint->velocity.x = 0.0;
+ setpoint->attitude.pitch = 0.0;
+ setpoint->attitudeRate.pitch = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_OFF:
+ // Set the modes
+ setpoint->mode.x = modeDisable;
+ setpoint->mode.pitch = modeDisable;
+ // Set the setpoints
+ setpoint->position.x = 0.0;
+ setpoint->velocity.x = 0.0;
+ setpoint->attitude.pitch = 0.0;
+ setpoint->attitudeRate.pitch = 0.0;
+ break;
+
+ default:
+ // Set the flag that an invalid mode
+ // was requested
+ invalid_controller_mode_requested = true;
+ break;
+ }
+
+ // PROCESS THE Y CONTROLLER
+ switch (y_controller_mode)
+ {
+ case DFALL_CONTROLLER_MODE_ANGULAR_RATE:
+ // Set the modes
+ setpoint->mode.y = modeDisable;
+ setpoint->mode.roll = modeVelocity;
+ // Set the setpoint
+ setpoint->position.y = 0.0;
+ setpoint->velocity.y = 0.0;
+ setpoint->attitude.roll = 0.0;
+ setpoint->attitudeRate.roll = values->yControllerSetpoint;
+ break;
+
+ case DFALL_CONTROLLER_MODE_ANGLE:
+ // Set the modes
+ setpoint->mode.y = modeDisable;
+ setpoint->mode.roll = modeAbs;
+ // Set the setpoints
+ setpoint->position.y = 0.0;
+ setpoint->velocity.y = 0.0;
+ setpoint->attitude.roll = values->yControllerSetpoint;
+ setpoint->attitudeRate.roll = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_VELOCITY:
+ // Set the modes
+ setpoint->mode.y = modeVelocity;
+ setpoint->mode.roll = modeAbs;
+ // Set the setpoints
+ setpoint->position.y = 0.0;
+ setpoint->velocity.y = values->yControllerSetpoint;
+ setpoint->attitude.roll = 0.0;
+ setpoint->attitudeRate.roll = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_POSITION:
+ // Set the modes
+ setpoint->mode.y = modeAbs;
+ setpoint->mode.roll = modeAbs;
+ // Set the setpoints
+ setpoint->position.y = values->yControllerSetpoint;
+ setpoint->velocity.y = 0.0;
+ setpoint->attitude.roll = 0.0;
+ setpoint->attitudeRate.roll = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_OFF:
+ // Set the modes
+ setpoint->mode.y = modeDisable;
+ setpoint->mode.roll = modeDisable;
+ // Set the setpoints
+ setpoint->position.y = 0.0;
+ setpoint->velocity.y = 0.0;
+ setpoint->attitude.roll = 0.0;
+ setpoint->attitudeRate.roll = 0.0;
+ break;
+
+ default:
+ // Set the flag that an invalid mode
+ // was requested
+ invalid_controller_mode_requested = true;
+ break;
+ }
+
+ // PROCESS THE Z CONTROLLER
+ switch (z_controller_mode)
+ {
+ case DFALL_CONTROLLER_MODE_VELOCITY:
+ // Set the mode
+ setpoint->mode.z = modeVelocity;
+ // Set the setpoints
+ setpoint->position.z = 0.0;
+ setpoint->velocity.z = values->zControllerSetpoint;
+ break;
+
+ case DFALL_CONTROLLER_MODE_POSITION:
+ // Set the mode
+ setpoint->mode.z = modeAbs;
+ // Set the setpoints
+ setpoint->position.z = values->zControllerSetpoint;
+ setpoint->velocity.z = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_OFF:
+ // Set the mode
+ setpoint->mode.z = modeDisable;
+ // Set the setpoints
+ setpoint->position.z = 0.0;
+ setpoint->velocity.z = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_ANGULAR_RATE:
+ case DFALL_CONTROLLER_MODE_ANGLE:
+ default:
+ // Set the flag that an invalid mode
+ // was requested
+ invalid_controller_mode_requested = true;
+ break;
+ }
+
+ // PROCESS THE YAW CONTROLLER
+ switch (yaw_controller_mode)
+ {
+ case DFALL_CONTROLLER_MODE_ANGULAR_RATE:
+ // Set the mode
+ setpoint->mode.yaw = modeVelocity;
+ // Set the setpoint
+ setpoint->attitude.yaw = 0.0;
+ setpoint->attitudeRate.yaw = values->yawControllerSetpoint;
+ break;
+
+ case DFALL_CONTROLLER_MODE_ANGLE:
+ // Set the modes
+ setpoint->mode.yaw = modeAbs;
+ // Set the setpoints
+ setpoint->attitude.roll = values->yawControllerSetpoint;
+ setpoint->attitudeRate.roll = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_OFF:
+ // Set the modes
+ setpoint->mode.yaw = modeDisable;
+ // Set the setpoints
+ setpoint->attitude.yaw = 0.0;
+ setpoint->attitudeRate.yaw = 0.0;
+ break;
+
+ case DFALL_CONTROLLER_MODE_VELOCITY:
+ case DFALL_CONTROLLER_MODE_POSITION:
+ default:
+ // Set the flag that an invalid mode
+ // was requested
+ invalid_controller_mode_requested = true;
+ break;
+ }
+
+ // Set the thrust setpoint to zero
+ setpoint->thrust = 0;
+
+ // Tranfer the per-motor commands from the packet
+ // to the respective setpoints
+ // NOTES:
+ // (1) this is performed regardless of the
+ // "z_controller_mode" because the per motor
+ // commands can be used for correcting steady-
+ // state offsets in {x,y,yaw}.
+ // (2) if the "z_controller_mode" is in "POSITION"
+ // or "VELOCITY" mode, then onboard controllers
+ // will compute the main thurst controler, and
+ // the user is expected to fill in cmd{1,2,3,4}
+ // with only adjustment values.
+ setpoint->cmd1 = limitUint16(values->cmd1);
+ setpoint->cmd2 = limitUint16(values->cmd2);
+ setpoint->cmd3 = limitUint16(values->cmd3);
+ setpoint->cmd4 = limitUint16(values->cmd4);
+
+ // Set everything to off and zero if an invlaid
+ // controller mode was requested
+ if (invalid_controller_mode_requested)
+ {
+ // Set the modes
+ setpoint->mode.x = modeDisable;
+ setpoint->mode.pitch = modeDisable;
+ setpoint->mode.y = modeDisable;
+ setpoint->mode.roll = modeDisable;
+ setpoint->mode.z = modeDisable;
+ setpoint->mode.yaw = modeDisable;
+
+ // Set the setpoints
+ setpoint->position.x = 0.0;
+ setpoint->velocity.x = 0.0;
+ setpoint->attitude.pitch = 0.0;
+ setpoint->attitudeRate.pitch = 0.0;
+ setpoint->position.y = 0.0;
+ setpoint->velocity.y = 0.0;
+ setpoint->attitude.roll = 0.0;
+ setpoint->attitudeRate.roll = 0.0;
+ setpoint->position.z = 0.0;
+ setpoint->velocity.z = 0.0;
+ setpoint->attitude.yaw = 0.0;
+ setpoint->attitudeRate.yaw = 0.0;
+ }
+
+ // Turn on the "dfall mode adjustments"
+ setpoint->useDfallAdjustmentsToControllerPID = true;
}
/* ---===== 3 - packetDecoders array =====--- */
@@ -377,6 +703,7 @@ const static packetDecoder_t packetDecoders[] = {
[hoverType] = hoverDecoder,
[fullStateType] = fullStateDecoder,
[positionType] = positionDecoder,
+ [dfallType] = dfallDecoder,
};
/* Decoder switch */
diff --git a/src/modules/src/power_distribution_stock.c b/src/modules/src/power_distribution_stock.c
index d3b7d8d..072a699 100644
--- a/src/modules/src/power_distribution_stock.c
+++ b/src/modules/src/power_distribution_stock.c
@@ -80,18 +80,18 @@ void powerDistribution(const control_t *control)
#ifdef QUAD_FORMATION_X
int16_t r = control->roll / 2.0f;
int16_t p = control->pitch / 2.0f;
- motorPower.m1 = limitThrust(control->thrust - r + p + control->yaw);
- motorPower.m2 = limitThrust(control->thrust - r - p - control->yaw);
- motorPower.m3 = limitThrust(control->thrust + r - p + control->yaw);
- motorPower.m4 = limitThrust(control->thrust + r + p - control->yaw);
+ motorPower.m1 = limitThrust(control->cmd1 - r + p + control->yaw);
+ motorPower.m2 = limitThrust(control->cmd2 - r - p - control->yaw);
+ motorPower.m3 = limitThrust(control->cmd3 + r - p + control->yaw);
+ motorPower.m4 = limitThrust(control->cmd4 + r + p - control->yaw);
#else // QUAD_FORMATION_NORMAL
- motorPower.m1 = limitThrust(control->thrust + control->pitch +
+ motorPower.m1 = limitThrust(control->cmd1 + control->pitch +
control->yaw);
- motorPower.m2 = limitThrust(control->thrust - control->roll -
+ motorPower.m2 = limitThrust(control->cmd2 - control->roll -
control->yaw);
- motorPower.m3 = limitThrust(control->thrust - control->pitch +
+ motorPower.m3 = limitThrust(control->cmd3 - control->pitch +
control->yaw);
- motorPower.m4 = limitThrust(control->thrust + control->roll -
+ motorPower.m4 = limitThrust(control->cmd4 + control->roll -
control->yaw);
#endif
@@ -117,11 +117,11 @@ PARAM_ADD(PARAM_UINT16, m1, &motorPowerSet.m1)
PARAM_ADD(PARAM_UINT16, m2, &motorPowerSet.m2)
PARAM_ADD(PARAM_UINT16, m3, &motorPowerSet.m3)
PARAM_ADD(PARAM_UINT16, m4, &motorPowerSet.m4)
-PARAM_GROUP_STOP(ring)
+PARAM_GROUP_STOP(motorPowerSet)
LOG_GROUP_START(motor)
-LOG_ADD(LOG_INT32, m4, &motorPower.m4)
LOG_ADD(LOG_INT32, m1, &motorPower.m1)
LOG_ADD(LOG_INT32, m2, &motorPower.m2)
LOG_ADD(LOG_INT32, m3, &motorPower.m3)
+LOG_ADD(LOG_INT32, m4, &motorPower.m4)
LOG_GROUP_STOP(motor)
diff --git a/src/modules/src/stabilizer.c b/src/modules/src/stabilizer.c
index 372ec94..cb4f848 100644
--- a/src/modules/src/stabilizer.c
+++ b/src/modules/src/stabilizer.c
@@ -92,6 +92,10 @@ static struct {
int16_t ax;
int16_t ay;
int16_t az;
+ // attitude - milliradians
+ int16_t roll;
+ int16_t pitch;
+ int16_t yaw;
// compressed quaternion, see quatcompress.h
int32_t quat;
// angular velocity - milliradians / sec
@@ -151,6 +155,11 @@ static void compressState()
stateCompressed.ay = state.acc.y * 9.81f * 1000.0f;
stateCompressed.az = (state.acc.z + 1) * 9.81f * 1000.0f;
+ float const deg2millirad = ((float)M_PI * 1000.0f) / 180.0f;
+ stateCompressed.roll = state.attitude.roll * deg2millirad;
+ stateCompressed.pitch = state.attitude.pitch * deg2millirad;
+ stateCompressed.yaw = state.attitude.yaw * deg2millirad;
+
float const q[4] = {
state.attitudeQuaternion.x,
state.attitudeQuaternion.y,
@@ -158,7 +167,7 @@ static void compressState()
state.attitudeQuaternion.w};
stateCompressed.quat = quatcompress(q);
- float const deg2millirad = ((float)M_PI * 1000.0f) / 180.0f;
+ //float const deg2millirad = ((float)M_PI * 1000.0f) / 180.0f;
stateCompressed.rateRoll = sensorData.gyro.x * deg2millirad;
stateCompressed.ratePitch = -sensorData.gyro.y * deg2millirad;
stateCompressed.rateYaw = sensorData.gyro.z * deg2millirad;
@@ -670,6 +679,10 @@ LOG_ADD(LOG_INT16, ax, &stateCompressed.ax) // acceleration - mm /
LOG_ADD(LOG_INT16, ay, &stateCompressed.ay)
LOG_ADD(LOG_INT16, az, &stateCompressed.az)
+LOG_ADD(LOG_INT16, roll, &stateCompressed.roll) // attitude - milliradians
+LOG_ADD(LOG_INT16, pitch, &stateCompressed.pitch)
+LOG_ADD(LOG_INT16, yaw, &stateCompressed.yaw)
+
LOG_ADD(LOG_UINT32, quat, &stateCompressed.quat) // compressed quaternion, see quatcompress.h
LOG_ADD(LOG_INT16, rateRoll, &stateCompressed.rateRoll) // angular velocity - milliradians / sec
{"subversion": 2, "release": "2020.02", "fw_platform": "cf2", "version": 1, "files": {"cf2-2020.02_withDfallPatch.bin": {"release": "2020.02", "platform": "cf2", "type": "fw", "target": "stm32", "repository": "crazyflie-firmware"}, "cf2_nrf-2020.02.bin": {"release": "2020.02", "platform": "cf2", "type": "fw", "target": "nrf51", "repository": "crazyflie2-nrf-firmware"}}}
\ No newline at end of file
diff --git a/src/modules/interface/attitude_controller.h b/src/modules/interface/attitude_controller.h
index ad23ef0..f79b7d1 100644
--- a/src/modules/interface/attitude_controller.h
+++ b/src/modules/interface/attitude_controller.h
@@ -63,6 +63,11 @@ void attitudeControllerResetRollAttitudePID(void);
*/
void attitudeControllerResetPitchAttitudePID(void);
+/**
+ * Reset controller yaw attitude PID
+ */
+void attitudeControllerResetYawAttitudePID(void);
+
/**
* Reset controller roll, pitch and yaw PID's.
*/
diff --git a/src/modules/interface/stabilizer_types.h b/src/modules/interface/stabilizer_types.h
index 418cc0b..30d031b 100644
--- a/src/modules/interface/stabilizer_types.h
+++ b/src/modules/interface/stabilizer_types.h
@@ -144,6 +144,10 @@ typedef struct control_s {
int16_t pitch;
int16_t yaw;
float thrust;
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
} control_t;
typedef enum mode_e {
@@ -152,12 +156,24 @@ typedef enum mode_e {
modeVelocity
} stab_mode_t;
+typedef enum pps_mode_e {
+ modeDisabled = 0,
+ modeMotors,
+ modeRate,
+ modeAngle
+} pps_mode_t;
+
typedef struct setpoint_s {
uint32_t timestamp;
attitude_t attitude;
attitude_t attitudeRate;
float thrust;
+ pps_mode_t pps_mode;
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
point_t position;
velocity_t velocity;
bool velocity_body;
diff --git a/src/modules/src/attitude_pid_controller.c b/src/modules/src/attitude_pid_controller.c
index 8b5f4aa..f16288f 100644
--- a/src/modules/src/attitude_pid_controller.c
+++ b/src/modules/src/attitude_pid_controller.c
@@ -142,9 +142,14 @@ void attitudeControllerResetRollAttitudePID(void)
void attitudeControllerResetPitchAttitudePID(void)
{
- pidReset(&pidRoll);
+ pidReset(&pidPitch);
}
+void attitudeControllerResetYawAttitudePID(void)
+{
+ pidReset(&pidYaw);
+}
+
void attitudeControllerResetAllPID(void)
{
pidReset(&pidRoll);
diff --git a/src/modules/src/controller_pid.c b/src/modules/src/controller_pid.c
index 0e5e62d..516315a 100644
--- a/src/modules/src/controller_pid.c
+++ b/src/modules/src/controller_pid.c
@@ -51,9 +51,13 @@ void stateController(control_t *control, setpoint_t *setpoint,
}
if (RATE_DO_EXECUTE(POSITION_RATE, tick)) {
- positionController(&actuatorThrust, &attitudeDesired, setpoint, state);
+ if(setpoint->pps_mode != modeMotors && setpoint->pps_mode != modeRate && setpoint->pps_mode != modeAngle)
+ {
+ positionController(&actuatorThrust, &attitudeDesired, setpoint, state);
+ }
}
+
if (RATE_DO_EXECUTE(ATTITUDE_RATE, tick)) {
// Switch between manual and automatic position control
if (setpoint->mode.z == modeDisable) {
@@ -63,7 +67,7 @@ void stateController(control_t *control, setpoint_t *setpoint,
attitudeDesired.roll = setpoint->attitude.roll;
attitudeDesired.pitch = setpoint->attitude.pitch;
}
-
+ /* if everything is modeVelocity, skip this */
attitudeControllerCorrectAttitudePID(state->attitude.roll, state->attitude.pitch, state->attitude.yaw,
attitudeDesired.roll, attitudeDesired.pitch, attitudeDesired.yaw,
&rateDesired.roll, &rateDesired.pitch, &rateDesired.yaw);
@@ -80,6 +84,12 @@ void stateController(control_t *control, setpoint_t *setpoint,
attitudeControllerResetPitchAttitudePID();
}
+ //added for PPSSafeController to make the Onboard Controller using the external YawRate. Pure speed controller, no position/500 small steps
+ if (setpoint->mode.yaw == modeVelocity) {
+ rateDesired.yaw = (-1) * setpoint->attitudeRate.yaw;
+ attitudeControllerResetYawAttitudePID();
+ }
+
// TODO: Investigate possibility to subtract gyro drift.
attitudeControllerCorrectRatePID(sensors->gyro.x, -sensors->gyro.y, sensors->gyro.z,
rateDesired.roll, rateDesired.pitch, rateDesired.yaw);
@@ -100,19 +110,76 @@ void stateController(control_t *control, setpoint_t *setpoint,
control->thrust = actuatorThrust;
}
- if (control->thrust == 0)
+ if(setpoint->pps_mode == modeMotors)
{
- control->thrust = 0;
- control->roll = 0;
- control->pitch = 0;
- control->yaw = 0;
-
- attitudeControllerResetAllPID();
- positionControllerResetAllPID();
-
- // Reset the calculated YAW angle for rate control
- attitudeDesired.yaw = state->attitude.yaw;
+ control->roll = 0;
+ control->pitch = 0;
+ control->yaw = 0;
+ control->cmd1 = setpoint->cmd1;
+ control->cmd2 = setpoint->cmd2;
+ control->cmd3 = setpoint->cmd3;
+ control->cmd4 = setpoint->cmd4;
+ if ((control->cmd1 == 0 && control->cmd2 == 0 && control->cmd3 == 0 && control->cmd4 == 0))
+ {
+ control->cmd1 = 0;
+ control->cmd2 = 0;
+ control->cmd3 = 0;
+ control->cmd4 = 0;
+ control->roll = 0;
+ control->pitch = 0;
+ control->yaw = 0;
+
+ attitudeControllerResetAllPID();
+ positionControllerResetAllPID();
+
+ // Reset the calculated YAW angle for rate control
+ attitudeDesired.yaw = state->attitude.yaw;
+ }
+ }
+ else if(setpoint->pps_mode == modeRate || setpoint->pps_mode == modeAngle)
+ {
+ control->cmd1 = setpoint->cmd1;
+ control->cmd2 = setpoint->cmd2;
+ control->cmd3 = setpoint->cmd3;
+ control->cmd4 = setpoint->cmd4;
+ if ((control->cmd1 == 0 && control->cmd2 == 0 && control->cmd3 == 0 && control->cmd4 == 0))
+ {
+ control->cmd1 = 0;
+ control->cmd2 = 0;
+ control->cmd3 = 0;
+ control->cmd4 = 0;
+ control->roll = 0;
+ control->pitch = 0;
+ control->yaw = 0;
+
+ attitudeControllerResetAllPID();
+ positionControllerResetAllPID();
+
+ // Reset the calculated YAW angle for rate control
+ attitudeDesired.yaw = state->attitude.yaw;
+ }
}
+ else /* pps_mode == modeDisabled */
+ {
+ control->cmd1 = control->thrust;
+ control->cmd2 = control->thrust;
+ control->cmd3 = control->thrust;
+ control->cmd4 = control->thrust;
+ if (control->thrust == 0)
+ {
+ control->thrust = 0;
+ control->roll = 0;
+ control->pitch = 0;
+ control->yaw = 0;
+
+ attitudeControllerResetAllPID();
+ positionControllerResetAllPID();
+
+ // Reset the calculated YAW angle for rate control
+ attitudeDesired.yaw = state->attitude.yaw;
+ }
+ }
+
}
diff --git a/src/modules/src/crtp_commander_generic.c b/src/modules/src/crtp_commander_generic.c
index 993dead..64447d6 100644
--- a/src/modules/src/crtp_commander_generic.c
+++ b/src/modules/src/crtp_commander_generic.c
@@ -34,6 +34,8 @@
#include "num.h"
#include "FreeRTOS.h"
+/* #include "motors.h" */
+
/* The generic commander format contains a packet type and data that has to be
* decoded into a setpoint_t structure. The aim is to make it future-proof
* by easily allowing the addition of new packets for future use cases.
@@ -67,6 +69,9 @@ enum packet_type {
cppmEmuType = 3,
altHoldType = 4,
hoverType = 5,
+ PPSMotorsType = 6,
+ PPSRateType = 7,
+ PPSAngleType = 8,
};
/* ---===== 2 - Decoding functions =====--- */
@@ -292,6 +297,152 @@ static void hoverDecoder(setpoint_t *setpoint, uint8_t type, const void *data, s
setpoint->velocity_body = true;
}
+struct PPSMotorsPacket_s {
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
+} __attribute__((packed));
+
+static void PPSMotorsDecoder(setpoint_t *setpoint, uint8_t type, const void *data, size_t datalen)
+{
+ const struct PPSMotorsPacket_s *values = data;
+ ASSERT(datalen == sizeof(struct PPSMotorsPacket_s));
+
+ /* we dont use position controller onboard */
+ setpoint->mode.x = modeDisable;
+ setpoint->mode.y = modeDisable;
+ setpoint->mode.z = modeDisable;
+
+ setpoint->thrust = 0;
+ setpoint->position.x = 0;
+ setpoint->position.y = 0;
+ setpoint->position.z = 0;
+ setpoint->velocity.x = 0;
+ setpoint->velocity.y = 0;
+ setpoint->velocity.z = 0;
+
+ /* we dont use rate controller onboard either */
+ setpoint->mode.roll = modeDisable;
+ setpoint->mode.pitch = modeDisable;
+ setpoint->mode.yaw = modeDisable;
+
+ setpoint->attitude.roll = 0;
+ setpoint->attitude.pitch = 0;
+ setpoint->attitude.yaw = 0;
+ setpoint->attitudeRate.roll = 0;
+ setpoint->attitudeRate.pitch = 0;
+ setpoint->attitudeRate.yaw = 0;
+
+ /* update cmds */
+
+ setpoint->cmd1 = limitUint16(values->cmd1);
+ setpoint->cmd2 = limitUint16(values->cmd2);
+ setpoint->cmd3 = limitUint16(values->cmd3);
+ setpoint->cmd4 = limitUint16(values->cmd4);
+
+ setpoint->pps_mode = modeMotors;
+}
+
+struct PPSRatePacket_s {
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
+ float roll_rate;
+ float pitch_rate;
+ float yaw_rate;
+} __attribute__((packed));
+
+static void PPSRateDecoder(setpoint_t *setpoint, uint8_t type, const void *data, size_t datalen)
+{
+ const struct PPSRatePacket_s *values = data;
+ ASSERT(datalen == sizeof(struct PPSRatePacket_s));
+
+ /* we dont use position controller onboard */
+ setpoint->mode.x = modeDisable;
+ setpoint->mode.y = modeDisable;
+ setpoint->mode.z = modeDisable;
+
+ setpoint->thrust = 0;
+ setpoint->position.x = 0;
+ setpoint->position.y = 0;
+ setpoint->position.z = 0;
+ setpoint->velocity.x = 0;
+ setpoint->velocity.y = 0;
+ setpoint->velocity.z = 0;
+
+ /* we use rate controller onboard either */
+ setpoint->mode.roll = modeVelocity;
+ setpoint->mode.pitch = modeVelocity;
+ setpoint->mode.yaw = modeVelocity;
+
+ setpoint->attitude.roll = 0;
+ setpoint->attitude.pitch = 0;
+ setpoint->attitude.yaw = 0;
+ setpoint->attitudeRate.roll = values->roll_rate;
+ setpoint->attitudeRate.pitch = values->pitch_rate;
+ setpoint->attitudeRate.yaw = values->yaw_rate;
+
+ /* update cmds */
+
+ setpoint->cmd1 = limitUint16(values->cmd1);
+ setpoint->cmd2 = limitUint16(values->cmd2);
+ setpoint->cmd3 = limitUint16(values->cmd3);
+ setpoint->cmd4 = limitUint16(values->cmd4);
+
+ setpoint->pps_mode = modeRate;
+}
+
+struct PPSAnglePacket_s {
+ uint16_t cmd1;
+ uint16_t cmd2;
+ uint16_t cmd3;
+ uint16_t cmd4;
+ float roll;
+ float pitch;
+ float yaw;
+} __attribute__((packed));
+
+static void PPSAngleDecoder(setpoint_t *setpoint, uint8_t type, const void *data, size_t datalen)
+{
+ const struct PPSAnglePacket_s *values = data;
+ ASSERT(datalen == sizeof(struct PPSRatePacket_s));
+
+ /* we dont use position controller onboard */
+ setpoint->mode.x = modeDisable;
+ setpoint->mode.y = modeDisable;
+ setpoint->mode.z = modeDisable;
+
+ setpoint->thrust = 0;
+ setpoint->position.x = 0;
+ setpoint->position.y = 0;
+ setpoint->position.z = 0;
+ setpoint->velocity.x = 0;
+ setpoint->velocity.y = 0;
+ setpoint->velocity.z = 0;
+
+ /* we use position angle controller onboard */
+ setpoint->mode.roll = modeAbs;
+ setpoint->mode.pitch = modeAbs;
+ setpoint->mode.yaw = modeAbs;
+
+ setpoint->attitude.roll = values->roll;
+ setpoint->attitude.pitch = values->pitch;
+ setpoint->attitude.yaw = values->yaw;
+ setpoint->attitudeRate.roll = 0;
+ setpoint->attitudeRate.pitch = 0;
+ setpoint->attitudeRate.yaw = 0;
+
+ /* update cmds */
+ setpoint->cmd1 = limitUint16(values->cmd1);
+ setpoint->cmd2 = limitUint16(values->cmd2);
+ setpoint->cmd3 = limitUint16(values->cmd3);
+ setpoint->cmd4 = limitUint16(values->cmd4);
+
+ setpoint->pps_mode = modeAngle;
+}
+
/* ---===== 3 - packetDecoders array =====--- */
const static packetDecoder_t packetDecoders[] = {
[stopType] = stopDecoder,
@@ -300,6 +451,9 @@ const static packetDecoder_t packetDecoders[] = {
[cppmEmuType] = cppmEmuDecoder,
[altHoldType] = altHoldDecoder,
[hoverType] = hoverDecoder,
+ [PPSMotorsType] = PPSMotorsDecoder,
+ [PPSRateType] = PPSRateDecoder,
+ [PPSAngleType] = PPSAngleDecoder,
};
/* Decoder switch */
diff --git a/src/modules/src/power_distribution_stock.c b/src/modules/src/power_distribution_stock.c
index 0e66c0b..79d5f2c 100644
--- a/src/modules/src/power_distribution_stock.c
+++ b/src/modules/src/power_distribution_stock.c
@@ -76,18 +76,19 @@ void powerDistribution(const control_t *control)
#ifdef QUAD_FORMATION_X
int16_t r = control->roll / 2.0f;
int16_t p = control->pitch / 2.0f;
- motorPower.m1 = limitThrust(control->thrust - r + p + control->yaw);
- motorPower.m2 = limitThrust(control->thrust - r - p - control->yaw);
- motorPower.m3 = limitThrust(control->thrust + r - p + control->yaw);
- motorPower.m4 = limitThrust(control->thrust + r + p - control->yaw);
+ motorPower.m1 = limitThrust(control->cmd1 - r + p + control->yaw);
+ motorPower.m2 = limitThrust(control->cmd2 - r - p - control->yaw);
+ motorPower.m3 = limitThrust(control->cmd3 + r - p + control->yaw);
+ motorPower.m4 = limitThrust(control->cmd4 + r + p - control->yaw);
+
#else // QUAD_FORMATION_NORMAL
- motorPower.m1 = limitThrust(control->thrust + control->pitch +
+ motorPower.m1 = limitThrust(control->cmd1 + control->pitch +
control->yaw);
- motorPower.m2 = limitThrust(control->thrust - control->roll -
+ motorPower.m2 = limitThrust(control->cmd2 - control->roll -
control->yaw);
- motorPower.m3 = limitThrust(control->thrust - control->pitch +
+ motorPower.m3 = limitThrust(control->cmd3 - control->pitch +
control->yaw);
- motorPower.m4 = limitThrust(control->thrust + control->roll -
+ motorPower.m4 = limitThrust(control->cmd4 + control->roll -
control->yaw);
#endif
diff --git a/src/modules/src/stabilizer.c b/src/modules/src/stabilizer.c
index eccc709..6b9fcc3 100644
--- a/src/modules/src/stabilizer.c
+++ b/src/modules/src/stabilizer.c
@@ -130,7 +130,6 @@ static void stabilizerTask(void* param)
commanderGetSetpoint(&setpoint, &state);
sitAwUpdateSetpoint(&setpoint, &sensorData, &state);
-
stateController(&control, &setpoint, &sensorData, &state, tick);
checkEmergencyStopTimeout();
crazyflie-firmware/success_building_for_version_2020-02.png

69.8 KiB

File moved
cmake_minimum_required(VERSION 3.0)
project(dfall_pkg)
## Add support for C++11, supported in ROS Kinetic and newer
# add_definitions(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
message_generation
roscpp
rospy
std_msgs
genmsg
rosbag
roslib
)
# CHECK IF THE EIGEN PACKAGE IS AVAILABLE
find_package (Eigen3 3.3 NO_MODULE)
# CHECK IF THE QT PACKAGES ARE AVAILABLE
find_package(Qt5Widgets CONFIG)
find_package(Qt5Core CONFIG)
find_package(Qt5Gui CONFIG)
find_package(Qt5Svg CONFIG)
find_package(Qt5Charts CONFIG)
# VICON DATASTREAM SDK PACKAGE
# Ensure that the cache variable where the result would be stored is clear
message(STATUS "NOTE: Prior to being unset: VICON_LIBRARY = " ${VICON_LIBRARY})
unset(VICON_LIBRARY CACHE)
message(STATUS "NOTE: After being unset: VICON_LIBRARY = " ${VICON_LIBRARY})
# Find the Vicon Data Stream SDK Pacakge
find_library(VICON_LIBRARY ViconDataStreamSDK_CPP PATHS lib/vicon NO_DEFAULT_PATH)
message(STATUS "NOTE: After calling find_library(): VICON_LIBRARY = " ${VICON_LIBRARY})
# Let the user know if the library was found or not
if(VICON_LIBRARY)
message(STATUS "NOTE: the Vicon Data Stream SDK library was found")
else()
message(STATUS "NOTE: the Vicon Data Stream SDK library was NOT found")
endif()
# LET THE USER KNOW IF THE EIGEN PACKAGE WAS FOUND OR NOT
if(Eigen3_FOUND)
message(STATUS "NOTE: the Eigen3 package was found")
else()
message(STATUS "NOTE: the Eigen3 package was NOT found")
endif()
# LET THE USER KNOW IF THE QT PACKAGES WERE FOUND OR NOT
if(Qt5Widgets_FOUND)
message(STATUS "NOTE: the Qt5 Widgets package was found")
else()
message(STATUS "NOTE: the Qt5 Widgets package was NOT found")
endif()
if(Qt5Core_FOUND)
message(STATUS "NOTE: the Qt5 Core package was found")
else()
message(STATUS "NOTE: the Qt5 Core package was NOT found")
endif()
if(Qt5Gui_FOUND)
message(STATUS "NOTE: the Qt5 Gui package was found")
else()
message(STATUS "NOTE: the Qt5 Gui package was NOT found")
endif()
if(Qt5Svg_FOUND)
message(STATUS "NOTE: the Qt5 Svg package was found")
else()
message(STATUS "NOTE: the Qt5 Svg package was NOT found")
endif()
if(Qt5Charts_FOUND)
message(STATUS "NOTE: the Qt5 Charts package was found")
else()
message(STATUS "NOTE: the Qt5 Charts package was NOT found")
endif()
if(Qt5Widgets_FOUND AND Qt5Core_FOUND AND Qt5Gui_FOUND AND Qt5Svg_FOUND AND Qt5Charts_FOUND)
set(Qt5_FOUND TRUE)
else()
set(Qt5_FOUND FALSE)
endif()
if(Qt5_FOUND)
message(STATUS "NOTE: hence compiling Qt GUIs")
else()
message(STATUS "NOTE: hence NOT compiling Qt GUIs")
endif()
if(Qt5_FOUND)
# GUI -- Add precompiler definitions to include ROS things in GUI compilation
add_definitions(-DCATKIN_MAKE)
# GUI -- Things needed for Qt wrapper build process
set(CMAKE_INCLUDE_CURRENT_DIR ON)
set(CMAKE_AUTOMOC ON)
endif()
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
if(Qt5_FOUND)
# GUI -- Add src, includes, and resources
set(SYSTEM_CONFIG_GUI_LIB_PATH_SRC ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/src)
set(SYSTEM_CONFIG_GUI_LIB_PATH_INC ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/include)
set(SYSTEM_CONFIG_GUI_LIB_PATH_FORMS ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/forms)
set(SYSTEM_CONFIG_GUI_RESOURCE_FILE_QRC ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/systemconfiggui.qrc)
# Flying Agent GUI -- Add src, includes, forms, and resources
set(FLYING_AGENT_GUI_LIB_PATH_SRC ${PROJECT_SOURCE_DIR}/GUI_Qt/flyingAgentGUI/src)
set(FLYING_AGENT_GUI_LIB_PATH_INC ${PROJECT_SOURCE_DIR}/GUI_Qt/flyingAgentGUI/include)
set(FLYING_AGENT_GUI_LIB_PATH_FORMS ${PROJECT_SOURCE_DIR}/GUI_Qt/flyingAgentGUI/forms)
set(FLYING_AGENT_GUI_RESOURCE_FILE_QRC ${PROJECT_SOURCE_DIR}/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc)
endif()
# #set the default path for built executables to the "bin" directory
# set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
# #set the default path for built libraries to the "lib" directory
# set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
# Need c++11 for some things - mainly for the GUI
add_definitions(-std=c++11)
if(Qt5_FOUND)
# GUI -- Special Qt sources that need to be wrapped before being compiled
# they have the Qt macro QOBJECT inside, the MOC cpp file needs to be done manually
set(SRC_HDRS_QOBJECT_GUI
${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/crazyFlyZoneTab.h
${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/myGraphicsScene.h
${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/myGraphicsView.h
${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/mainguiwindow.h
${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/rosNodeThread_for_systemConfigGUI.h
${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/CFLinker.h
)
# GUI -- wrap UI file and QOBJECT files
qt5_wrap_ui(UIS_HDRS_GUI ${SYSTEM_CONFIG_GUI_LIB_PATH_FORMS}/mainguiwindow.ui)
qt5_wrap_cpp(SRC_MOC_HDRS_GUI ${SRC_HDRS_QOBJECT_GUI})
# GUI -- wrap resource file qrc->rcc
qt5_add_resources(SYSTEM_CONFIG_GUI_RESOURCE_FILE_RRC ${SYSTEM_CONFIG_GUI_RESOURCE_FILE_QRC})
# Flying Agent GUI
# - Special Qt sources that need to be wrapped before being compiled
# they have the Qt macro QOBJECT inside, the MOC cpp file needs to
# be done manually
set(SRC_HDRS_QOBJECT_FLYING_AGENT_GUI
${FLYING_AGENT_GUI_LIB_PATH_INC}/connectstartstopbar.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/controllerstatusbanner.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/controllertabs.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/coordinator.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/coordinatorrow.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/csonecontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/defaultcontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/enablecontrollerloadyamlbar.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/mainwindow.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/pickercontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/remotecontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/rosNodeThread_for_flyingAgentGUI.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/safecontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/studentcontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/templatecontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/tutorialcontrollertab.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/topbanner.h
${FLYING_AGENT_GUI_LIB_PATH_INC}/tuningcontrollertab.h
)
# Flying Agent GUI -- wrap UI file and QOBJECT files
qt5_wrap_ui(UIS_HDRS_FLYING_AGENT_GUI
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/connectstartstopbar.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/controllerstatusbanner.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/controllertabs.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/coordinator.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/coordinatorrow.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/csonecontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/defaultcontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/enablecontrollerloadyamlbar.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/mainwindow.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/pickercontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/remotecontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/safecontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/studentcontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/templatecontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/tutorialcontrollertab.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/topbanner.ui
${FLYING_AGENT_GUI_LIB_PATH_FORMS}/tuningcontrollertab.ui
)
qt5_wrap_cpp(SRC_MOC_HDRS_FLYING_AGENT_GUI ${SRC_HDRS_QOBJECT_FLYING_AGENT_GUI})
# Flying Agent GUI -- wrap resource file qrc->rcc
qt5_add_resources(FLYING_AGENT_GUI_RESOURCE_FILE_RCC ${FLYING_AGENT_GUI_RESOURCE_FILE_QRC})
endif()
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
add_message_files(
FILES
AreaBounds.msg
ControlCommand.msg
CrazyflieContext.msg
CrazyflieDB.msg
CrazyflieEntry.msg
CustomButton.msg
DebugMsg.msg
FlyingVehicleState.msg
GyroMeasurements.msg
Setpoint.msg
SetpointV2.msg
UnlabeledMarker.msg
ViconData.msg
ViconSubscribeObjectName.msg
#------------------------
IntWithHeader.msg
FloatWithHeader.msg
StringWithHeader.msg
SetpointWithHeader.msg
CustomButtonWithHeader.msg
#------------------------
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
add_service_files(
FILES
IntIntService.srv
IntStringService.srv
Controller.srv
CMRead.srv
CMQuery.srv
CMQueryCrazyflieName.srv
CMUpdate.srv
CMCommand.srv
LoadYamlFromFilename.srv
GetDebugValuesService.srv
GetSetpointService.srv
)
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs
# )
generate_messages(
DEPENDENCIES
std_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
if(Qt5_FOUND)
catkin_package(
INCLUDE_DIRS include ${SYSTEM_CONFIG_GUI_LIB_PATH_INC} # SystemConfigGUI -- include headers from GUI in package
INCLUDE_DIRS include ${FLYING_AGENT_GUI_LIB_PATH_INC} # FlyingAgentGUI -- include headers from GUI in package
LIBRARIES
CATKIN_DEPENDS roscpp rospy std_msgs rosbag roslib
DEPENDS
)
else()
catkin_package(
LIBRARIES
CATKIN_DEPENDS roscpp rospy std_msgs rosbag roslib
DEPENDS
)
endif()
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
if(Qt5_FOUND)
include_directories(
${SYSTEM_CONFIG_GUI_LIB_PATH_INC} # SystemConfigGUI -- include directory inside GUI folder
${FLYING_AGENT_GUI_LIB_PATH_INC} # FlyingAgentGUI -- include directory inside GUI folder
${catkin_INCLUDE_DIRS}
include
include/nodes
$ENV{HOME}/Software/osqp-0.5.0-linux64/include
)
else()
include_directories(
${catkin_INCLUDE_DIRS}
include
include/nodes
)
endif()
# Find OSQP library
# Clear cache to force finding each time
unset(OSQP_LIBRARY CACHE)
find_library(OSQP_LIBRARY
NAMES libosqp.so
PATHS "$ENV{HOME}/Software/osqp-0.5.0-linux64/lib"
)
## Declare a C++ library
##add_library(${PROJECT_NAME}
## src/blablalba.cpp
##)
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/dfall_pkg_node.cpp)
if(VICON_LIBRARY)
add_executable(ViconDataPublisher src/nodes/ViconDataPublisher.cpp)
endif()
add_executable(FlyingAgentClient src/nodes/FlyingAgentClient.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(AgentStatusForWebInterface src/nodes/AgentStatusForWebInterface.cpp)
add_executable(BatteryMonitor src/nodes/BatteryMonitor.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(CrazyRadioEmulator src/nodes/CrazyRadioEmulator.cpp
src/classes/QuadrotorSimulator.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(CsoneControllerService src/nodes/CsoneControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(DefaultControllerService src/nodes/DefaultControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
# add_executable(SafeControllerService src/nodes/SafeControllerService.cpp)
# add_executable(DemoControllerService src/nodes/DemoControllerService.cpp
# src/classes/GetParamtersAndNamespaces.cpp)
add_executable(StudentControllerService src/nodes/StudentControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
# add_executable(MpcControllerService src/nodes/MpcControllerService.cpp)
add_executable(RemoteControllerService src/nodes/RemoteControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(TuningControllerService src/nodes/TuningControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(PickerControllerService src/nodes/PickerControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(TemplateControllerService src/nodes/TemplateControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(TutorialControllerService src/nodes/TutorialControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(TestMotorsControllerService src/nodes/TestMotorsControllerService.cpp
src/classes/GetParamtersAndNamespaces.cpp)
add_executable(CentralManagerService src/nodes/CentralManagerService.cpp src/classes/CrazyflieIO.cpp)
add_executable(ParameterService src/nodes/ParameterService.cpp)
add_executable(MocapEmulator src/nodes/MocapEmulator.cpp
src/classes/QuadrotorSimulator.cpp
src/classes/GetParamtersAndNamespaces.cpp)
if(Qt5_FOUND)
# GUI -- Add sources here
set(SYSTEM_CONFIG_GUI_CPP_SOURCES # compilation of sources
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/mainguiwindow.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/main.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/cornergrabber.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/crazyFlyZone.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/crazyFlyZoneTab.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/myGraphicsRectItem.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/myGraphicsScene.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/myGraphicsView.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/tablePiece.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/marker.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/rosNodeThread_for_systemConfigGUI.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/crazyFly.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/CFLinker.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/channelLUT.cpp
${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/centerMarker.cpp
)
# FLYING AGENT GUI -- Add sources here
set(FLYING_AGENT_GUI_CPP_SOURCES # compilation of sources
${FLYING_AGENT_GUI_LIB_PATH_SRC}/mainwindow.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/main.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/rosNodeThread_for_flyingAgentGUI.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/connectstartstopbar.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/controllerstatusbanner.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/controllertabs.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/coordinator.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/coordinatorrow.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/csonecontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/defaultcontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/enablecontrollerloadyamlbar.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/pickercontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/remotecontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/safecontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/studentcontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/templatecontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/tutorialcontrollertab.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/topbanner.cpp
${FLYING_AGENT_GUI_LIB_PATH_SRC}/tuningcontrollertab.cpp
)
# GUI -- Add executables here
add_executable(SystemConfigGUI ${SYSTEM_CONFIG_GUI_CPP_SOURCES} ${UIS_HDRS_GUI} ${SRC_MOC_HDRS_GUI} ${SYSTEM_CONFIG_GUI_RESOURCE_FILE_RRC})
qt5_use_modules(SystemConfigGUI Widgets)
# FLYING AGENT GUI -- Add executables here
add_executable(FlyingAgentGUI ${FLYING_AGENT_GUI_CPP_SOURCES} ${UIS_HDRS_FLYING_AGENT_GUI} ${SRC_MOC_HDRS_FLYING_AGENT_GUI} ${FLYING_AGENT_GUI_RESOURCE_FILE_RCC})
qt5_use_modules(FlyingAgentGUI Widgets)
endif()
if(VICON_LIBRARY)
add_dependencies(ViconDataPublisher dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
endif()
add_dependencies(FlyingAgentClient dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(AgentStatusForWebInterface dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(BatteryMonitor dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(CrazyRadioEmulator dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(CsoneControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(DefaultControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
# add_dependencies(SafeControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
# add_dependencies(DemoControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(StudentControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
# add_dependencies(MpcControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(RemoteControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(TuningControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(PickerControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(TemplateControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(TutorialControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(TestMotorsControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(CentralManagerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(ParameterService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(MocapEmulator dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
if(Qt5_FOUND)
# GUI-- dependencies
add_dependencies(SystemConfigGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
# FLYING AGENT GUI-- dependencies
add_dependencies(FlyingAgentGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
endif()
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
if(VICON_LIBRARY)
target_link_libraries(ViconDataPublisher ${catkin_LIBRARIES})
target_link_libraries(ViconDataPublisher ${VICON_LIBRARY})
endif()
target_link_libraries(FlyingAgentClient ${catkin_LIBRARIES})
target_link_libraries(AgentStatusForWebInterface ${catkin_LIBRARIES})
target_link_libraries(BatteryMonitor ${catkin_LIBRARIES})
target_link_libraries(CrazyRadioEmulator ${catkin_LIBRARIES})
target_link_libraries(CsoneControllerService ${catkin_LIBRARIES})
target_link_libraries(DefaultControllerService ${catkin_LIBRARIES})
# target_link_libraries(SafeControllerService ${catkin_LIBRARIES})
# target_link_libraries(DemoControllerService ${catkin_LIBRARIES})
target_link_libraries(StudentControllerService ${catkin_LIBRARIES})
# if(Eigen3_FOUND)
# target_link_libraries(MpcControllerService ${catkin_LIBRARIES} Eigen3::Eigen)
# else()
# target_link_libraries(MpcControllerService ${catkin_LIBRARIES})
# endif()
target_link_libraries(RemoteControllerService ${catkin_LIBRARIES})
target_link_libraries(TuningControllerService ${catkin_LIBRARIES})
target_link_libraries(PickerControllerService ${catkin_LIBRARIES})
target_link_libraries(TemplateControllerService ${catkin_LIBRARIES})
target_link_libraries(TutorialControllerService ${catkin_LIBRARIES} ${OSQP_LIBRARY})
target_link_libraries(TestMotorsControllerService ${catkin_LIBRARIES})
target_link_libraries(CentralManagerService ${catkin_LIBRARIES})
target_link_libraries(ParameterService ${catkin_LIBRARIES})
target_link_libraries(MocapEmulator ${catkin_LIBRARIES})
if(Qt5_FOUND)
# GUI -- link libraries
target_link_libraries(SystemConfigGUI Qt5::Widgets) # GUI -- let SystemConfigGUI have acesss to Qt stuff
target_link_libraries(SystemConfigGUI Qt5::Svg)
target_link_libraries(SystemConfigGUI ${catkin_LIBRARIES})
# Flying Agent GUI -- link libraries
target_link_libraries(FlyingAgentGUI Qt5::Widgets) # GUI -- let FlyingAgentGUI have acesss to Qt stuff
target_link_libraries(FlyingAgentGUI Qt5::Charts)
target_link_libraries(FlyingAgentGUI ${catkin_LIBRARIES})
endif()
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_dfall_pkg.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
#-------------------------------------------------
#
# Project created by QtCreator 2018-04-26T16:04:19
#
#-------------------------------------------------
QT += core gui
greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
#greaterThan(QT_MAJOR_VERSION, 4): QT += svg
greaterThan(QT_MAJOR_VERSION, 4): QT += charts
#greaterThan(QT_MAJOR_VERSION, 4): QT += multimedia
TARGET = flyingAgentGUI
TEMPLATE = app
INCLUDEPATH += $$PWD/include
CONFIG += c++11
SOURCES += src/main.cpp\
src/mainwindow.cpp \
src/topbanner.cpp \
src/connectstartstopbar.cpp \
src/enablecontrollerloadyamlbar.cpp \
src/controllerstatusbanner.cpp \
src/controllertabs.cpp \
src/csonecontrollertab.cpp \
src/safecontrollertab.cpp \
src/coordinator.cpp \
src/coordinatorrow.cpp \
src/studentcontrollertab.cpp \
src/defaultcontrollertab.cpp \
src/pickercontrollertab.cpp \
src/templatecontrollertab.cpp \
src/tutorialcontrollertab.cpp \
src/tuningcontrollertab.cpp \
src/remotecontrollertab.cpp
HEADERS += include/mainwindow.h \
include/topbanner.h \
include/connectstartstopbar.h \
include/enablecontrollerloadyamlbar.h \
include/controllerstatusbanner.h \
include/controllertabs.h \
include/csonecontrollertab.h \
include/safecontrollertab.h \
include/coordinator.h \
include/coordinatorrow.h \
include/studentcontrollertab.h \
include/defaultcontrollertab.h \
include/pickercontrollertab.h \
include/templatecontrollertab.h \
include/tutorialcontrollertab.h \
include/tuningcontrollertab.h \
include/Constants_for_Qt_compile.h \
include/remotecontrollertab.h
FORMS += forms/mainwindow.ui \
forms/topbanner.ui \
forms/connectstartstopbar.ui \
forms/enablecontrollerloadyamlbar.ui \
forms/controllertabs.ui \
forms/controllerstatusbanner.ui \
forms/csonecontrollertab.ui \
forms/safecontrollertab.ui \
forms/coordinator.ui \
forms/coordinatorrow.ui \
forms/studentcontrollertab.ui \
forms/defaultcontrollertab.ui \
forms/pickercontrollertab.ui \
forms/templatecontrollertab.ui \
forms/tutorialcontrollertab.ui \
forms/tuningcontrollertab.ui \
forms/remotecontrollertab.ui
RESOURCES += \
flyingagentgui.qrc
<RCC>
<qresource prefix="/">
<file>images/battery_20.png</file>
<file>images/battery_40.png</file>
<file>images/battery_60.png</file>
<file>images/battery_80.png</file>
<file>images/battery_empty.png</file>
<file>images/battery_full.png</file>
<file>images/battery_unknown.png</file>
<file>images/battery_unavailable.png</file>
<file>images/rf_connected.png</file>
<file>images/rf_connecting.png</file>
<file>images/rf_disconnected.png</file>
<file>images/flying_state_disabling.png</file>
<file>images/flying_state_enabling.png</file>
<file>images/flying_state_flying.png</file>
<file>images/flying_state_off.png</file>
<file>images/flying_state_unknown.png</file>
<file>images/flying_state_unavailable.png</file>
<file>images/emergency_stop.png</file>
</qresource>
</RCC>
\ No newline at end of file
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ConnectStartStopBar</class>
<widget class="QWidget" name="ConnectStartStopBar">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1791</width>
<height>300</height>
</rect>
</property>
<property name="font">
<font>
<pointsize>16</pointsize>
</font>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>12</number>
</property>
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QPushButton" name="rf_disconnect_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>750</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Disconnect</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="rf_status_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>72</width>
<height>55</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>95</width>
<height>70</height>
</size>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rf_connect_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>750</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Connect</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="battery_voltage_lineEdit">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>-.-- V</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="battery_status_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>38</width>
<height>55</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>50</width>
<height>70</height>
</size>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="enable_flying_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>750</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Take off</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="disable_flying_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>750</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Land</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="flying_state_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>72</width>
<height>55</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>90</width>
<height>70</height>
</size>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="motors_off_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>750</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Motors OFF</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ControllerStatusBanner</class>
<widget class="QWidget" name="ControllerStatusBanner">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>173</width>
<height>1282</height>
</rect>
</property>
<property name="font">
<font>
<pointsize>16</pointsize>
</font>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<property name="spacing">
<number>0</number>
</property>
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout">
<property name="topMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QFrame" name="frame_isOff">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color:rgb(160,40,40);</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>15</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label_isOff">
<property name="font">
<font>
<pointsize>16</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>O
F
F</string>
</property>
<property name="alignment">
<set>Qt::AlignHCenter|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QFrame" name="frame_isActive">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color:rgb(40,120,40);</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>15</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label_isActive">
<property name="font">
<font>
<pointsize>16</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>A
C
T
I
V
E</string>
</property>
<property name="alignment">
<set>Qt::AlignHCenter|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QFrame" name="frame_isCoord">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color:rgb(150,150,150)</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout_4">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>15</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label_isCoord">
<property name="font">
<font>
<pointsize>16</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>C
O
O
R
D</string>
</property>
<property name="alignment">
<set>Qt::AlignHCenter|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ControllerTabs</class>
<widget class="QWidget" name="ControllerTabs">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1779</width>
<height>718</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<pointsize>16</pointsize>
</font>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QTabWidget" name="controller_tabs_widget">
<property name="currentIndex">
<number>6</number>
</property>
<property name="movable">
<bool>true</bool>
</property>
<widget class="QWidget" name="default_tab">
<attribute name="title">
<string>Default</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_2">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_default">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="DefaultControllerTab" name="default_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_default" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="student_tab">
<attribute name="title">
<string>Student</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_4">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_student">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="StudentControllerTab" name="student_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_student" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="csone_tab">
<attribute name="title">
<string>CS1</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_8">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_csone" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_csone">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="CsoneControllerTab" name="csone_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="picker_tab">
<attribute name="title">
<string>Picker</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_5">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_picker">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="PickerControllerTab" name="picker_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_picker" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="tuning_tab">
<attribute name="title">
<string>Tuning</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_6">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_tuning" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_tuning">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="TuningControllerTab" name="tuning_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="remote_tab">
<attribute name="title">
<string>Remote</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_3">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_remote">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="RemoteControllerTab" name="remote_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_remote" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="template_tab">
<attribute name="title">
<string>Template</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_7">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_template">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="TemplateControllerTab" name="template_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_template" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="tutorial_tab">
<attribute name="title">
<string>Tutorial</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_9">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>5</number>
</property>
<item row="0" column="1">
<widget class="QScrollArea" name="scrollArea_tutorial">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="TutorialControllerTab" name="tutorial_controller_tab_widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1638</width>
<height>576</height>
</rect>
</property>
</widget>
</widget>
</item>
<item row="0" column="0">
<widget class="ControllerStatusBanner" name="statusBanner_tutorial" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>StudentControllerTab</class>
<extends>QWidget</extends>
<header>studentcontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>DefaultControllerTab</class>
<extends>QWidget</extends>
<header>defaultcontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>PickerControllerTab</class>
<extends>QWidget</extends>
<header>pickercontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>TuningControllerTab</class>
<extends>QWidget</extends>
<header>tuningcontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>TemplateControllerTab</class>
<extends>QWidget</extends>
<header>templatecontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>TutorialControllerTab</class>
<extends>QWidget</extends>
<header>tutorialcontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>RemoteControllerTab</class>
<extends>QWidget</extends>
<header>remotecontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>CsoneControllerTab</class>
<extends>QWidget</extends>
<header>csonecontrollertab.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>ControllerStatusBanner</class>
<extends>QWidget</extends>
<header>controllerstatusbanner.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>Coordinator</class>
<widget class="QWidget" name="Coordinator">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>603</width>
<height>1050</height>
</rect>
</property>
<property name="font">
<font>
<pointsize>16</pointsize>
</font>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="coordintor_title_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Coordinator</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="coordinator_id_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>ID = </string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="refresh_button">
<property name="text">
<string>Refresh</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="toggle_details_button">
<property name="text">
<string>Toggle Details</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="delete_button">
<property name="text">
<string>Remove All</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="coordinate_all_checkBox">
<property name="font">
<font>
<pointsize>16</pointsize>
</font>
</property>
<property name="styleSheet">
<string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
</property>
<property name="text">
<string>Coordinate All</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QScrollArea" name="coordinated_agents_scrollArea">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="coordinated_agents_scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>565</width>
<height>622</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_for_coordinatedAgentsScrollArea"/>
</widget>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>CoordinatorRow</class>
<widget class="QWidget" name="CoordinatorRow">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>740</width>
<height>45</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>45</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>45</height>
</size>
</property>
<property name="font">
<font>
<pointsize>12</pointsize>
</font>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>2</number>
</property>
<property name="leftMargin">
<number>2</number>
</property>
<property name="topMargin">
<number>5</number>
</property>
<property name="rightMargin">
<number>2</number>
</property>
<property name="bottomMargin">
<number>5</number>
</property>
<item>
<widget class="QCheckBox" name="shouldCoordinate_checkBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>35</height>
</size>
</property>
<property name="font">
<font>
<pointsize>12</pointsize>
</font>
</property>
<property name="styleSheet">
<string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
</property>
<property name="text">
<string>IDYYY , CFXX</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rf_disconnect_button">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>DIS</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="rf_status_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>43</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>43</width>
<height>35</height>
</size>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rf_connect_button">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>CON</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="battery_voltage_lineEdit">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>68</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>68</width>
<height>35</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>-.-- V</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="battery_status_label">
<property name="minimumSize">
<size>
<width>25</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>25</width>
<height>35</height>
</size>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="enable_flying_button">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>EN</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="disable_flying_button">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>DIS</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="flying_state_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>50</width>
<height>35</height>
</size>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="motors_off_button">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>35</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>OFF</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="controller_enabled_label">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>35</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Controller</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>CsoneControllerTab</class>
<widget class="QWidget" name="CsoneControllerTab">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>3197</width>
<height>1336</height>
</rect>
</property>
<property name="font">
<font>
<pointsize>16</pointsize>
</font>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="7" column="0">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="8" column="0">
<widget class="QLabel" name="label_time_series_time_2">
<property name="text">
<string>Time series for pitch angle in degrees</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QChartView" name="chartView_for_x">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_5">
<property name="spacing">
<number>0</number>
</property>
<item>
<widget class="QFrame" name="red_frame_position_left">
<property name="maximumSize">
<size>
<width>10</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color:red;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_time_series_time">
<property name="text">
<string>Time series for x position in meters</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QFrame" name="red_frame_position_right">
<property name="maximumSize">
<size>
<width>10</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color:red;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
</layout>
</item>
<item row="10" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="5" column="0">
<layout class="QGridLayout" name="gridLayout_7">
<property name="topMargin">
<number>0</number>
</property>
<item row="2" column="5">
<widget class="QLineEdit" name="lineEdit_overshoot_percent">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>---</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="0" column="9">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="2">
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_step_end">
<property name="text">
<string>Step End</string>
</property>
</widget>
</item>
<item row="0" column="6">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_step_start">
<property name="text">
<string>Step Start</string>
</property>
</widget>
</item>
<item row="0" column="5">
<widget class="QLineEdit" name="lineEdit_overshoot_value">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>---</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="lineEdit_step_start">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>---</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLineEdit" name="lineEdit_step_end">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>---</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_overshoot_value">
<property name="text">
<string>Overshoot [meters]</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLabel" name="label_overshoot_percent">
<property name="text">
<string>Overshoot [percent]</string>
</property>
</widget>
</item>
<item row="0" column="7">
<widget class="QLabel" name="label_rise_time">
<property name="text">
<string>Rise Time</string>
</property>
</widget>
</item>
<item row="2" column="7">
<widget class="QLabel" name="label_rise_time_2">
<property name="text">
<string>Settling Time</string>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QLineEdit" name="lineEdit_rise_time">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>---</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="8">
<widget class="QLineEdit" name="lineEdit_settling_time">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>---</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item row="6" column="0">
<widget class="Line" name="line_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="2" column="0">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="9" column="0">
<widget class="QChartView" name="chartView_for_pitch"/>
</item>
<item row="1" column="0">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="0" column="0">
<layout class="QGridLayout" name="gridLayout">
<property name="topMargin">
<number>50</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<item row="1" column="17">
<layout class="QGridLayout" name="gridLayout_8">
<item row="2" column="0">
<widget class="QPushButton" name="reset_integrator_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_integrator_state">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>off</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="toggle_integrator_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Toggle</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="8">
<layout class="QGridLayout" name="gridLayout_13">
<item row="0" column="0">
<widget class="QLabel" name="label_time_delay_units">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>[milli sec]</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="set_time_delay_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Set</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLineEdit" name="lineEdit_time_delay">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="0" column="19">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>13</width>
<height>29</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="17">
<widget class="QLabel" name="label_integrator">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Integrator</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="18">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>13</width>
<height>29</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="10">
<widget class="QLabel" name="label_pid_controller">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>PD Controller</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="13">
<layout class="QGridLayout" name="gridLayout_4">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label_step_size">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Size</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_step_duration">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Duration</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLineEdit" name="lineEdit_step_size">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0.50</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="lineEdit_step_duration">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>20</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="perform_step_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Perform</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QPushButton" name="log_data_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Log</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="10">
<layout class="QGridLayout" name="gridLayout_6">
<item row="1" column="0">
<widget class="QPushButton" name="set_pd_controller_parameters_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Set</string>
</property>
</widget>
</item>
<item row="0" column="0">
<layout class="QGridLayout" name="gridLayout_5">
<property name="rightMargin">
<number>0</number>
</property>
<item row="0" column="1">
<widget class="QLabel" name="label_kp">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>k_p</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="lineEdit_kp">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0.5</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="lineEdit_kd">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0.2</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_kd">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>k_d</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="0" column="14">
<spacer name="horizontalSpacer_simulation">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>100</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_lead_compenstor">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Lead Compensator</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="12">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>100</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="13">
<widget class="QLabel" name="label_step_details">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Step Details</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="15">
<layout class="QGridLayout" name="gridLayout_10">
<item row="2" column="0">
<widget class="QPushButton" name="clear_simulation_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="simulate_step_response_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Perform</string>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_simulation_blank">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string/>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="0">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QGridLayout" name="gridLayout_3">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="1" column="2">
<widget class="QLineEdit" name="lineEdit_alpha">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0.50</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_T">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>T</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_alpha">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>alpha</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLineEdit" name="lineEdit_k">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0.1000</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="lineEdit_T">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>1.00</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_k">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>k</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QPushButton" name="set_lead_compensator_parameters_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Set</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="1">
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QGridLayout" name="gridLayout_9">
<item row="1" column="1">
<widget class="QLineEdit" name="lineEdit_alpha_lag">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>1.00</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_T_lag">
<property name="text">
<string>T</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_alpha_lag">
<property name="text">
<string>alpha</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLineEdit" name="lineEdit_T_lag">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0.00</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QPushButton" name="set_lag_compensator_parameters_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Set</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="0" column="15">
<widget class="QLabel" name="label_simulation">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Simulation</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_lag_compenstor">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Lag Compensator</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="16">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>100</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="8">
<widget class="QLabel" name="label_time_delay">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Time Delay</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="9">
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QLabel" name="label_pitch_error_units">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>[degrees]</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="lineEdit_pitch_error">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Source Code Pro</family>
</font>
</property>
<property name="text">
<string>0.000</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="set_pitch_error_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Set</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="0" column="7">
<spacer name="horizontalSpacer_pd_controller">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>100</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="9">
<widget class="QLabel" name="label_pitch_error">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Pitch Error</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>QChartView</class>
<extends>QGraphicsView</extends>
<header>QtCharts</header>
</customwidget>
</customwidgets>
<tabstops>
<tabstop>lineEdit_k</tabstop>
<tabstop>lineEdit_T</tabstop>
<tabstop>lineEdit_alpha</tabstop>
<tabstop>lineEdit_time_delay</tabstop>
<tabstop>lineEdit_kp</tabstop>
<tabstop>lineEdit_kd</tabstop>
<tabstop>lineEdit_step_size</tabstop>
<tabstop>lineEdit_step_duration</tabstop>
<tabstop>set_lead_compensator_parameters_button</tabstop>
<tabstop>set_time_delay_button</tabstop>
<tabstop>set_pd_controller_parameters_button</tabstop>
<tabstop>perform_step_button</tabstop>
<tabstop>log_data_button</tabstop>
<tabstop>simulate_step_response_button</tabstop>
<tabstop>clear_simulation_button</tabstop>
<tabstop>toggle_integrator_button</tabstop>
<tabstop>reset_integrator_button</tabstop>
<tabstop>lineEdit_rise_time</tabstop>
<tabstop>lineEdit_settling_time</tabstop>
<tabstop>lineEdit_step_end</tabstop>
<tabstop>lineEdit_step_start</tabstop>
<tabstop>chartView_for_x</tabstop>
<tabstop>chartView_for_pitch</tabstop>
<tabstop>lineEdit_overshoot_value</tabstop>
<tabstop>lineEdit_overshoot_percent</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>DefaultControllerTab</class>
<widget class="QWidget" name="DefaultControllerTab">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1614</width>
<height>991</height>
</rect>
</property>
<property name="font">
<font>
<pointsize>16</pointsize>
</font>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="0">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_6">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_current_state_title">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Current State:</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_current_state">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="4" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="0">
<layout class="QGridLayout" name="gridLayout_2">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="2" column="1">
<widget class="QLabel" name="label_row_x">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>x [m]</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="6">
<widget class="QLabel" name="label_increment_title">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Increment</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_error_title">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Error</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QLabel" name="label_row_yaw">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>yaw [deg]</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_error_title_line2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>meas-ref</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_current_title_line2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Setpoint</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_current_title">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Current</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QLabel" name="label_increment_title_line2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Setpoint</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLabel" name="label_row_y">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>y [m]</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="6">
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QPushButton" name="y_increment_minus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>-</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>140</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>0.1</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="y_increment_plus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>+</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="4" column="6">
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QPushButton" name="z_increment_minus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>-</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>140</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>0.1</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="z_increment_plus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>+</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="3">
<widget class="QLineEdit" name="lineEdit_setpoint_current_x">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QLineEdit" name="lineEdit_error_yaw">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="5" column="6">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QPushButton" name="yaw_increment_minus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>-</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>140</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>15</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="yaw_increment_plus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>+</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="5" column="3">
<widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="lineEdit_error_x">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QLabel" name="label_row_roll">
<property name="text">
<string>roll [deg]</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="6" column="3">
<widget class="QPushButton" name="default_setpoint_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Default</string>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QLineEdit" name="lineEdit_error_z">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_measured_title">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Measured</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QLabel" name="label_row_pitch">
<property name="text">
<string>pitch [deg]</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QLineEdit" name="lineEdit_error_y">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QLabel" name="label_row_z">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>z [m]</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QLineEdit" name="lineEdit_setpoint_current_y">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QLineEdit" name="lineEdit_setpoint_current_z">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="6">
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<widget class="QPushButton" name="x_increment_minus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>-</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>140</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>0.1</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="x_increment_plus_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>60</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>+</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_5">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QFrame" name="red_frame_position_left">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>10</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color:red;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_measured_title_line2">
<property name="text">
<string>Position</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QFrame" name="red_frame_position_right">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>10</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color:red;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_8">
<item>
<widget class="QLineEdit" name="lineEdit_measured_x">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_9">
<item>
<widget class="QLineEdit" name="lineEdit_measured_y">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="4" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_10">
<item>
<widget class="QLineEdit" name="lineEdit_measured_z">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="5" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_11">
<item>
<widget class="QLineEdit" name="lineEdit_measured_yaw">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="6" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<widget class="QLineEdit" name="lineEdit_measured_pitch">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="7" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_13">
<item>
<widget class="QLineEdit" name="lineEdit_measured_roll">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string>xx.xx</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="7">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="5">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_new_title">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>New</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="label_new_title_line2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Setpoint</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QLineEdit" name="lineEdit_setpoint_new_x">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QLineEdit" name="lineEdit_setpoint_new_y">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QLineEdit" name="lineEdit_setpoint_new_z">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="5" column="4">
<widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="font">
<font>
<family>Courier</family>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="6" column="4">
<widget class="QPushButton" name="set_setpoint_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>60</height>
</size>
</property>
<property name="text">
<string>Set New</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>