Skip to content
Snippets Groups Projects
Commit 1619928d authored by beuchatp's avatar beuchatp
Browse files

Added ROS connections in the Picker GUI. Next step to update the...

Added ROS connections in the Picker GUI. Next step to update the PickerControlService to the new standards (by mimicking the StudentControllerService
parent 33769a7a
No related branches found
No related tags found
No related merge requests found
...@@ -7,7 +7,7 @@ ...@@ -7,7 +7,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>1978</width> <width>1978</width>
<height>1188</height> <height>1312</height>
</rect> </rect>
</property> </property>
<property name="font"> <property name="font">
...@@ -2389,124 +2389,304 @@ ...@@ -2389,124 +2389,304 @@
</widget> </widget>
</item> </item>
<item row="22" column="4"> <item row="22" column="4">
<widget class="QLineEdit" name="lineEdit_measured_x"> <layout class="QHBoxLayout" name="horizontalLayout_20">
<property name="sizePolicy"> <property name="spacing">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed"> <number>0</number>
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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>
<property name="readOnly"> <item>
<bool>true</bool> <widget class="QLineEdit" name="lineEdit_measured_x">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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>
<widget class="QFrame" name="frame_x_unavailable">
<property name="minimumSize">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>20</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>
<spacer name="horizontalSpacer_2">
<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="22" column="8">
<layout class="QHBoxLayout" name="horizontalLayout_36">
<property name="spacing">
<number>0</number>
</property> </property>
</widget> <item>
<widget class="QLineEdit" name="lineEdit_measured_yaw">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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>
<widget class="QFrame" name="frame_yaw_unavailable">
<property name="minimumSize">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>20</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>
<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>
<item row="22" column="7"> <item row="22" column="7">
<widget class="QLineEdit" name="lineEdit_measured_z"> <layout class="QHBoxLayout" name="horizontalLayout_37">
<property name="sizePolicy"> <property name="spacing">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed"> <number>0</number>
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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> </property>
</widget> <item>
<widget class="QLineEdit" name="lineEdit_measured_z">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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>
<widget class="QFrame" name="frame_z_unavailable">
<property name="minimumSize">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>20</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>
<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>
</layout>
</item> </item>
<item row="22" column="6"> <item row="22" column="6">
<widget class="QLineEdit" name="lineEdit_measured_y"> <layout class="QHBoxLayout" name="horizontalLayout_38">
<property name="sizePolicy"> <property name="spacing">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed"> <number>0</number>
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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="22" column="8">
<widget class="QLineEdit" name="lineEdit_measured_yaw">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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> </property>
</widget> <item>
<widget class="QLineEdit" name="lineEdit_measured_y">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>180</width>
<height>16777215</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>
<widget class="QFrame" name="frame_y_unavailable">
<property name="minimumSize">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>20</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>
<spacer name="horizontalSpacer_5">
<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>
</layout> </layout>
</item> </item>
......
...@@ -2,7 +2,9 @@ ...@@ -2,7 +2,9 @@
#define PICKERCONTROLLERTAB_H #define PICKERCONTROLLERTAB_H
#include <QWidget> #include <QWidget>
#include <QMutex>
#include <QVector> #include <QVector>
#include <QTextStream>
#define DECIMAL_PLACES_POSITION 2 #define DECIMAL_PLACES_POSITION 2
#define DECIMAL_PLACES_ANGLE_DEGREES 1 #define DECIMAL_PLACES_ANGLE_DEGREES 1
...@@ -11,13 +13,13 @@ ...@@ -11,13 +13,13 @@
#define DEFAULT_INCREMENT_POSITION_XY 0.01 #define DEFAULT_INCREMENT_POSITION_XY 0.01
#define DEFAULT_INCREMENT_POSITION_Z 0.01 #define DEFAULT_INCREMENT_POSITION_Z 0.01
#define DEFAULT_INCREMENT_ANGLE_DEGREES 5 #define DEFAULT_INCREMENT_ANGLE_DEGREES 5
#define DEFAULT_INCREMENT_MASS_GRAMS 1 #define DEFAULT_INCREMENT_MASS_GRAMS 0.5
#define PICKER_STATE_UNKNOWN -1 #define PICKER_STATE_UNKNOWN -1
#define PICKER_STATE_STANDBY 0 #define PICKER_STATE_STANDBY 0
#define PICKER_STATE_GOTO_START 1 #define PICKER_STATE_GOTO_START 1
#define PICKER_STATE_ATTACH 2 #define PICKER_STATE_ATTACH 2
#define PICKER_STATE_LIFT 3 #define PICKER_STATE_LIFT_UP 3
#define PICKER_STATE_GOTO_END 4 #define PICKER_STATE_GOTO_END 4
#define PICKER_STATE_PUT_DOWN 5 #define PICKER_STATE_PUT_DOWN 5
#define PICKER_STATE_SQUAT 6 #define PICKER_STATE_SQUAT 6
...@@ -29,6 +31,36 @@ ...@@ -29,6 +31,36 @@
#define PICKER_DEFAULT_YAW_DEGREES 0 #define PICKER_DEFAULT_YAW_DEGREES 0
#define PICKER_DEFAULT_MASS_GRAMS 30 #define PICKER_DEFAULT_MASS_GRAMS 30
#ifdef CATKIN_MAKE
#include <ros/ros.h>
#include <ros/network.h>
#include <ros/package.h>
// Include the standard message types
//#include "std_msgs/Int32.h"
//#include "std_msgs/Float32.h"
//#include <std_msgs/String.h>
// Include the DFALL message types
//#include "d_fall_pps/IntWithHeader.h"
#include "d_fall_pps/SetpointWithHeader.h"
//#include "d_fall_pps/CustomButtonWithHeader.h"
// Include the DFALL service types
#include "d_fall_pps/GetSetpointService.h"
// Include the shared definitions
#include "nodes/Constants.h"
// SPECIFY THE PACKAGE NAMESPACE
//using namespace d_fall_pps;
#else
// Include the shared definitions
#include "include/Constants_for_Qt_compile.h"
#endif
namespace Ui { namespace Ui {
...@@ -43,12 +75,14 @@ public: ...@@ -43,12 +75,14 @@ public:
explicit PickerControllerTab(QWidget *parent = 0); explicit PickerControllerTab(QWidget *parent = 0);
~PickerControllerTab(); ~PickerControllerTab();
private:
int current_picker_state = PICKER_STATE_STANDBY;
void publish_setpoint_if_current_state_matches(QVector<int> state_to_match);
void publish_request_setpoint_change_for_state(int state_to_publish); public slots:
void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
void poseDataUnavailableSlot();
private slots: private slots:
void on_button_goto_start_clicked(); void on_button_goto_start_clicked();
...@@ -201,8 +235,58 @@ private slots: ...@@ -201,8 +235,58 @@ private slots:
void on_lineEdit_increment_mass_editingFinished(); void on_lineEdit_increment_mass_editingFinished();
private: private:
Ui::PickerControllerTab *ui; Ui::PickerControllerTab *ui;
// --------------------------------------------------- //
// PRIVATE VARIABLES
// The type of this node, i.e., agent or a coordinator,
// specified as a parameter in the "*.launch" file
int m_type = 0;
// The ID of this node
int m_ID;
// For coordinating multiple agents
std::vector<int> m_vector_of_agentIDs_toCoordinate;
bool m_shouldCoordinateAll = true;
QMutex m_agentIDs_toCoordinate_mutex;
// THE CURRENT STATE OF THE PICKER
int current_picker_state = PICKER_STATE_STANDBY;
#ifdef CATKIN_MAKE
// PUBLISHER
// > For requesting the setpoint to be changed
ros::Publisher requestSetpointChangePublisher;
// SUBSCRIBER
// > For being notified when the setpoint is changed
ros::Subscriber setpointChangedSubscriber;
#endif
// --------------------------------------------------- //
// PRIVATE FUNCTIONS
#ifdef CATKIN_MAKE
// For receiving message that the setpoint was changed
void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
// Fill the header for a message
void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
// Get the paramters that specify the type and ID
bool getTypeAndIDParameters();
#endif
void publish_setpoint_if_current_state_matches(QVector<int> state_to_match);
void publish_request_setpoint_change_for_state(int state_to_publish);
}; };
#endif // PICKERCONTROLLERTAB_H #endif // PICKERCONTROLLERTAB_H
...@@ -2,6 +2,7 @@ float64 x ...@@ -2,6 +2,7 @@ float64 x
float64 y float64 y
float64 z float64 z
float64 yaw float64 yaw
float64 mass
bool isChecked bool isChecked
uint32 buttonID uint32 buttonID
bool shouldCheckForAgentID bool shouldCheckForAgentID
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment