diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/csonecontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/csonecontrollertab.ui index 20626a719c5b1e82026169fd726c613d4107f1bc..2e7d1709c5308eb6bce359dcea610cdbda560c9e 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/csonecontrollertab.ui +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/csonecontrollertab.ui @@ -421,7 +421,23 @@ <property name="rightMargin"> <number>0</number> </property> - <item row="1" column="7"> + <item row="0" column="2"> + <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="8"> <layout class="QGridLayout" name="gridLayout_8"> <item row="2" column="0"> <widget class="QPushButton" name="reset_integrator_button"> @@ -479,7 +495,7 @@ </item> </layout> </item> - <item row="0" column="6"> + <item row="0" column="7"> <spacer name="horizontalSpacer_7"> <property name="orientation"> <enum>Qt::Horizontal</enum> @@ -495,7 +511,7 @@ </property> </spacer> </item> - <item row="0" column="4"> + <item row="0" column="5"> <spacer name="horizontalSpacer_3"> <property name="orientation"> <enum>Qt::Horizontal</enum> @@ -527,7 +543,7 @@ </property> </widget> </item> - <item row="0" column="9"> + <item row="0" column="10"> <spacer name="horizontalSpacer_2"> <property name="orientation"> <enum>Qt::Horizontal</enum> @@ -708,7 +724,7 @@ </item> </layout> </item> - <item row="1" column="2"> + <item row="1" column="3"> <layout class="QGridLayout" name="gridLayout_6"> <item row="1" column="0"> <widget class="QPushButton" name="set_pd_controller_parameters_button"> @@ -824,7 +840,7 @@ </item> </layout> </item> - <item row="0" column="5"> + <item row="0" column="6"> <widget class="QLabel" name="label_step_details"> <property name="font"> <font> @@ -840,7 +856,7 @@ </property> </widget> </item> - <item row="1" column="5"> + <item row="1" column="6"> <layout class="QGridLayout" name="gridLayout_4"> <property name="leftMargin"> <number>0</number> @@ -900,6 +916,11 @@ <height>60</height> </size> </property> + <property name="font"> + <font> + <family>Courier</family> + </font> + </property> <property name="text"> <string>0.2</string> </property> @@ -922,6 +943,11 @@ <height>60</height> </size> </property> + <property name="font"> + <font> + <family>Courier</family> + </font> + </property> <property name="text"> <string>10</string> </property> @@ -971,7 +997,7 @@ </layout> </item> <item row="0" column="1"> - <spacer name="horizontalSpacer"> + <spacer name="horizontalSpacer_pd_controller"> <property name="orientation"> <enum>Qt::Horizontal</enum> </property> @@ -986,7 +1012,7 @@ </property> </spacer> </item> - <item row="0" column="2"> + <item row="0" column="3"> <widget class="QLabel" name="label_pid_controller"> <property name="font"> <font> @@ -1002,7 +1028,7 @@ </property> </widget> </item> - <item row="0" column="7"> + <item row="0" column="8"> <widget class="QLabel" name="label_integrator"> <property name="font"> <font> @@ -1018,7 +1044,7 @@ </property> </widget> </item> - <item row="0" column="8"> + <item row="0" column="9"> <spacer name="horizontalSpacer_8"> <property name="orientation"> <enum>Qt::Horizontal</enum> @@ -1031,6 +1057,72 @@ </property> </spacer> </item> + <item row="1" column="2"> + <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>300</width> + <height>60</height> + </size> + </property> + <property name="font"> + <font> + <family>Courier</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> </layout> </item> <item row="7" column="0"> diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h index a468c4daf7acd7d9d9d21ae1561d6e5cb92747df..e45d064c2074037079ca66473d07ade7dd94d584 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h @@ -128,6 +128,8 @@ private slots: void on_set_lead_compensator_parameters_button_clicked(); + void on_set_time_delay_button_clicked(); + void on_toggle_integrator_button_clicked(); void on_reset_integrator_button_clicked(); @@ -136,6 +138,7 @@ private slots: void on_lineEdit_alpha_returnPressed(); void on_lineEdit_kp_returnPressed(); void on_lineEdit_kd_returnPressed(); + void on_lineEdit_time_delay_returnPressed(); void on_lineEdit_step_size_returnPressed(); void on_lineEdit_step_duration_returnPressed(); @@ -201,6 +204,9 @@ private: // > For requesting a change in the integrator state ros::Publisher requestIntegratorStateChangePublisher; + // > For requesting the time delay to be changed + ros::Publisher requestTimeDelayChangePublisher; + // SUBSCRIBER // > For being notified when the setpoint is changed ros::Subscriber setpointChangedSubscriber; @@ -240,6 +246,8 @@ private: void publishRequestForIntegratorStateChange(int flag_to_publish); + void publishRequestForTimeDelayChange(int time_delay_to_publish); + }; #endif // CSONECONTROLLERTAB_H diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp index 1c58ecd9a24461a58011dfc53886e9b0d1624115..a2114441b2c555939256e9580e1d7db5480bbdd6 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp @@ -47,6 +47,15 @@ CsoneControllerTab::CsoneControllerTab(QWidget *parent) : ui->red_frame_position_left->setVisible(false); ui->red_frame_position_right->setVisible(false); + // ------------------------------------------------------------- // + // HIDE THE PD CONTROLLER FIELDS + ui->label_pid_controller->hide(); + ui->label_kp->hide(); + ui->label_kd->hide(); + ui->lineEdit_kp->hide(); + ui->lineEdit_kd->hide(); + ui->set_pd_controller_parameters_button->hide(); + // ------------------------------------------------------------- // // SETUP THE CHART VIEW FOR THE X POSITION // @@ -157,6 +166,9 @@ CsoneControllerTab::CsoneControllerTab(QWidget *parent) : // CREATE THE REQUEST CONTROLLER PARAMTER CHANGE PUBLISHER requestControllerParamterChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("CsoneControllerService/RequestControllerParametersChange", 1); + // CREATE THE REQUEST CONTROLLER PARAMTER CHANGE PUBLISHER + requestTimeDelayChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::IntWithHeader>("CsoneControllerService/RequestTimeDelayChange", 1); + // CREATE THE REQUEST INTEGRATOR STATE CHANGE PUBLISHER requestIntegratorStateChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::IntWithHeader>("CsoneControllerService/RequestIntegratorStateChange", 1); @@ -402,7 +414,7 @@ void CsoneControllerTab::on_set_lead_compensator_parameters_button_clicked() k = 0.0; ui->lineEdit_k->setText(qstr + QString::number( k, 'f', 4)); } - else if (T > 100.0) + else if (k > 100.0) { k = 100.0; ui->lineEdit_k->setText(qstr + QString::number( k, 'f', 4)); @@ -461,6 +473,35 @@ void CsoneControllerTab::on_set_lead_compensator_parameters_button_clicked() +void CsoneControllerTab::on_set_time_delay_button_clicked() +{ + // Initialise local variable for the time delay + float time_delay_int = 0; + + // Take the new value if available, otherwise use default + if(!ui->lineEdit_time_delay->text().isEmpty()) + { + float time_delay_float = (ui->lineEdit_time_delay->text()).toFloat(); + // Ensure that it is in the range [0,1000] + if (time_delay_float < 0.0) + time_delay_int = 0; + else if (time_delay_float > 1000.0) + time_delay_int = 1000; + else + time_delay_int = int(time_delay_float); + } + else + { + time_delay_int = 0; + } + + // Put the value back into the line edit + ui->lineEdit_time_delay->setText( QString::number( time_delay_int, 'd', 0) ); + + // Call the function to publish the time delay + publishRequestForTimeDelayChange(time_delay_int); +} + void CsoneControllerTab::on_toggle_integrator_button_clicked() @@ -504,6 +545,11 @@ void CsoneControllerTab::on_lineEdit_kd_returnPressed() ui->set_pd_controller_parameters_button->animateClick(); } +void CsoneControllerTab::on_lineEdit_time_delay_returnPressed() +{ + ui->set_time_delay_button->animateClick(); +} + void CsoneControllerTab::on_lineEdit_step_size_returnPressed() { ui->perform_step_button->animateClick(); @@ -1056,6 +1102,33 @@ void CsoneControllerTab::publishRequestForIntegratorStateChange(int flag_to_publ + +void CsoneControllerTab::publishRequestForTimeDelayChange(int time_delay_to_publish) +{ +#ifdef CATKIN_MAKE + // Initialise the message as a local variable + dfall_pkg::IntWithHeader msg; + + // Fill the header of the message + fillIntMessageHeader( msg ); + + // Fill in the controller values + msg.data = time_delay_to_publish; + + // Publish the setpoint + this->requestTimeDelayChangePublisher.publish(msg); + + // Inform the user about the change + ROS_INFO_STREAM("[CSONE CONTROLLER GUI] Published request for time delay of " << time_delay_to_publish << " milliseconds"); +#else + // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator" + QTextStream(stdout) << "[CSONE CONTROLLER GUI] would publish request for time delay of " << time_delay_to_publish << " milliseconds"; +#endif +} + + + + // ---------------------------------------------------------------------------------- // A GGGG EEEEE N N TTTTT III DDDD SSSS // A A G E NN N T I D D S