Skip to content

Commit

Permalink
Merge pull request #2094 from aminballoon/main
Browse files Browse the repository at this point in the history
Camera zoom and focus
  • Loading branch information
julianoes authored Mar 19, 2024
2 parents e06de06 + 35c2046 commit 432e4d7
Show file tree
Hide file tree
Showing 15 changed files with 17,378 additions and 4,876 deletions.
2 changes: 1 addition & 1 deletion proto
Submodule proto updated 1 files
+115 −1 protos/camera/camera.proto
2 changes: 1 addition & 1 deletion src/cmake/compiler_flags.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ if(MINGW)
endif()

if(MSVC)
add_definitions(-DWINDOWS -D_USE_MATH_DEFINES)
add_definitions(-DWINDOWS -D_USE_MATH_DEFINES -DNOMINMAX -DWIN32_LEAN_AND_MEAN)
set(warnings "-WX -W2")
set(gtest_force_shared_crt ON CACHE BOOL "" FORCE)

Expand Down
2 changes: 1 addition & 1 deletion src/mavsdk/core/log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <mutex>

#if defined(WINDOWS)
#include "windows_include.h"
#include <windows.h>
#define WIN_COLOR_RED 4
#define WIN_COLOR_GREEN 10
#define WIN_COLOR_YELLOW 14
Expand Down
2 changes: 1 addition & 1 deletion src/mavsdk/core/serial_connection.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include "connection.h"

#if defined(WINDOWS)
#include "windows_include.h"
#include <windows.h>
#endif

namespace mavsdk {
Expand Down
18 changes: 0 additions & 18 deletions src/mavsdk/core/windows_include.h

This file was deleted.

117 changes: 117 additions & 0 deletions src/mavsdk/plugins/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,6 +264,123 @@ Camera::Result Camera::reset_settings() const
return _impl->reset_settings();
}

void Camera::zoom_in_start_async(const ResultCallback callback)
{
_impl->zoom_in_start_async(callback);
}

Camera::Result Camera::zoom_in_start() const
{
return _impl->zoom_in_start();
}

void Camera::zoom_out_start_async(const ResultCallback callback)
{
_impl->zoom_out_start_async(callback);
}

Camera::Result Camera::zoom_out_start() const
{
return _impl->zoom_out_start();
}

void Camera::zoom_stop_async(const ResultCallback callback)
{
_impl->zoom_stop_async(callback);
}

Camera::Result Camera::zoom_stop() const
{
return _impl->zoom_stop();
}

void Camera::zoom_range_async(float range, const ResultCallback callback)
{
_impl->zoom_range_async(range, callback);
}

Camera::Result Camera::zoom_range(float range) const
{
return _impl->zoom_range(range);
}

void Camera::track_point_async(
float point_x, float point_y, float radius, const ResultCallback callback)
{
_impl->track_point_async(point_x, point_y, radius, callback);
}

Camera::Result Camera::track_point(float point_x, float point_y, float radius) const
{
return _impl->track_point(point_x, point_y, radius);
}

void Camera::track_rectangle_async(
float top_left_x,
float top_left_y,
float bottom_right_x,
float bottom_right_y,
const ResultCallback callback)
{
_impl->track_rectangle_async(top_left_x, top_left_y, bottom_right_x, bottom_right_y, callback);
}

Camera::Result Camera::track_rectangle(
float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) const
{
return _impl->track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y);
}

void Camera::track_stop_async(const ResultCallback callback)
{
_impl->track_stop_async(callback);
}

Camera::Result Camera::track_stop() const
{
return _impl->track_stop();
}

void Camera::focus_in_start_async(const ResultCallback callback)
{
_impl->focus_in_start_async(callback);
}

Camera::Result Camera::focus_in_start() const
{
return _impl->focus_in_start();
}

void Camera::focus_out_start_async(const ResultCallback callback)
{
_impl->focus_out_start_async(callback);
}

Camera::Result Camera::focus_out_start() const
{
return _impl->focus_out_start();
}

void Camera::focus_stop_async(const ResultCallback callback)
{
_impl->focus_stop_async(callback);
}

Camera::Result Camera::focus_stop() const
{
return _impl->focus_stop();
}

void Camera::focus_range_async(float range, const ResultCallback callback)
{
_impl->focus_range_async(range, callback);
}

Camera::Result Camera::focus_range(float range) const
{
return _impl->focus_range(range);
}

std::ostream& operator<<(std::ostream& str, Camera::Result const& result)
{
switch (result) {
Expand Down
Loading

0 comments on commit 432e4d7

Please sign in to comment.