Commit 14097878 authored by Michael Carpenter's avatar Michael Carpenter

Addition of new "Point Camera" action on the Map for APM

parent 89e333e8
......@@ -27,7 +27,6 @@ This file is part of the QGROUNDCONTROL project
*/
#include "ArduPilotMegaMAV.h"
ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)//,
// place other initializers here
......@@ -63,3 +62,23 @@ void ArduPilotMegaMAV::receiveMessage(LinkInterface* link, mavlink_message_t mes
}
}
}
void ArduPilotMegaMAV::setMountConfigure(unsigned char mode, bool stabilize_roll,bool stabilize_pitch,bool stabilize_yaw)
{
//Only supported by APM
mavlink_message_t msg;
mavlink_msg_mount_configure_pack(255,1,&msg,this->uasId,1,mode,stabilize_roll,stabilize_pitch,stabilize_yaw);
sendMessage(msg);
}
void ArduPilotMegaMAV::setMountControl(double pa,double pb,double pc,bool islatlong)
{
mavlink_message_t msg;
if (islatlong)
{
mavlink_msg_mount_control_pack(255,1,&msg,this->uasId,1,pa*10000000.0,pb*10000000.0,pc*10000000.0,0);
}
else
{
mavlink_msg_mount_control_pack(255,1,&msg,this->uasId,1,pa,pb,pc,0);
}
sendMessage(msg);
}
......@@ -25,12 +25,18 @@ This file is part of the QGROUNDCONTROL project
#define ARDUPILOTMEGAMAV_H
#include "UAS.h"
#include "ardupilotmega/mavlink_msg_mount_configure.h"
#include "ardupilotmega/mavlink_msg_mount_control.h"
#include "ardupilotmega/mavlink_msg_mount_status.h"
class ArduPilotMegaMAV : public UAS
{
Q_OBJECT
public:
ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id = 0);
/** @brief Set camera mount stabilization modes */
void setMountConfigure(unsigned char mode, bool stabilize_roll,bool stabilize_pitch,bool stabilize_yaw);
/** @brief Set camera mount control */
void setMountControl(double pa,double pb,double pc,bool islatlong);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
......
......@@ -5,6 +5,7 @@
#include "MAV2DIcon.h"
#include "Waypoint2DIcon.h"
#include "UASWaypointManager.h"
#include "ArduPilotMegaMAV.h"
QGCMapWidget::QGCMapWidget(QWidget *parent) :
mapcontrol::OPMapWidget(parent),
......@@ -59,6 +60,16 @@ bool QGCMapWidget::guidedAltActionTriggered()
guidedActionTriggered();
return true;
}
void QGCMapWidget::cameraActionTriggered()
{
ArduPilotMegaMAV *newmav = qobject_cast<ArduPilotMegaMAV*>(this->uas);
if (newmav)
{
newmav->setMountConfigure(4,true,true,true);
internals::PointLatLng pos = map->FromLocalToLatLng(mousePressPos.x(), mousePressPos.y());
newmav->setMountControl(pos.Lat(),pos.Lng(),100,true);
}
}
void QGCMapWidget::mousePressEvent(QMouseEvent *event)
{
......@@ -237,6 +248,7 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
{
// Only execute if proper UAS is set
if (!uas) return;
this->uas = uas;
// Disconnect old MAV manager
if (currWPManager)
......@@ -251,6 +263,12 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
if (uas)
{
currWPManager = uas->getWaypointManager();
QList<QAction*> actionList = this->actions();
for (int i=0;i<actionList.size();i++)
{
this->removeAction(actionList[i]);
actionList[i]->deleteLater();
}
if (currWPManager->guidedModeSupported())
{
QAction *guidedaction = new QAction(this);
......@@ -261,6 +279,14 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
guidedaction->setText("Go To Here Alt (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered()));
this->addAction(guidedaction);
if (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
QAction *cameraaction = new QAction(this);
cameraaction->setText("Point Camera Here");
connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered()));
this->addAction(cameraaction);
}
}
// Connect the waypoint manager / data storage to the UI
......
......@@ -40,6 +40,8 @@ signals:
void waypointChanged(Waypoint* wp);
public slots:
/** @brief Action triggered with point-camera action is selected from the context menu */
void cameraActionTriggered();
/** @brief Action triggered when guided action is selected from the context menu */
void guidedActionTriggered();
/** @brief Action triggered when guided action is selected from the context menu, allows for altitude selection */
......@@ -158,6 +160,7 @@ protected:
float homeAltitude; ///< Home altitude
QPoint mousePressPos; ///< Mouse position when the button is released.
int defaultGuidedAlt; ///< Default altitude for guided mode
UASInterface *uas; ///< Currently selected UAS.
};
......
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