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 226e5c459e4bb415bf29e291e0ea82ba8632fb05..d1a886d82c0a0c62004b539d9898bc2b9483e62e 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 @@ -7,7 +7,7 @@ <x>0</x> <y>0</y> <width>1494</width> - <height>536</height> + <height>597</height> </rect> </property> <property name="font"> @@ -89,9 +89,9 @@ </widget> </item> <item> - <widget class="QLabel" name="label_measured_title_line2"> + <widget class="QLabel" name="label_time_series_time"> <property name="text"> - <string>Position</string> + <string>Time series for x-position in meters</string> </property> <property name="alignment"> <set>Qt::AlignCenter</set> @@ -144,7 +144,7 @@ </widget> </item> <item row="6" column="0"> - <widget class="QPushButton" name="default_setpoint_button"> + <widget class="QPushButton" name="set_controller_parameters_button"> <property name="sizePolicy"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding"> <horstretch>0</horstretch> @@ -190,7 +190,7 @@ <number>0</number> </property> <item row="1" column="2"> - <widget class="QLineEdit" name="lineEdit_setpoint_new_z"> + <widget class="QLineEdit" name="lineEdit_alpha"> <property name="sizePolicy"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding"> <horstretch>0</horstretch> @@ -209,7 +209,7 @@ </font> </property> <property name="text"> - <string/> + <string>1.0</string> </property> <property name="alignment"> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> @@ -217,7 +217,7 @@ </widget> </item> <item row="1" column="0"> - <widget class="QLineEdit" name="lineEdit_setpoint_new_x"> + <widget class="QLineEdit" name="lineEdit_k"> <property name="sizePolicy"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding"> <horstretch>0</horstretch> @@ -236,7 +236,7 @@ </font> </property> <property name="text"> - <string/> + <string>0.1</string> </property> <property name="alignment"> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> @@ -244,7 +244,7 @@ </widget> </item> <item row="1" column="1"> - <widget class="QLineEdit" name="lineEdit_setpoint_new_y"> + <widget class="QLineEdit" name="lineEdit_T"> <property name="sizePolicy"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding"> <horstretch>0</horstretch> @@ -263,7 +263,7 @@ </font> </property> <property name="text"> - <string/> + <string>1.0</string> </property> <property name="alignment"> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> @@ -271,7 +271,7 @@ </widget> </item> <item row="0" column="0"> - <widget class="QLabel" name="label_row_x"> + <widget class="QLabel" name="label_k"> <property name="sizePolicy"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <horstretch>0</horstretch> @@ -287,7 +287,7 @@ </widget> </item> <item row="0" column="1"> - <widget class="QLabel" name="label_current_title_line2"> + <widget class="QLabel" name="label_T"> <property name="sizePolicy"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <horstretch>0</horstretch> @@ -303,7 +303,7 @@ </widget> </item> <item row="0" column="2"> - <widget class="QLabel" name="label_new_title_line2_2"> + <widget class="QLabel" name="label_alpha"> <property name="sizePolicy"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <horstretch>0</horstretch> @@ -335,7 +335,7 @@ <number>0</number> </property> <item row="0" column="0"> - <widget class="QLabel" name="label_new_title_line2"> + <widget class="QLabel" name="label_step_size"> <property name="sizePolicy"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <horstretch>0</horstretch> @@ -351,7 +351,7 @@ </widget> </item> <item row="1" column="0"> - <widget class="QLineEdit" name="lineEdit_custom_1"> + <widget class="QLineEdit" name="lineEdit_step_size"> <property name="sizePolicy"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding"> <horstretch>0</horstretch> @@ -364,6 +364,12 @@ <height>60</height> </size> </property> + <property name="text"> + <string>0.2</string> + </property> + <property name="alignment"> + <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> + </property> </widget> </item> </layout> 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 114d0b7b745ca33fd5d9fee0e333d29941eeafd8..28c6aca4deb1535c8c86488284ce7fa05378a6a8 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 @@ -106,21 +106,15 @@ private slots: void newDataForPerformingStepAndPlotting(float x); void analyseStepResponse(); - void on_lineEdit_setpoint_new_x_returnPressed(); - void on_lineEdit_setpoint_new_y_returnPressed(); - void on_lineEdit_setpoint_new_z_returnPressed(); - void on_lineEdit_setpoint_new_yaw_returnPressed(); + //void on_lineEdit_k_returnPressed(); + //void on_lineEdit_T_returnPressed(); + //void on_lineEdit_alpha_returnPressed(); + //void on_lineEdit_step_size_returnPressed(); - void on_set_setpoint_button_clicked(); - - void on_default_setpoint_button_clicked(); + void on_set_controller_parameters_button_clicked(); void on_perform_step_button_clicked(); - void on_custom_button_2_clicked(); - void on_custom_button_3_clicked(); - - @@ -142,6 +136,12 @@ private: bool m_shouldCoordinateAll = true; QMutex m_agentIDs_toCoordinate_mutex; + // For the current setpoints + float m_current_setpoint_x = 0.0; + float m_current_setpoint_y = 0.0; + float m_current_setpoint_z = 0.4; + float m_current_setpoint_yaw = 0.0; + // FOR PLOTTING DATA ON THE CHART // > Mutex for serialising acess to any charting variable QMutex m_chart_mutex; @@ -164,6 +164,9 @@ private: // > For requesting the setpoint to be changed ros::Publisher requestSetpointChangePublisher; + // > For requestion the controller paramters to be changed + ros::Publisher requestControllerParamterChangePublisher; + // SUBSCRIBER // > For being notified when the setpoint is changed ros::Subscriber setpointChangedSubscriber; @@ -182,9 +185,6 @@ private: // For receiving message that the setpoint was changed void setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint); - // Publish a message when a custom button is pressed - void publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer); - // Fill the header for a message void fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg ); void fillCustomButtonMessageHeader( dfall_pkg::CustomButtonWithHeader & msg ); @@ -195,6 +195,8 @@ private: void publishSetpoint(float x, float y, float z, float yaw_degrees); + void publishControllerParamters(float k, float T, float alpha); + }; #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 3be53160c55c8dde6c9d897f0703e99e228518c8..162a1b829c1c69577c6df17281cc9e201f4257b3 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 @@ -115,6 +115,9 @@ CsoneControllerTab::CsoneControllerTab(QWidget *parent) : // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("CsoneControllerService/RequestSetpointChange", 1); + // CREATE THE REQUEST CONTROLLER PARAMTER CHANGE PUBLISHER + requestControllerParamterChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("CsoneControllerService/RequestControllerParametersChange", 1); + // SUBSCRIBE TO SETPOINT CHANGES // Only if this is an agent GUI if (m_type == TYPE_AGENT) @@ -159,12 +162,6 @@ CsoneControllerTab::~CsoneControllerTab() // ---------------------------------------------------------------------------------- -// CCCC U U SSSS TTTTT OOO M M -// C U U S T O O MM MM -// C U U SSS T O O M M M -// C U U S T O O M M -// CCCC UUU SSSS T OOO M M -// // 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 @@ -173,30 +170,6 @@ CsoneControllerTab::~CsoneControllerTab() // ---------------------------------------------------------------------------------- -#ifdef CATKIN_MAKE -void CsoneControllerTab::publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer) -{ - // Initialise the message as a local variable - dfall_pkg::CustomButtonWithHeader msg; - // Fill the header of the message - fillCustomButtonMessageHeader( msg ); - // Fill in the button index - msg.button_index = button_index; - // Get the line edit data, as a float if possible - bool isValidFloat = false; - float lineEdit_as_float = (lineEdit_pointer->text()).toFloat(&isValidFloat); - // Fill in the data - if (isValidFloat) - msg.float_data = lineEdit_as_float; - else - msg.string_data = (lineEdit_pointer->text()).toStdString(); - // Publish the setpoint - this->customButtonPublisher.publish(msg); - // Inform the user about the change - ROS_INFO_STREAM("[CSONE CONTROLLER TAB GUI] button " << button_index << " clicked."); -} -#endif - void CsoneControllerTab::on_perform_step_button_clicked() { @@ -225,27 +198,133 @@ void CsoneControllerTab::on_perform_step_button_clicked() #endif } -void CsoneControllerTab::on_custom_button_2_clicked() + +void CsoneControllerTab::on_set_controller_parameters_button_clicked() { - m_lineSeries_for_setpoint_x->append(22, 6); - //ui->chartView_for_x->chart()->createDefaultAxes(); -#ifdef CATKIN_MAKE - publish_custom_button_command(2,ui->lineEdit_custom_2); -#endif + // Initialise local variable for each of (x,y,z,yaw) + float k = 1.0f, T = 1.0f, alpha = 1.0f; + + // Initialise a string variable for adding the "+" + QString qstr = ""; + + // Take the new value if available, otherwise use default + // > For k + if(!ui->lineEdit_k->text().isEmpty()) + { + k = (ui->lineEdit_k->text()).toFloat(); + // Ensure that it is in the range [0,100] + if (k < 0.0) + { + k = 0.0; + ui->lineEdit_k->setText(qstr + QString::number( k, 'f', 3)); + } + else if (T > 100.0) + { + k = 100.0; + ui->lineEdit_T->setText(qstr + QString::number( k, 'f', 3)); + } + } + else + { + ui->lineEdit_k->setText(qstr + QString::number( k, 'f', 3)); + } + + // > For T + if(!ui->lineEdit_T->text().isEmpty()) + { + T = (ui->lineEdit_T->text()).toFloat(); + // Ensure that it is in the range [0,100] + if (T < 0.0) + { + T = 0.0; + ui->lineEdit_T->setText(qstr + QString::number( T, 'f', 3)); + } + else if (T > 100.0) + { + T = 100.0; + ui->lineEdit_T->setText(qstr + QString::number( T, 'f', 3)); + } + } + else + { + ui->lineEdit_T->setText(qstr + QString::number( T, 'f', 3)); + } + + // > For T + if(!ui->lineEdit_alpha->text().isEmpty()) + { + alpha = (ui->lineEdit_alpha->text()).toFloat(); + // Ensure that it is in the range [0,100] + if (alpha < 0.0) + { + alpha = 0.0; + ui->lineEdit_alpha->setText(qstr + QString::number( alpha, 'f', 3)); + } + else if (T > 100.0) + { + T = 100.0; + ui->lineEdit_alpha->setText(qstr + QString::number( alpha, 'f', 3)); + } + } + else + { + ui->lineEdit_alpha->setText(qstr + QString::number( alpha, 'f', 3)); + } + + // Call the function to publish the setpoint + publishControllerParamters(k,T,alpha); } -void CsoneControllerTab::on_custom_button_3_clicked() + +void CsoneControllerTab::publishControllerParamters(float k, float T, float alpha) { - m_lineSeries_for_setpoint_x->append(22, 6); - ui->chartView_for_x->chart()->createDefaultAxes(); - ui->chartView_for_x->chart()->axisX()->setMax(24); #ifdef CATKIN_MAKE - publish_custom_button_command(3,ui->lineEdit_custom_3); + // Initialise the message as a local variable + dfall_pkg::SetpointWithHeader msg; + + // Fill the header of the message + fillSetpointMessageHeader( msg ); + + // Fill in the controller values + msg.x = k; + msg.y = T; + msg.z = alpha; + + // Publish the setpoint + this->requestControllerParamterChangePublisher.publish(msg); + + // Inform the user about the change + ROS_INFO_STREAM("[CSONE CONTROLLER GUI] Published request for setpoint change to: [" << k << ", "<< T << ", "<< alpha << "]"); +#else + // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator" + QTextStream(stdout) << "[CSONE CONTROLLER GUI] would publish request for: [" << k << ", "<< T << ", "<< alpha << "]"; #endif } +//void CsoneControllerTab::on_lineEdit_k_returnPressed() +//{ +// ui->set_setpoint_button->animateClick(); +//} + +//void CsoneControllerTab::on_lineEdit_T_returnPressed() +//{ +// ui->set_setpoint_button->animateClick(); +//} + +//void CsoneControllerTab::on_lineEdit_alpha_returnPressed() +//{ +// ui->set_setpoint_button->animateClick(); +//} + +//void CsoneControllerTab::on_lineEdit_step_size_returnPressed() +//{ +// ui->set_setpoint_button->animateClick(); +//} + + + // ---------------------------------------------------------------------------------- @@ -262,23 +341,6 @@ void CsoneControllerTab::setMeasuredPose(float x , float y , float z , float rol // Check if the object is occluded for this data if (!occluded) { - // INITIALISE A STRING VARIABLE FOR ADDING THE "+" - QString qstr = ""; - // UPDATE THE MEASUREMENT COLUMN - if (x < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_measured_x->setText(qstr + QString::number( x, 'f', 3)); - if (y < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_measured_y->setText(qstr + QString::number( y, 'f', 3)); - if (z < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', 3)); - - if (roll < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_measured_roll->setText(qstr + QString::number( roll * RAD2DEG, 'f', 1)); - if (pitch < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1)); - if (yaw < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 1)); - // Ensure the red frames are not visible if ( ui->red_frame_position_left->isVisible() ) ui->red_frame_position_left->setVisible(false); @@ -308,13 +370,13 @@ void CsoneControllerTab::setMeasuredPose(float x , float y , float z , float rol void CsoneControllerTab::poseDataUnavailableSlot() { - ui->lineEdit_measured_x->setText("xx.xx"); - ui->lineEdit_measured_y->setText("xx.xx"); - ui->lineEdit_measured_z->setText("xx.xx"); +// ui->lineEdit_measured_x->setText("xx.xx"); +// ui->lineEdit_measured_y->setText("xx.xx"); +// ui->lineEdit_measured_z->setText("xx.xx"); - ui->lineEdit_measured_roll->setText("xx.xx"); - ui->lineEdit_measured_pitch->setText("xx.xx"); - ui->lineEdit_measured_yaw->setText("xx.xx"); +// ui->lineEdit_measured_roll->setText("xx.xx"); +// ui->lineEdit_measured_pitch->setText("xx.xx"); +// ui->lineEdit_measured_yaw->setText("xx.xx"); } @@ -336,8 +398,9 @@ void CsoneControllerTab::newDataForPerformingStepAndPlotting(float x) if (m_shouldStoreData_for_plotting) { // Add the data to the line series - float temp_x_setpoint = (ui->lineEdit_setpoint_current_x->text()).toFloat(); - m_lineSeries_for_setpoint_x->append(m_time_for_step, (ui->lineEdit_setpoint_current_x->text()).toFloat() ); + //float temp_x_setpoint = (ui->lineEdit_setpoint_current_x->text()).toFloat(); + float temp_x_setpoint = m_current_setpoint_x; + m_lineSeries_for_setpoint_x->append(m_time_for_step, temp_x_setpoint ); m_lineSeries_for_measured_x->append(m_time_for_step, x ); // Reset the min, max, and rezoom time at the start of performing the step @@ -364,17 +427,23 @@ void CsoneControllerTab::newDataForPerformingStepAndPlotting(float x) // Set the flag so that we do not enter this loop again m_shouldPerformStep = false; - // Extract the current setpoints - float current_x = (ui->lineEdit_setpoint_current_x->text()).toFloat(); - float current_y = (ui->lineEdit_setpoint_current_y->text()).toFloat(); - float current_z = (ui->lineEdit_setpoint_current_z->text()).toFloat(); - float current_yaw = (ui->lineEdit_setpoint_current_yaw->text()).toFloat(); + // Extract the current step size + float step_size = (ui->lineEdit_step_size->text()).toFloat(); // Determine the new x setpoint - float new_x = -current_x; + float new_x = 0.0; + if (x < 0) + new_x = 0.5 * step_size; + else + new_x = -0.5 * step_size; + + // Specify the default setpoints for (y,z,yaw) + float default_y = m_current_setpoint_y; + float default_z = m_current_setpoint_z; + float default_yaw = m_current_setpoint_yaw; // Publish the new setpoint - publishSetpoint(new_x,current_y,current_z,current_yaw); + publishSetpoint(new_x,default_y,default_z,default_yaw); } } @@ -601,16 +670,11 @@ void CsoneControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWithHe // Lock the mutex m_chart_mutex.lock(); - // UPDATE THE SETPOINT COLUMN - if (x < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_setpoint_current_x->setText(qstr + QString::number( x, 'f', 3)); - if (y < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_setpoint_current_y->setText(qstr + QString::number( y, 'f', 3)); - if (z < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_setpoint_current_z->setText(qstr + QString::number( z, 'f', 3)); - - if (yaw < 0.0f) qstr = ""; else qstr = "+"; - ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 1)); + // Update the class variables for the current setpoint + m_current_setpoint_x = x; + m_current_setpoint_y = y; + m_current_setpoint_z = z; + m_current_setpoint_yaw = yaw; // Unlock the mutex m_chart_mutex.unlock(); @@ -669,88 +733,6 @@ void CsoneControllerTab::publishSetpoint(float x, float y, float z, float yaw_de -void CsoneControllerTab::on_lineEdit_setpoint_new_x_returnPressed() -{ - ui->set_setpoint_button->animateClick(); -} - -void CsoneControllerTab::on_lineEdit_setpoint_new_y_returnPressed() -{ - ui->set_setpoint_button->animateClick(); -} - -void CsoneControllerTab::on_lineEdit_setpoint_new_z_returnPressed() -{ - ui->set_setpoint_button->animateClick(); -} - -void CsoneControllerTab::on_lineEdit_setpoint_new_yaw_returnPressed() -{ - ui->set_setpoint_button->animateClick(); -} - -void CsoneControllerTab::on_set_setpoint_button_clicked() -{ - // Lock the mutex - m_chart_mutex.lock(); - - // Initialise local variable for each of (x,y,z,yaw) - float x = 0.0f, y = 0.0f, z = 0.0f, yaw = 0.0f; - - // Take the new value if available, otherwise use the old value - // > For x - if(!ui->lineEdit_setpoint_new_x->text().isEmpty()) - x = (ui->lineEdit_setpoint_new_x->text()).toFloat(); - else - x = (ui->lineEdit_setpoint_current_x->text()).toFloat(); - // > For y - if(!ui->lineEdit_setpoint_new_y->text().isEmpty()) - y = (ui->lineEdit_setpoint_new_y->text()).toFloat(); - else - y = (ui->lineEdit_setpoint_current_y->text()).toFloat(); - // > For z - if(!ui->lineEdit_setpoint_new_z->text().isEmpty()) - z = (ui->lineEdit_setpoint_new_z->text()).toFloat(); - else - z = (ui->lineEdit_setpoint_current_z->text()).toFloat(); - // > For yaw - if(!ui->lineEdit_setpoint_new_yaw->text().isEmpty()) - yaw = (ui->lineEdit_setpoint_new_yaw->text()).toFloat(); - else - yaw = (ui->lineEdit_setpoint_current_yaw->text()).toFloat(); - - // Unlock the mutex - m_chart_mutex.unlock(); - - // Call the function to publish the setpoint - publishSetpoint(x,y,z,yaw); -} - -void CsoneControllerTab::on_default_setpoint_button_clicked() -{ -#ifdef CATKIN_MAKE - // Publish this as a blank setpoint with the - // "buttonID" field set appropriately - - // Initialise the message as a local variable - dfall_pkg::SetpointWithHeader msg; - - // Fill the header of the message - fillSetpointMessageHeader( msg ); - - // Fill in the (x,y,z,yaw) values - msg.buttonID = REQUEST_DEFAULT_SETPOINT_BUTTON_ID; - - // Publish the default setpoint button press - this->requestSetpointChangePublisher.publish(msg); - - // Inform the user about the change - ROS_INFO_STREAM("[CSONE CONTROLLER GUI] Published request for setpoint change to the default"); -#endif -} - - - // ---------------------------------------------------------------------------------- @@ -821,10 +803,10 @@ void CsoneControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool sh m_chart_mutex.lock(); // Set information back to the default - ui->lineEdit_setpoint_current_x->setText("xx.xx"); - ui->lineEdit_setpoint_current_y->setText("xx.xx"); - ui->lineEdit_setpoint_current_z->setText("xx.xx"); - ui->lineEdit_setpoint_current_yaw->setText("xx.xx"); + m_current_setpoint_x = 0.0; + m_current_setpoint_y = 0.0; + m_current_setpoint_z = 0.4; + m_current_setpoint_yaw = 0.0; // Unlock the mutex m_chart_mutex.unlock();