diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro index 61aa744e5c1027e93fad9c516450e8eb0922d57a..0175414f1cbbf0b84363db3111330625fed062b1 100755 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro @@ -45,7 +45,9 @@ HEADERS += \ include/tablePiece.h \ include/globalDefinitions.h \ include/marker.h \ - include/crazyFly.h + include/crazyFly.h \ + \ + include/constants_for_qt_compile.h FORMS += \ forms/mainguiwindow.ui diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui index 737f460b0ae385e2d25c23aabc6eb990df265ec6..2d50c2a9dd741d735d515d406cda65846f8db683 100755 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui @@ -6,7 +6,7 @@ <rect> <x>0</x> <y>0</y> - <width>1176</width> + <width>1228</width> <height>1559</height> </rect> </property> @@ -273,7 +273,7 @@ </property> <layout class="QVBoxLayout" name="verticalLayout_2"> <item> - <widget class="QPushButton" name="all_motors_off_button"> + <widget class="QPushButton" name="emergency_stop_button"> <property name="sizePolicy"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <horstretch>0</horstretch> @@ -300,7 +300,7 @@ </font> </property> <property name="text"> - <string>All motors OFF</string> + <string>Emergency Stop</string> </property> </widget> </item> @@ -870,329 +870,56 @@ </widget> <widget class="QWidget" name="tab"> <attribute name="title"> - <string>Command all</string> + <string>Mocap</string> </attribute> <layout class="QGridLayout" name="gridLayout_2"> - <item row="10" column="1"> - <widget class="QPushButton" name="all_load_custom_controller_yaml_coordinator_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Load Custom YAML</string> - </property> - </widget> - </item> - <item row="6" column="0" colspan="2"> - <widget class="QLabel" name="all_yaml_label"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>20</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>40</height> - </size> - </property> - <property name="font"> - <font> - <weight>75</weight> - <bold>true</bold> - </font> - </property> - <property name="text"> - <string>LOAD YAML PARAMETERS</string> - </property> - <property name="alignment"> - <set>Qt::AlignBottom|Qt::AlignHCenter</set> - </property> - </widget> - </item> - <item row="3" column="0"> - <widget class="QPushButton" name="all_take_off_button"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Take off</string> - </property> - </widget> - </item> - <item row="1" column="1"> - <widget class="QPushButton" name="all_connect_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Reconnect</string> - </property> - </widget> - </item> - <item row="2" column="0" colspan="2"> - <widget class="QLabel" name="all_flying_state_label"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>20</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>40</height> - </size> - </property> - <property name="font"> - <font> - <weight>75</weight> - <bold>true</bold> - </font> - </property> - <property name="text"> - <string>FLYING STATE</string> - </property> - <property name="alignment"> - <set>Qt::AlignBottom|Qt::AlignHCenter</set> - </property> - </widget> - </item> - <item row="5" column="0"> - <widget class="QPushButton" name="all_enable_safe_controller_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Enable Safe</string> - </property> - </widget> - </item> - <item row="8" column="1"> - <widget class="QPushButton" name="all_load_custom_controller_yaml_own_agent_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Load Custom YAML</string> - </property> - </widget> - </item> - <item row="1" column="0"> - <widget class="QPushButton" name="all_disconnect_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Disconnect</string> - </property> - </widget> - </item> - <item row="5" column="1"> - <widget class="QPushButton" name="all_enable_custom_controller_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Enable Custom</string> - </property> - </widget> - </item> - <item row="3" column="1"> - <widget class="QPushButton" name="all_land_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Land</string> - </property> - </widget> - </item> - <item row="8" column="0"> - <widget class="QPushButton" name="all_load_safe_controller_yaml_own_agent_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Load Safe YAML</string> - </property> - </widget> - </item> - <item row="7" column="0" colspan="2"> - <widget class="QLabel" name="all_yaml_agent_label"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>30</height> - </size> - </property> - <property name="text"> - <string>> From agenet's local file</string> - </property> - </widget> - </item> - <item row="10" column="0"> - <widget class="QPushButton" name="all_load_safe_controller_yaml_coordinator_button"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>50</height> - </size> - </property> - <property name="text"> - <string>Load Safe YAML</string> - </property> - </widget> - </item> - <item row="9" column="0" colspan="2"> - <widget class="QLabel" name="all_yaml_coordinator_label"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>30</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>30</height> - </size> - </property> - <property name="text"> - <string>> From coordinator's file</string> - </property> - </widget> - </item> - <item row="0" column="0" colspan="2"> - <widget class="QLabel" name="all_radio_label"> - <property name="minimumSize"> - <size> - <width>0</width> - <height>20</height> - </size> - </property> - <property name="maximumSize"> - <size> - <width>16777215</width> - <height>40</height> - </size> - </property> - <property name="font"> - <font> - <weight>75</weight> - <bold>true</bold> - </font> - </property> - <property name="lineWidth"> - <number>1</number> - </property> - <property name="text"> - <string>CRAZYRADIO</string> - </property> - <property name="alignment"> - <set>Qt::AlignBottom|Qt::AlignHCenter</set> - </property> - </widget> + <item row="0" column="0"> + <layout class="QGridLayout" name="gridLayout_6"> + <item row="0" column="0"> + <widget class="QLabel" name="all_radio_label"> + <property name="minimumSize"> + <size> + <width>0</width> + <height>20</height> + </size> + </property> + <property name="maximumSize"> + <size> + <width>16777215</width> + <height>40</height> + </size> + </property> + <property name="font"> + <font> + <weight>75</weight> + <bold>true</bold> + </font> + </property> + <property name="lineWidth"> + <number>1</number> + </property> + <property name="text"> + <string>Work in progress.</string> + </property> + <property name="alignment"> + <set>Qt::AlignBottom|Qt::AlignHCenter</set> + </property> + </widget> + </item> + <item row="1" 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> + </layout> </item> </layout> </widget> @@ -1245,8 +972,8 @@ <rect> <x>0</x> <y>0</y> - <width>1176</width> - <height>25</height> + <width>1228</width> + <height>40</height> </rect> </property> </widget> diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h new file mode 100644 index 0000000000000000000000000000000000000000..b361da05638f8715502151fdce96166c4ea49128 --- /dev/null +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h @@ -0,0 +1,286 @@ +// Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat +// +// This file is part of D-FaLL-System. +// +// D-FaLL-System is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// D-FaLL-System is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with D-FaLL-System. If not, see <http://www.gnu.org/licenses/>. +// +// +// ---------------------------------------------------------------------------------- +// DDDD FFFFF L L SSSS Y Y SSSS TTTTT EEEEE M M +// D D F aaa L L S Y Y S T E MM MM +// D D --- FFFF a a L L --- SSS Y SSS T EEE M M M +// D D F a aa L L S Y S T E M M +// DDDD F aa a LLLL LLLL SSSS Y SSSS T EEEEE M M +// +// +// DESCRIPTION: +// Constants that are used across multiple files +// +// ---------------------------------------------------------------------------------- + + +// ---------------------------------------------------------------------------------- +// U U +// U U +// U U +// U U +// UUU +// ---------------------------------------------------------------------------------- + + +// Conversions between degrees and radians +#define RAD2DEG 180.0/PI +#define DEG2RAD PI/180.0 + +// PI +#define PI 3.141592653589 + + + + + + +// ---------------------------------------------------------------------------------- +// +// +// +// +// +// ---------------------------------------------------------------------------------- + + + +// The types, i.e., agent or coordinator +#define TYPE_INVALID -1 +#define TYPE_COORDINATOR 1 +#define TYPE_AGENT 2 + + + + + + +// ---------------------------------------------------------------------------------- +// +// +// +// +// +// ---------------------------------------------------------------------------------- + + + +// These constants define the modes that can be used for controller this is +// running on-board the Crazyflie 2.0. +// Therefore, the constants defined here need to be in agreement with those +// defined in the firmware running on-board the Crazyflie 2.0. +// The following is a short description about each mode: +// +// CF_COMMAND_TYPE_MOTORS +// In this mode the Crazyflie will apply the requested 16-bit per motor +// command directly to each of the motors +// +// CF_COMMAND_TYPE_RATE +// In this mode the Crazyflie will apply the requested 16-bit per motor +// command directly to each of the motors, and additionally request the +// body frame roll, pitch, and yaw angular rates from the PID rate +// controllers implemented in the Crazyflie 2.0 firmware. +// +// CF_COMMAND_TYPE_ANGLE +// In this mode the Crazyflie will apply the requested 16-bit per motor +// command directly to each of the motors, and additionally request the +// body frame roll, pitch, and yaw angles from the PID attitude +// controllers implemented in the Crazyflie 2.0 firmware. +#define CF_COMMAND_TYPE_MOTORS 6 +#define CF_COMMAND_TYPE_RATE 7 +#define CF_COMMAND_TYPE_ANGLE 8 + +// Types of controllers being used: +#define SAFE_CONTROLLER 1 +#define DEMO_CONTROLLER 2 +#define STUDENT_CONTROLLER 3 +#define MPC_CONTROLLER 4 +#define REMOTE_CONTROLLER 5 +#define TUNING_CONTROLLER 6 +#define PICKER_CONTROLLER 7 + +// The constants that "command" changes in the +// operation state of this agent +#define CMD_USE_SAFE_CONTROLLER 1 +#define CMD_USE_DEMO_CONTROLLER 2 +#define CMD_USE_STUDENT_CONTROLLER 3 +#define CMD_USE_MPC_CONTROLLER 4 +#define CMD_USE_REMOTE_CONTROLLER 5 +#define CMD_USE_TUNING_CONTROLLER 6 +#define CMD_USE_PICKER_CONTROLLER 7 + + +#define CMD_CRAZYFLY_TAKE_OFF 11 +#define CMD_CRAZYFLY_LAND 12 +#define CMD_CRAZYFLY_MOTORS_OFF 13 + +// Flying states +#define STATE_MOTORS_OFF 1 +#define STATE_TAKE_OFF 2 +#define STATE_FLYING 3 +#define STATE_LAND 4 +#define STATE_UNAVAILABLE 5 + + +// Commands for CrazyRadio +#define CMD_RECONNECT 0 +#define CMD_DISCONNECT 1 + + +// CrazyRadio states: +#define CRAZY_RADIO_STATE_CONNECTED 0 +#define CRAZY_RADIO_STATE_CONNECTING 1 +#define CRAZY_RADIO_STATE_DISCONNECTED 2 + + + + +// ---------------------------------------------------------------------------------- +// BBBB A TTTTT TTTTT EEEEE RRRR Y Y +// B B A A T T E R R Y Y +// BBBB A A T T EEE RRRR Y +// B B AAAAA T T E R R Y +// BBBB A A T T EEEEE R R Y +// ---------------------------------------------------------------------------------- + +// Battery levels +#define BATTERY_LEVEL_000 0 +#define BATTERY_LEVEL_010 1 +#define BATTERY_LEVEL_020 2 +#define BATTERY_LEVEL_030 3 +#define BATTERY_LEVEL_040 4 +#define BATTERY_LEVEL_050 5 +#define BATTERY_LEVEL_060 6 +#define BATTERY_LEVEL_070 7 +#define BATTERY_LEVEL_080 8 +#define BATTERY_LEVEL_090 9 +#define BATTERY_LEVEL_100 10 +#define BATTERY_LEVEL_UNAVAILABLE -1 + +// Battery states +#define BATTERY_STATE_NORMAL 0 +#define BATTERY_STATE_LOW 1 + + + + + +// ---------------------------------------------------------------------------------- +// Y Y A M M L +// Y Y A A MM MM L +// Y A A M M M L +// Y AAAAA M M L +// Y A A M M LLLLL +// ---------------------------------------------------------------------------------- + +// For where to load the yaml file from +#define LOAD_YAML_FROM_AGENT 1 +#define LOAD_YAML_FROM_COORDINATOR 2 + + + + + +// ---------------------------------------------------------------------------------- +// +// +// +// +// +// ---------------------------------------------------------------------------------- + +// For standard buttons in the GUI +#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID 100 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +// OLD STUFF FOR LOADING YAML FILES +// For which controller parameters to load from file +#define LOAD_YAML_SAFE_CONTROLLER_AGENT 1 +#define LOAD_YAML_DEMO_CONTROLLER_AGENT 2 +#define LOAD_YAML_STUDENT_CONTROLLER_AGENT 3 +#define LOAD_YAML_MPC_CONTROLLER_AGENT 4 +#define LOAD_YAML_REMOTE_CONTROLLER_AGENT 5 +#define LOAD_YAML_TUNING_CONTROLLER_AGENT 6 +#define LOAD_YAML_PICKER_CONTROLLER_AGENT 7 + +#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR 11 +#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR 12 +#define LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR 13 +#define LOAD_YAML_MPC_CONTROLLER_COORDINATOR 14 +#define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR 15 +#define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR 16 +#define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR 17 + + +// For sending commands to the controller node informing +// which parameters to fetch +// > NOTE: these are identical to the #defines above, but +// used because they have the name distinguishes +// between: +// - "loading" a yaml file into ram +// - "fetching" the values that were loaded into ram +#define FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT 1 +#define FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT 2 +#define FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT 3 +#define FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT 4 +#define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT 5 +#define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT 6 +#define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT 7 + +#define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR 11 +#define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR 12 +#define FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR 13 +#define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR 14 +#define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR 15 +#define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR 16 +#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR 17 \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h index c25a843d718c0802e87beea70de7812a9d329482..2a85b0fc3bbc6f73d4db68b331f66585067413e8 100755 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h @@ -41,9 +41,4 @@ #define FROM_CENTIMETERS_TO_UNITS 1 #define FROM_MILIMETERS_TO_UNITS 0.1 -#define PI 3.1415926 - -#define FROM_RADIANS_TO_DEGREES 180.0/PI -#define FROM_DEGREES_TO_RADIANS PI/180.0 - #endif diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h index e0f696ccec790c74bfa7b3a87acf7c446ef766c8..e9fa132020ba0d73e56e5f9282863c048ecfe385 100755 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h @@ -58,28 +58,19 @@ #include "dfall_pkg/CrazyflieDB.h" #include "dfall_pkg/CrazyflieEntry.h" +// Include the shared definitions +#include "nodes/Constants.h" -// The constants that are sent to the agents in order to -// "command" changes in their operation state -#define CMD_USE_SAFE_CONTROLLER 1 -#define CMD_USE_CUSTOM_CONTROLLER 2 -#define CMD_CRAZYFLY_TAKE_OFF 3 -#define CMD_CRAZYFLY_LAND 4 -#define CMD_CRAZYFLY_MOTORS_OFF 5 +// Include other classes +#include "classes/GetParamtersAndNamespaces.h" -// The constants that are sent to the agents in order to -// adjust their radio connection -#define CMD_RECONNECT 0 -#define CMD_DISCONNECT 1 -// For which controller parameters to load -#define LOAD_YAML_SAFE_CONTROLLER_AGENT 1 -#define LOAD_YAML_CUSTOM_CONTROLLER_AGENT 2 -#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR 3 -#define LOAD_YAML_CUSTOM_CONTROLLER_COORDINATOR 4 +using namespace dfall_pkg; -using namespace dfall_pkg; +#else +// Include the shared definitions +#include "include/constants_for_qt_compile.h" #endif @@ -171,12 +162,14 @@ private slots: void on_load_from_DB_button_clicked(); - #ifdef CATKIN_MAKE +#ifdef CATKIN_MAKE void updateNewViconData(const ptrToMessage& p_msg); - #endif +#endif + void on_checkBox_vicon_crazyflies_toggled(bool checked); void on_scaleSpinBox_valueChanged(double arg1); + void on_refresh_cfs_button_clicked(); void on_refresh_student_ids_button_clicked(); @@ -188,27 +181,13 @@ private slots: void updateComboBoxes(); void setTabIndex(int index); + void doTabClosed(int tab_index); void on_comboBoxCFs_currentTextChanged(const QString &arg1); - - // For the buttons that "command" all of the agent nodes - // > For the radio connection - void on_all_connect_button_clicked(); - void on_all_disconnect_button_clicked(); - // > For changing the operation state - void on_all_take_off_button_clicked(); - void on_all_land_button_clicked(); - void on_all_motors_off_button_clicked(); - void on_all_enable_safe_controller_button_clicked(); - void on_all_enable_custom_controller_button_clicked(); - // > For loading the parameter - void on_all_load_safe_controller_yaml_own_agent_button_clicked(); - void on_all_load_custom_controller_yaml_own_agent_button_clicked(); - // > For sending a message with updated parameters - void on_all_load_safe_controller_yaml_coordinator_button_clicked(); - void on_all_load_custom_controller_yaml_coordinator_button_clicked(); + // For the emergency stop button + void on_emergency_stop_button_clicked(); private: @@ -219,14 +198,6 @@ private: void _init(); #ifdef CATKIN_MAKE - ros::Timer m_timer_yaml_file_for_safe_controller; - ros::Timer m_timer_yaml_file_for_custom_controller; - - void safeYamlFileTimerCallback(const ros::TimerEvent&); - void customYamlFileTimerCallback(const ros::TimerEvent&); - - void customSendYamlAsMessageTimerCallback(const ros::TimerEvent&); - float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name); void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length); int getParameterInt(ros::NodeHandle& nodeHandle, std::string name); @@ -236,7 +207,7 @@ private: #endif - #ifdef CATKIN_MAKE +#ifdef CATKIN_MAKE rosNodeThread* _rosNodeThread; std::vector<Marker*> markers_vector; std::vector<crazyFly*> crazyflies_vector; @@ -246,26 +217,7 @@ private: //ros::Publisher DBChangedPublisher; ros::Publisher emergencyStopPublisher; - - // Publsher for sending "commands" from here (the master) to all - // of the agent nodes (where a "command" is the integer that - // gives the directive to "take-off", "land, "motors-off", etc...) - ros::Publisher commandAllAgentsPublisher; - - // Publisher for sending a request from here (the master) to all "Parameter Service" nodes - // that it should re-load parameters from the YAML file for the controllers. - // > This is recieved and acted on by both Coordinate and Agent type "Parameter Services", - // > A coordinator type "Parameter Service" will subsequently request the agents to fetch - // the parameters from itself. - // > A agent type "Parameter Service" will subsequently request its own agent to fetch - // the parameters from itself. - ros::Publisher requestLoadControllerYamlPublisher; - - // Publisher for sending a request from here (the master) to all - // of the agents nodes that they should (re/dis)-connect from - // the Crazy-Radio - ros::Publisher crazyRadioCommandAllAgentsPublisher; - #endif +#endif void updateComboBoxesCFs(); diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp index d83ccd4e464d1060e58ef03ec5c410dbbccafb29..8d40b6eb34e32b25f04a85b4ad78fd5779a17b0b 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp @@ -88,7 +88,7 @@ void crazyFly::updateCF(const CrazyflieData* p_crazyfly_msg) this->setPos(m_x * FROM_METERS_TO_UNITS, -m_y * FROM_METERS_TO_UNITS); // - y because of coordinates - this->setRotation(- m_yaw * FROM_RADIANS_TO_DEGREES); //negative beacause anti-clock wise should be positive + this->setRotation(- m_yaw * RAD2DEG); //negative beacause anti-clock wise should be positive } } diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp index 1fb3cf4afd571961402a08197b511d98e990ee91..3b495f9f1ba0499d5b380b8814305ed115ed19c8 100755 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp @@ -260,7 +260,7 @@ void MainGUIWindow::_init() // Add keyboard shortcuts // > for "all motors off", press the space bar - ui->all_motors_off_button->setShortcut(tr("Space")); + ui->emergency_stop_button->setShortcut(tr("Space")); // > for "kill GUI node", press "CTRL+C" while the GUI window is the focus QShortcut* close_GUI_shortcut = new QShortcut(QKeySequence(tr("CTRL+C")), this, SLOT(close())); @@ -280,24 +280,6 @@ void MainGUIWindow::_init() // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM ros::NodeHandle nodeHandle_dfall_root("/dfall"); emergencyStopPublisher = nodeHandle_dfall_root.advertise<dfall_pkg::IntWithHeader>("emergencyStop", 1); - - // Initialise the publisher for sending "commands" from here (the master) - // to all of the agent nodes - commandAllAgentsPublisher = nodeHandle.advertise<std_msgs::Int32>("commandAllAgents", 1); - - // Publisher for sending a request from here (the master) to all "Parameter Service" nodes - // that it should re-load parameters from the YAML file for the controllers. - // > This is recieved and acted on by both Coordinate and Agent type "Parameter Services", - // > A coordinator type "Parameter Service" will subsequently request the agents to fetch - // the parameters from itself. - // > A agent type "Parameter Service" will subsequently request its own agent to fetch - // the parameters from itself. - requestLoadControllerYamlPublisher = nodeHandle.advertise<std_msgs::Int32>("requestLoadControllerYaml", 1); - - // Initialise the publisher for sending a request from here (the master) - // to all of the agents nodes that they should (re/dis)-connect from - // the Crazy-Radio - crazyRadioCommandAllAgentsPublisher = nodeHandle.advertise<std_msgs::Int32>("crazyRadioCommandAllAgents", 1); #endif } @@ -1084,322 +1066,27 @@ void MainGUIWindow::on_comboBoxCFs_currentTextChanged(const QString &arg1) // ---------------------------------------------------------------------------------- -// CCCC OOO M M M M A N N DDDD A L L -// C O O MM MM MM MM A A NN N D D A A L L -// C O O M M M M M M A A N N N D D A A L L -// C O O M M M M AAAAA N NN D D AAAAA L L -// CCCC OOO M M M M A A N N DDDD A A LLLLL LLLLL +// EEEEE M M EEEEE RRRR GGGG EEEEE N N CCCC Y Y +// E MM MM E R R G E NN N C Y Y +// EEE M M M EEE RRRR G GG EEE N N N C Y +// E M M E R R G G E N NN C Y +// EEEEE M M EEEEE R R GGG EEEEE N N CCCC Y // -// BBBB U U TTTTT TTTTT OOO N N SSSS -// B B U U T T O O NN N S -// BBBB U U T T O O N N N SSS -// B B U U T T O O N NN S -// BBBB UUU T T OOO N N SSSS +// SSSS TTTTT OOO PPPP +// S T O O P P +// SSS T O O PPPP +// S T O O P +// SSSS T OOO P // ---------------------------------------------------------------------------------- -// For the buttons that commands all of the agent nodes to: -// > (RE)CONNECT THE RADIO -void MainGUIWindow::on_all_connect_button_clicked() -{ -// std_msgs::Int32 msg; -// msg.data = CMD_RECONNECT; -// crazyRadioCommandAllAgentsPublisher.publish(msg); -} -// > DISCONNECT THE RADIO -void MainGUIWindow::on_all_disconnect_button_clicked() -{ -// std_msgs::Int32 msg; -// msg.data = CMD_DISCONNECT; -// crazyRadioCommandAllAgentsPublisher.publish(msg); -} -// > TAKE-OFF -void MainGUIWindow::on_all_take_off_button_clicked() -{ -// std_msgs::Int32 msg; -// msg.data = CMD_CRAZYFLY_TAKE_OFF; -// commandAllAgentsPublisher.publish(msg); -} -// > LAND -void MainGUIWindow::on_all_land_button_clicked() -{ -// std_msgs::Int32 msg; -// msg.data = CMD_CRAZYFLY_LAND; -// commandAllAgentsPublisher.publish(msg); -} -// > MOTORS OFF -void MainGUIWindow::on_all_motors_off_button_clicked() +// > EMERGENCY STOP +void MainGUIWindow::on_emergency_stop_button_clicked() { #ifdef CATKIN_MAKE dfall_pkg::IntWithHeader msg; msg.data = CMD_CRAZYFLY_MOTORS_OFF; msg.shouldCheckForAgentID = false; - //commandAllAgentsPublisher.publish(msg); emergencyStopPublisher.publish(msg); #endif } -// > ENABLE SAFE CONTROLLER -void MainGUIWindow::on_all_enable_safe_controller_button_clicked() -{ -// std_msgs::Int32 msg; -// msg.data = CMD_USE_SAFE_CONTROLLER; -// commandAllAgentsPublisher.publish(msg); -} -// > ENABLE SAFE CONTROLLER -void MainGUIWindow::on_all_enable_custom_controller_button_clicked() -{ -// std_msgs::Int32 msg; -// msg.data = CMD_USE_CUSTOM_CONTROLLER; -// commandAllAgentsPublisher.publish(msg); -} -// > LOAD THE YAML PARAMETERS FOR THE SAFE CONTROLLER -void MainGUIWindow::on_all_load_safe_controller_yaml_own_agent_button_clicked() -{ -// // Disable the button -// ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false); -// ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false); - -// // Send the message that the YAML paremters should be loaded -// std_msgs::Int32 msg; -// msg.data = LOAD_YAML_SAFE_CONTROLLER_AGENT; -// requestLoadControllerYamlPublisher.publish(msg); - -// // Start a timer which will enable the button in its callback -// // > This is required because the agent node waits some time between -// // re-loading the values from the YAML file and then assigning then -// // to the local variable of the agent. -// // > Thus we use this timer to prevent the user from clicking the -// // button in the GUI repeatedly. -// ros::NodeHandle nodeHandle("~"); -// m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true); -} -// > LOAD THE YAML PARAMETERS FOR THE CUSTOM CONTROLLER -void MainGUIWindow::on_all_load_custom_controller_yaml_own_agent_button_clicked() -{ -// // Disable the button -// ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false); -// ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false); - -// // Send the message that the YAML paremters should be loaded -// std_msgs::Int32 msg; -// msg.data = LOAD_YAML_CUSTOM_CONTROLLER_AGENT; -// requestLoadControllerYamlPublisher.publish(msg); - -// // Start a timer which will enable the button in its callback -// // > This is required because the agent node waits some time between -// // re-loading the values from the YAML file and then assigning then -// // to the local variable of the agent. -// // > Thus we use this timer to prevent the user from clicking the -// // button in the GUI repeatedly. -// ros::NodeHandle nodeHandle("~"); -// m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true); - -} -// > SEND THE YAML PARAMETERS FOR THE SAFE CONTROLLER -void MainGUIWindow::on_all_load_safe_controller_yaml_coordinator_button_clicked() -{ -// // Disable the button -// ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false); -// ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false); - -// // Send the message that the YAML paremters should be loaded -// // by the coordinator (and then the agent informed) -// std_msgs::Int32 msg; -// msg.data = LOAD_YAML_SAFE_CONTROLLER_COORDINATOR; -// requestLoadControllerYamlPublisher.publish(msg); - -// // Start a timer which will enable the button in its callback -// // > This is required because the agent node waits some time between -// // re-loading the values from the YAML file and then assigning then -// // to the local variable of the agent. -// // > Thus we use this timer to prevent the user from clicking the -// // button in the GUI repeatedly. -// ros::NodeHandle nodeHandle("~"); -// m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true); -} -// > SEND THE YAML PARAMETERS FOR THE CUSTOM CONTROLLER -void MainGUIWindow::on_all_load_custom_controller_yaml_coordinator_button_clicked() -{ -// // Disable the button -// ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false); -// ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false); - -// // Send the message that the YAML paremters should be loaded -// // by the coordinator (and then the agent informed) -// std_msgs::Int32 msg; -// msg.data = LOAD_YAML_CUSTOM_CONTROLLER_COORDINATOR; -// requestLoadControllerYamlPublisher.publish(msg); - -// // Start a timer which will enable the button in its callback -// // > This is required because the agent node waits some time between -// // re-loading the values from the YAML file and then assigning then -// // to the local variable of the agent. -// // > Thus we use this timer to prevent the user from clicking the -// // button in the GUI repeatedly. -// ros::NodeHandle nodeHandle("~"); -// m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true); - -} - -#ifdef CATKIN_MAKE -// > CALLBACK TO RE-ENABLE THE SAFE CONTROLLER YAML BUTTONS -void MainGUIWindow::safeYamlFileTimerCallback(const ros::TimerEvent&) -{ -// // Enble the "load" and the "send" safe controller YAML button again -// ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(true); -// ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(true); -} -// > CALLBACK TO RE-ENABLE THE CUSTOM CONTROLLER YAML BUTTONS -void MainGUIWindow::customYamlFileTimerCallback(const ros::TimerEvent&) -{ -// // Enble the "load" and the "send" custom controller YAML button again -// ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(true); -// ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(true); -} -#endif - -/* -// > CALLBACK TO SEND THE CUSTOM CONTROLLER YAML PARAMETERS AS A MESSAGE -void MainGUIWindow::customSendYamlAsMessageTimerCallback(const ros::TimerEvent&) -{ - // Load the CUSTOM controller YAML parameters from file into a message for - // sending directly to the "CustonControllerService" node of every agent - - ros::NodeHandle nodeHandle("~"); - - // Instaniate a local variable of the message type - CustomControllerYAML customControllerYamlMessage; - - // Load the data directly from the YAML file into the message - - // > For the mass - customControllerYamlMessage.mass = MainGUIWindow::getParameterFloat(nodeHandle, "mass"); - - // Debugging this this works - ROS_INFO_STREAM("DEBUGGING: mass loaded from the custom controller YAML = " << customControllerYamlMessage.mass ); - - // > For the control_frequency - customControllerYamlMessage.control_frequency = MainGUIWindow::getParameterFloat(nodeHandle, "control_frequency"); - - // > For the motorPoly coefficients - std::vector<float> temp_motorPoly(3); - MainGUIWindow::getParameterFloatVector(nodeHandle, "motorPoly", temp_motorPoly, 3); - // Copy the loaded data into the message - for ( int i=0 ; i<3 ; i++ ) - { - customControllerYamlMessage.motorPoly.push_back( temp_motorPoly[i] ); - } - - // > For the boolean about whether to execute the convert into body frame function - customControllerYamlMessage.shouldPerformConvertIntoBodyFrame = MainGUIWindow::getParameterBool(nodeHandle, "shouldPerformConvertIntoBodyFrame"); - - // > For the boolean about publishing the agents current position - customControllerYamlMessage.shouldPublishCurrent_xyz_yaw = MainGUIWindow::getParameterBool(nodeHandle, "shouldPublishCurrent_xyz_yaw"); - - // > For the boolean about following another agent - customControllerYamlMessage.shouldFollowAnotherAgent = MainGUIWindow::getParameterBool(nodeHandle, "shouldFollowAnotherAgent"); - - // > For the ordered agent ID's for following eachother in a line - std::vector<int> temp_follow_in_a_line_agentIDs(100); - int temp_number_of_agents_in_a_line = MainGUIWindow::getParameterIntVectorWithUnknownLength(nodeHandle, "follow_in_a_line_agentIDs", temp_follow_in_a_line_agentIDs); - // > Double check that the sizes agree - if ( temp_number_of_agents_in_a_line != temp_follow_in_a_line_agentIDs.size() ) - { - // Update the user if the sizes don't agree - ROS_ERROR_STREAM("parameter 'follow_in_a_line_agentIDs' was loaded with two different lengths, " << temp_number_of_agents_in_a_line << " versus " << temp_follow_in_a_line_agentIDs.size() ); - } - // Copy the loaded data into the message - for ( int i=0 ; i<temp_number_of_agents_in_a_line ; i++ ) - { - customControllerYamlMessage.follow_in_a_line_agentIDs.push_back( temp_follow_in_a_line_agentIDs[i] ); - } - - // Publish the message containing the loaded YAML parameters - customYAMLasMessagePublisher.publish(customControllerYamlMessage); - - // Start a timer which will enable the button in its callback - m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(0.5), &MainGUIWindow::customYamlFileTimerCallback, this, true); -} -*/ - - - - -// ---------------------------------------------------------------------------------- -// L OOO A DDDD Y Y A M M L -// L O O A A D D Y Y A A MM MM L -// L O O A A D D Y A A M M M L -// L O O AAAAA D D Y AAAAA M M L -// LLLLL OOO A A DDDD Y A A M M LLLLL -// -// PPPP A RRRR A M M EEEEE TTTTT EEEEE RRRR SSSS -// P P A A R R A A MM MM E T E R R S -// PPPP A A RRRR A A M M M EEE T EEE RRRR SSS -// P AAAAA R R AAAAA M M E T E R R S -// P A A R R A A M M EEEEE T EEEEE R R SSSS -// ---------------------------------------------------------------------------------- - - -#ifdef CATKIN_MAKE - -// load parameters from corresponding YAML file -// -float MainGUIWindow::getParameterFloat(ros::NodeHandle& nodeHandle, std::string name) -{ - float val; - if(!nodeHandle.getParam(name, val)) - { - ROS_ERROR_STREAM("missing parameter '" << name << "'"); - } - return val; -} - -void MainGUIWindow::getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length) -{ - if(!nodeHandle.getParam(name, val)){ - ROS_ERROR_STREAM("missing parameter '" << name << "'"); - } - if(val.size() != length) { - ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed"); - } -} - -int MainGUIWindow::getParameterInt(ros::NodeHandle& nodeHandle, std::string name) -{ - int val; - if(!nodeHandle.getParam(name, val)) - { - ROS_ERROR_STREAM("missing parameter '" << name << "'"); - } - return val; -} - -void MainGUIWindow::getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length) -{ - if(!nodeHandle.getParam(name, val)){ - ROS_ERROR_STREAM("missing parameter '" << name << "'"); - } - if(val.size() != length) { - ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed"); - } -} - -int MainGUIWindow::getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val) -{ - if(!nodeHandle.getParam(name, val)){ - ROS_ERROR_STREAM("missing parameter '" << name << "'"); - } - return val.size(); -} - -bool MainGUIWindow::getParameterBool(ros::NodeHandle& nodeHandle, std::string name) -{ - bool val; - if(!nodeHandle.getParam(name, val)) - { - ROS_ERROR_STREAM("missing parameter '" << name << "'"); - } - return val; -} - -#endif