Commit 3cc8eb8a authored by Alejandro's avatar Alejandro

Add button setHome to MapWidget

parent 552d4760
...@@ -315,6 +315,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -315,6 +315,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
currLossCounter = 0; currLossCounter = 0;
currReceiveCounter = 0; currReceiveCounter = 0;
emit receiveLossChanged(message.sysid, receiveLoss); emit receiveLossChanged(message.sysid, receiveLoss);
qDebug() << "LOSSCHANGED" << message.sysid<<" "<<receiveLoss;
} }
// The packet is emitted as a whole, as it is only 255 - 261 bytes short // The packet is emitted as a whole, as it is only 255 - 261 bytes short
......
...@@ -335,14 +335,6 @@ void MainWindow::buildCommonWidgets() ...@@ -335,14 +335,6 @@ void MainWindow::buildCommonWidgets()
addToToolsMenu (controlDockWidget, tr("Control"), SLOT(showToolWidget(bool)), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea); addToToolsMenu (controlDockWidget, tr("Control"), SLOT(showToolWidget(bool)), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea);
} }
if (!controlParameterWidget)
{
controlParameterWidget = new QDockWidget(tr("Control Parameters"), this);
controlParameterWidget->setObjectName("UNMANNED_SYSTEM_CONTROL_PARAMETERWIDGET");
controlParameterWidget->setWidget( new UASControlParameters(this) );
addToToolsMenu (controlParameterWidget, tr("Control Parameters"), SLOT(showToolWidget(bool)), MENU_UAS_CONTROL_PARAM, Qt::LeftDockWidgetArea);
}
if (!listDockWidget) if (!listDockWidget)
{ {
listDockWidget = new QDockWidget(tr("Unmanned Systems"), this); listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
...@@ -401,6 +393,14 @@ void MainWindow::buildCommonWidgets() ...@@ -401,6 +393,14 @@ void MainWindow::buildCommonWidgets()
dataplotWidget = new QGCDataPlot2D(this); dataplotWidget = new QGCDataPlot2D(this);
addToCentralWidgetsMenu (dataplotWidget, "Logfile Plot", SLOT(showCentralWidget()),CENTRAL_DATA_PLOT); addToCentralWidgetsMenu (dataplotWidget, "Logfile Plot", SLOT(showCentralWidget()),CENTRAL_DATA_PLOT);
} }
if (!controlParameterWidget)
{
controlParameterWidget = new QDockWidget(tr("Control Parameters"), this);
controlParameterWidget->setObjectName("UNMANNED_SYSTEM_CONTROL_PARAMETERWIDGET");
controlParameterWidget->setWidget( new UASControlParameters(this) );
addToToolsMenu (controlParameterWidget, tr("Control Parameters"), SLOT(showToolWidget(bool)), MENU_UAS_CONTROL_PARAM, Qt::LeftDockWidgetArea);
}
} }
......
...@@ -93,6 +93,8 @@ void MapWidget::init() ...@@ -93,6 +93,8 @@ void MapWidget::init()
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter); geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
mc->addLayer(geomLayer); mc->addLayer(geomLayer);
homePosition = new qmapcontrol::GeometryLayer("Station", mapadapter);
mc->addLayer(homePosition);
// //
...@@ -183,11 +185,17 @@ void MapWidget::init() ...@@ -183,11 +185,17 @@ void MapWidget::init()
goToButton->setToolTip(tr("Enter a latitude/longitude position to move the map to")); goToButton->setToolTip(tr("Enter a latitude/longitude position to move the map to"));
goToButton->setStatusTip(tr("Enter a latitude/longitude position to move the map to")); goToButton->setStatusTip(tr("Enter a latitude/longitude position to move the map to"));
setHome = new QPushButton(QIcon(":/images/actions/go-home.svg"), "", this);
setHome->setStyleSheet(buttonStyle);
setHome->setToolTip(tr("Set home"));
setHome->setStatusTip(tr("Set home"));
zoomin->setMaximumWidth(30); zoomin->setMaximumWidth(30);
zoomout->setMaximumWidth(30); zoomout->setMaximumWidth(30);
createPath->setMaximumWidth(30); createPath->setMaximumWidth(30);
// clearTracking->setMaximumWidth(30); // clearTracking->setMaximumWidth(30);
followgps->setMaximumWidth(30); followgps->setMaximumWidth(30);
setHome->setMaximumWidth(30);
goToButton->setMaximumWidth(30); goToButton->setMaximumWidth(30);
// Set checkable buttons // Set checkable buttons
...@@ -195,6 +203,7 @@ void MapWidget::init() ...@@ -195,6 +203,7 @@ void MapWidget::init()
// create a style and the slots to change the background so it is easier to distinguish // create a style and the slots to change the background so it is easier to distinguish
followgps->setCheckable(true); followgps->setCheckable(true);
createPath->setCheckable(true); createPath->setCheckable(true);
setHome->setCheckable(true);
// add buttons to control the map (zoom, GPS tracking and WP capture) // add buttons to control the map (zoom, GPS tracking and WP capture)
QGridLayout* innerlayout = new QGridLayout(mc); QGridLayout* innerlayout = new QGridLayout(mc);
...@@ -204,6 +213,7 @@ void MapWidget::init() ...@@ -204,6 +213,7 @@ void MapWidget::init()
innerlayout->addWidget(zoomout, 1, 0); innerlayout->addWidget(zoomout, 1, 0);
innerlayout->addWidget(followgps, 2, 0); innerlayout->addWidget(followgps, 2, 0);
innerlayout->addWidget(createPath, 3, 0); innerlayout->addWidget(createPath, 3, 0);
innerlayout->addWidget(setHome, 4, 0);
//innerlayout->addWidget(clearTracking, 4, 0); //innerlayout->addWidget(clearTracking, 4, 0);
// Add spacers to compress buttons on the top left // Add spacers to compress buttons on the top left
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 5, 0); innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 5, 0);
...@@ -262,6 +272,12 @@ void MapWidget::init() ...@@ -262,6 +272,12 @@ void MapWidget::init()
connect(createPath, SIGNAL(clicked(bool)), connect(createPath, SIGNAL(clicked(bool)),
this, SLOT(createPathButtonClicked(bool))); this, SLOT(createPathButtonClicked(bool)));
connect(setHome, SIGNAL(clicked(bool)), this, SLOT(createHomePositionClick(bool)));
connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*,QPointF)), this,
SLOT(createHomePosition(const QMouseEvent*,QPointF)));
//connect(setHome, SIGNAL(clicked(bool)), this, SLOT(createHomePosition(bool)));
connect(geomLayer, SIGNAL(geometryClicked(Geometry*,QPoint)), connect(geomLayer, SIGNAL(geometryClicked(Geometry*,QPoint)),
this, SLOT(captureGeometryClick(Geometry*, QPoint))); this, SLOT(captureGeometryClick(Geometry*, QPoint)));
...@@ -1199,3 +1215,46 @@ QPointF MapWidget::getPointxBearing_Range(double lat1, double lon1, double beari ...@@ -1199,3 +1215,46 @@ QPointF MapWidget::getPointxBearing_Range(double lat1, double lon1, double beari
return temp; return temp;
} }
void MapWidget::createHomePosition(const QMouseEvent *event, const QPointF coordinate)
{
if (QEvent::MouseButtonRelease == event->type() && setHome->isChecked())
{
homeCoordinate= coordinate;
Waypoint2DIcon* tempCirclePoint;
double latitud = homeCoordinate.x();
double longitud = homeCoordinate.y();
tempCirclePoint = new Waypoint2DIcon(
latitud,
longitud,
20, "g", qmapcontrol::Point::Middle);
QPen* pencil = new QPen(Qt::blue);
tempCirclePoint->setPen(pencil);
mc->layer("Station")->clearGeometries();
mc->layer("Station")->addGeometry(tempCirclePoint);
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(latitud, longitud,"g");
if (isVisible())
{
mc->updateRequest(tempPoint->boundingBox().toRect());
}
}
}
void MapWidget::createHomePositionClick(bool click)
{
Q_UNUSED(click);
if (!setHome->isChecked())
{
UASManager::instance()->setHomePosition(
static_cast<double>(homeCoordinate.x()),
static_cast<double>(homeCoordinate.y()), 0);
qDebug()<<"Set home position "<<homeCoordinate.x()<<" "<<homeCoordinate.y();
}
}
...@@ -118,6 +118,7 @@ protected: ...@@ -118,6 +118,7 @@ protected:
QPushButton* followgps; QPushButton* followgps;
QPushButton* createPath; QPushButton* createPath;
QPushButton* clearTracking; QPushButton* clearTracking;
QPushButton* setHome;
QLabel* gpsposition; QLabel* gpsposition;
QMenu* mapMenu; QMenu* mapMenu;
QPushButton* mapButton; QPushButton* mapButton;
...@@ -128,7 +129,7 @@ protected: ...@@ -128,7 +129,7 @@ protected:
qmapcontrol::Layer* overlay; ///< Street overlay (foreground) qmapcontrol::Layer* overlay; ///< Street overlay (foreground)
qmapcontrol::Layer* tracks; ///< Layer for UAV tracks qmapcontrol::Layer* tracks; ///< Layer for UAV tracks
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
qmapcontrol::GeometryLayer* homePosition; ///< Layer for station control
//only for experiment //only for experiment
qmapcontrol::GeometryLayer* camLayer; ///< Layer for camera indicator qmapcontrol::GeometryLayer* camLayer; ///< Layer for camera indicator
...@@ -163,6 +164,9 @@ protected: ...@@ -163,6 +164,9 @@ protected:
void createWaypointGraphAtMap(int id, const QPointF coordinate); void createWaypointGraphAtMap(int id, const QPointF coordinate);
void mapproviderSelected(QAction* action); void mapproviderSelected(QAction* action);
void createHomePosition(const QMouseEvent* event, const QPointF coordinate);
void createHomePositionClick(bool click);
signals: signals:
//void movePoint(QPointF newCoord); //void movePoint(QPointF newCoord);
//void captureMapCoordinateClick(const QPointF coordinate); //ROCA //void captureMapCoordinateClick(const QPointF coordinate); //ROCA
...@@ -188,6 +192,7 @@ private: ...@@ -188,6 +192,7 @@ private:
bool drawCamBorder; bool drawCamBorder;
int radioCamera; int radioCamera;
QPointF homeCoordinate;
}; };
#endif // MAPWIDGET_H #endif // MAPWIDGET_H
...@@ -84,7 +84,7 @@ ...@@ -84,7 +84,7 @@
<string notr="true"/> <string notr="true"/>
</property> </property>
<property name="currentIndex"> <property name="currentIndex">
<number>0</number> <number>1</number>
</property> </property>
<widget class="QWidget" name="tab"> <widget class="QWidget" name="tab">
<attribute name="title"> <attribute name="title">
...@@ -184,32 +184,30 @@ ...@@ -184,32 +184,30 @@
</attribute> </attribute>
<layout class="QGridLayout" name="gridLayout_3"> <layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0"> <item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_6"> <layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item> <item>
<widget class="QCheckBox" name="cxElevator"> <widget class="QCheckBox" name="cxdle_c">
<property name="text"> <property name="text">
<string>Elevator</string> <string>Elevator</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item>
<widget class="QCheckBox" name="cxRudder"> <widget class="QCheckBox" name="cxdr_c">
<property name="text"> <property name="text">
<string>Rudder</string> <string>Rudder</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item>
<widget class="QCheckBox" name="cxThrottle"> <widget class="QCheckBox" name="cxdt_c">
<property name="text"> <property name="text">
<string>Throttle</string> <string>Throttle</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item>
<widget class="QCheckBox" name="cxAilerons"> <widget class="QCheckBox" name="cxdla_c">
<property name="text"> <property name="text">
<string>Ailerons</string> <string>Ailerons</string>
</property> </property>
...@@ -217,40 +215,6 @@ ...@@ -217,40 +215,6 @@
</item> </item>
</layout> </layout>
</item> </item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QCheckBox" name="cxRightAileron">
<property name="text">
<string>Right Aileron</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cxRightElevator">
<property name="text">
<string>Right Elevator</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cxLeftFlap">
<property name="text">
<string>Left Flap</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cxRightFlap">
<property name="text">
<string>Right Flap</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="1" column="0"> <item row="1" column="0">
<widget class="QPushButton" name="btSetCtrl"> <widget class="QPushButton" name="btSetCtrl">
<property name="text"> <property name="text">
......
...@@ -27,6 +27,8 @@ UASControlParameters::UASControlParameters(QWidget *parent) : ...@@ -27,6 +27,8 @@ UASControlParameters::UASControlParameters(QWidget *parent) :
{ {
ui->setupUi(this); ui->setupUi(this);
ui->btSetCtrl->setStatusTip(tr("Set Passthrough"));
connect(ui->btGetCommands, SIGNAL(clicked()), this, SLOT(getCommands())); connect(ui->btGetCommands, SIGNAL(clicked()), this, SLOT(getCommands()));
connect(ui->btSetCtrl, SIGNAL(clicked()), this, SLOT(setPassthrough())); connect(ui->btSetCtrl, SIGNAL(clicked()), this, SLOT(setPassthrough()));
...@@ -91,11 +93,8 @@ void UASControlParameters::activeUasSet(UASInterface *uas) ...@@ -91,11 +93,8 @@ void UASControlParameters::activeUasSet(UASInterface *uas)
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(speedChanged(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(speedChanged(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
connect(uas, SIGNAL(thrustChanged(UASInterface*,double)), this, SLOT(thrustChanged(UASInterface*,double)) ); connect(uas, SIGNAL(thrustChanged(UASInterface*,double)), this, SLOT(thrustChanged(UASInterface*,double)) );
//connect(uas, SIGNAL(radioCalibrationReceived(QPointer<RadioCalibrationData>)), this, SLOT(radioChanged(QPointer<RadioCalibrationData>)));
activeUAS= uas; activeUAS= uas;
} }
...@@ -122,6 +121,8 @@ void UASControlParameters::updateAttitude(UASInterface *uas, double roll, double ...@@ -122,6 +121,8 @@ void UASControlParameters::updateAttitude(UASInterface *uas, double roll, double
void UASControlParameters::setCommands() void UASControlParameters::setCommands()
{ {
if(this->activeUAS)
{
UAS* myUas= static_cast<UAS*>(this->activeUAS); UAS* myUas= static_cast<UAS*>(this->activeUAS);
mavlink_message_t msg; mavlink_message_t msg;
...@@ -132,6 +133,7 @@ void UASControlParameters::setCommands() ...@@ -132,6 +133,7 @@ void UASControlParameters::setCommands()
mavlink_msg_mid_lvl_cmds_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCmds); mavlink_msg_mid_lvl_cmds_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCmds);
myUas->sendMessage(msg); myUas->sendMessage(msg);
}
} }
void UASControlParameters::getCommands() void UASControlParameters::getCommands()
...@@ -143,41 +145,28 @@ void UASControlParameters::getCommands() ...@@ -143,41 +145,28 @@ void UASControlParameters::getCommands()
void UASControlParameters::setPassthrough() void UASControlParameters::setPassthrough()
{ {
//UAS* myUas= static_cast<UAS*>(this->activeUAS); if(this->activeUAS)
{
UAS* myUas= static_cast<UAS*>(this->activeUAS);
//mavlink_message_t msg; mavlink_message_t msg;
int8_t tmpBit=0; int8_t tmpBit=0;
if(ui->cxAilerons->isChecked()) if(ui->cxdle_c->isChecked())//left elevator command
{
tmpBit+=1;
}
if(ui->cxElevator->isChecked())
{
tmpBit+=2;
}
if(ui->cxLeftFlap->isChecked())
{
tmpBit+=4;
}
if(ui->cxRightAileron->isChecked())
{ {
tmpBit+=8; tmpBit+=8;
} }
if(ui->cxRightElevator->isChecked()) if(ui->cxdr_c->isChecked())//rudder command
{ {
tmpBit+=16; tmpBit+=16;
} }
if(ui->cxRightFlap->isChecked())
{ if(ui->cxdla_c->isChecked())//left aileron command
tmpBit+=32;
}
if(ui->cxRudder->isChecked())
{ {
tmpBit+=64; tmpBit+=64;
} }
if(ui->cxThrottle->isChecked()) if(ui->cxdt_c->isChecked())//throttle command
{ {
tmpBit+=128; tmpBit+=128;
} }
...@@ -186,11 +175,13 @@ void UASControlParameters::setPassthrough() ...@@ -186,11 +175,13 @@ void UASControlParameters::setPassthrough()
r.b[1] = 0; r.b[1] = 0;
r.b[0] = tmpBit;//255; r.b[0] = tmpBit;//255;
tempCtrl.target= this->activeUAS->getUASID();
tempCtrl.bitfieldPt= (uint16_t)r.s; tempCtrl.bitfieldPt= (uint16_t)r.s;
//mavlink_msg_ctrl_srfc_pt_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCtrl); mavlink_msg_ctrl_srfc_pt_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCtrl);
//myUas->sendMessage(msg); myUas->sendMessage(msg);
qDebug()<<tempCtrl.bitfieldPt; //qDebug()<<tempCtrl.bitfieldPt;
}
} }
void UASControlParameters::updateMode(int uas,QString mode,QString description) void UASControlParameters::updateMode(int uas,QString mode,QString description)
...@@ -208,24 +199,3 @@ void UASControlParameters::thrustChanged(UASInterface *uas, double throttle) ...@@ -208,24 +199,3 @@ void UASControlParameters::thrustChanged(UASInterface *uas, double throttle)
Q_UNUSED(uas); Q_UNUSED(uas);
this->throttle= throttle; this->throttle= throttle;
} }
void UASControlParameters::radioChanged(const QPointer<RadioCalibrationData>& radio)
{
if (radio)
{
if (this->radio)
{
delete this->radio;
}
this->radio = new RadioCalibrationData(*radio);
// aileron->set((*radio)(RadioCalibrationData::AILERON));
// elevator->set((*radio)(RadioCalibrationData::ELEVATOR));
// rudder->set((*radio)(RadioCalibrationData::RUDDER));
// gyro->set((*radio)(RadioCalibrationData::GYRO));
// pitch->set((*radio)(RadioCalibrationData::PITCH));
// throttle->set((*radio)(RadioCalibrationData::THROTTLE));
}
}
...@@ -31,7 +31,6 @@ public slots: ...@@ -31,7 +31,6 @@ public slots:
void setPassthrough(); void setPassthrough();
void updateMode(int uas,QString mode,QString description); void updateMode(int uas,QString mode,QString description);
void thrustChanged(UASInterface* uas,double throttle); void thrustChanged(UASInterface* uas,double throttle);
void radioChanged(const QPointer<RadioCalibrationData>& radio);
private: private:
Ui::UASControlParameters *ui; Ui::UASControlParameters *ui;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment