Skip to content

Commit

Permalink
Hack for getting ardupilot work for tracking stuff (JUST FOR TESTING)
Browse files Browse the repository at this point in the history
  • Loading branch information
khanasif786 committed Sep 1, 2024
1 parent 2ffdd08 commit 5872731
Show file tree
Hide file tree
Showing 4 changed files with 51 additions and 15 deletions.
40 changes: 38 additions & 2 deletions src/Camera/SimulatedCameraControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <QtCore/QElapsedTimer>

class VideoManager;
#include "Vehicle.h"
class Vehicle;

/// Creates a simulated Camera Control which supports:
Expand Down Expand Up @@ -65,8 +66,43 @@ class SimulatedCameraControl : public MavlinkCameraControl
void stopStream () override {}
bool stopTakePhoto () override { return false;}
void resumeStream () override {}
void startTracking (QRectF /*rec*/) override {}
void startTracking (QPointF /*point*/, double /*radius*/) override {}
void startTracking (QRectF rec) override {
// if(_trackingMarquee != rec) {
// _trackingMarquee = rec;

qCDebug(CameraControlLog) << "Start Tracking (Rectangle: ["
<< static_cast<float>(rec.x()) << ", "
<< static_cast<float>(rec.y()) << "] - ["
<< static_cast<float>(rec.x() + rec.width()) << ", "
<< static_cast<float>(rec.y() + rec.height()) << "]";

_vehicle->sendMavCommand(1,
MAV_CMD_CAMERA_TRACK_RECTANGLE,
true,
static_cast<float>(rec.x()),
static_cast<float>(rec.y()),
static_cast<float>(rec.x() + rec.width()),
static_cast<float>(rec.y() + rec.height()));
// }
}
void startTracking (QPointF point, double radius) override {
// if(_trackingPoint != point || _trackingRadius != radius) {
// _trackingPoint = point;
// _trackingRadius = radius;

qCDebug(CameraControlLog) << "Start Tracking (Point: ["
<< static_cast<float>(point.x()) << ", "
<< static_cast<float>(point.y()) << "], Radius: "
<< static_cast<float>(radius);

_vehicle->sendMavCommand(1,
MAV_CMD_CAMERA_TRACK_POINT,
true,
static_cast<float>(point.x()),
static_cast<float>(point.y()),
static_cast<float>(radius));
// }
}
void stopTracking () override {}
int version () override { return 0; }
QString modelName () override { return QStringLiteral("Simulated Camera"); }
Expand Down
5 changes: 3 additions & 2 deletions src/Camera/VehicleCameraControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ VehicleCameraControl::VehicleCameraControl(const mavlink_camera_information_t *i
, _vehicle(vehicle)
, _compID(compID)
{
qCDebug(CameraControlLog) << "Vehicle Camera Control Object initialised";
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
memcpy(&_info, info, sizeof(mavlink_camera_information_t));
connect(this, &VehicleCameraControl::dataReady, this, &VehicleCameraControl::_dataReady);
Expand Down Expand Up @@ -2311,7 +2312,7 @@ VehicleCameraControl::startTracking(QRectF rec)
<< static_cast<float>(rec.x() + rec.width()) << ", "
<< static_cast<float>(rec.y() + rec.height()) << "]";

_vehicle->sendMavCommand(_compID,
_vehicle->sendMavCommand(0,
MAV_CMD_CAMERA_TRACK_RECTANGLE,
true,
static_cast<float>(rec.x()),
Expand All @@ -2334,7 +2335,7 @@ VehicleCameraControl::startTracking(QPointF point, double radius)
<< static_cast<float>(point.y()) << "], Radius: "
<< static_cast<float>(radius);

_vehicle->sendMavCommand(_compID,
_vehicle->sendMavCommand(0,
MAV_CMD_CAMERA_TRACK_POINT,
true,
static_cast<float>(point.x()),
Expand Down
9 changes: 4 additions & 5 deletions src/FlightDisplay/FlyViewVideo.qml
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ Item {

//create a new rectangle at the wanted position
if(videoStreaming._camera) {
if (videoStreaming._camera.trackingEnabled) {
if (true) {
trackingROI = trackingROIComponent.createObject(flyViewVideoMouseArea, {
"x": mouse.x,
"y": mouse.y
Expand Down Expand Up @@ -142,10 +142,9 @@ Item {
//if there is already a selection, delete it
if (trackingROI !== null) {
trackingROI.destroy();
}

}
if(videoStreaming._camera) {
if (videoStreaming._camera.trackingEnabled) {
if (true) {
// order coordinates --> top/left and bottom/right
x0 = Math.min(_track_rec_x, mouse.x)
x1 = Math.max(_track_rec_x, mouse.x)
Expand Down Expand Up @@ -210,7 +209,7 @@ Item {
running: true
onTriggered: {
if (videoStreaming._camera) {
if (videoStreaming._camera.trackingEnabled && videoStreaming._camera.trackingImageStatus) {
if (true) {
var margin_hor = (parent.parent.width - videoStreaming.getWidth()) / 2
var margin_ver = (parent.parent.height - videoStreaming.getHeight()) / 2
var left = margin_hor + videoStreaming.getWidth() * videoStreaming._camera.trackingImageRect.left
Expand Down
12 changes: 6 additions & 6 deletions src/FlightMap/Widgets/PhotoVideoControl.qml
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ Rectangle {
id: trackingControls
Layout.alignment: Qt.AlignHCenter
spacing: _margins
visible: _camera && _camera.hasTracking
visible: true

Rectangle {
Layout.alignment: Qt.AlignHCenter
Expand All @@ -276,10 +276,10 @@ Rectangle {
MouseArea {
anchors.fill: parent
onClicked: {
_camera.trackingEnabled = !_camera.trackingEnabled;
if (!_camera.trackingEnabled) {
!camera.stopTracking()
}
_camera.trackingEnabled = true; // !_camera.trackingEnabled;
// if (!_camera.trackingEnabled) {
// !camera.stopTracking()
//}
}
}
}
Expand All @@ -289,7 +289,7 @@ Rectangle {
Layout.alignment: Qt.AlignHCenter
text: qsTr("Camera Tracking")
font.pointSize: ScreenTools.defaultFontPointSize
visible: _camera && _camera.hasTracking
visible: true //_camera && _camera.hasTracking
}
}

Expand Down

0 comments on commit 5872731

Please sign in to comment.