Skip to content

Commit

Permalink
Merge pull request #426 from dronecore/camera-subscriptions
Browse files Browse the repository at this point in the history
camera: adding subscription APIs
  • Loading branch information
JonasVautherin authored Jun 20, 2018
2 parents 18e01d3 + e19e548 commit 6a36ad3
Show file tree
Hide file tree
Showing 9 changed files with 660 additions and 133 deletions.
13 changes: 13 additions & 0 deletions integration_tests/camera_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,15 @@ TEST(CameraTest, SetMode)
ASSERT_TRUE(system.has_camera());
auto camera = std::make_shared<Camera>(system);

bool received_mode_change = false;
Camera::Mode last_mode = Camera::Mode::UNKNOWN;

camera->subscribe_mode([&received_mode_change, &last_mode](Camera::Mode mode) {
LogInfo() << "Got mode: " << int(mode);
received_mode_change = true;
last_mode = mode;
});

std::vector<Camera::Mode> modes_to_test;
modes_to_test.push_back(Camera::Mode::PHOTO);
modes_to_test.push_back(Camera::Mode::VIDEO);
Expand All @@ -31,6 +40,10 @@ TEST(CameraTest, SetMode)
for (auto mode : modes_to_test) {
auto result = camera->set_mode(mode);
EXPECT_EQ(result, Camera::Result::SUCCESS);
std::this_thread::sleep_for(std::chrono::milliseconds(500));
EXPECT_TRUE(received_mode_change);
EXPECT_EQ(last_mode, mode);
received_mode_change = false;
}
}

Expand Down
102 changes: 99 additions & 3 deletions integration_tests/camera_settings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ TEST(CameraTest, ShowSettingsAndOptions)

LogDebug() << "Possible settings in photo mode: ";
for (auto setting : settings) {
LogDebug() << "-" << setting;
LogDebug() << "- " << setting;
}

if (is_e90) {
Expand Down Expand Up @@ -71,7 +71,7 @@ TEST(CameraTest, ShowSettingsAndOptions)
EXPECT_EQ(settings.size(), 5);
}

std::vector<std::string> options;
std::vector<Camera::Option> options;

if (is_e90) {
// Try something that is specific to the camera mode.
Expand Down Expand Up @@ -151,7 +151,7 @@ TEST(CameraTest, SetSettings)
EXPECT_STREQ("1", value_set.c_str());

// We should now be able to set shutter speed and ISO.
std::vector<std::string> options;
std::vector<Camera::Option> options;
// Try something that is specific to the camera mode.
EXPECT_TRUE(camera->get_possible_options("CAM_SHUTTERSPD", options));
EXPECT_EQ(options.size(), 19);
Expand Down Expand Up @@ -234,3 +234,99 @@ TEST(CameraTest, SetSettings)
EXPECT_STREQ(description.c_str(), "Shutter Speed");
}
}

static void receive_current_settings(bool &subscription_called,
const std::vector<Camera::Setting> settings)
{
LogDebug() << "Received current options:";
EXPECT_TRUE(settings.size() > 0);
for (auto &setting : settings) {
LogDebug() << "Got setting '" << setting.setting_id << "' with selected option '"
<< setting.option.option_id << "'";
}
subscription_called = true;
}

TEST(CameraTest, SubscribeCurrentSettings)
{
DroneCore dc;

ConnectionResult connection_ret = dc.add_udp_connection();
ASSERT_EQ(connection_ret, ConnectionResult::SUCCESS);

// Wait for system to connect via heartbeat.
std::this_thread::sleep_for(std::chrono::seconds(2));

System &system = dc.system();
ASSERT_TRUE(system.has_camera());
auto camera = std::make_shared<Camera>(system);

// We need to wait for the camera definition to be ready
// because we don't have a check yet.
std::this_thread::sleep_for(std::chrono::seconds(2));
// Reset exposure mode
EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "0"), Camera::Result::SUCCESS);

bool subscription_called = false;
camera->subscribe_current_settings(
std::bind(receive_current_settings, std::ref(subscription_called), _1));

EXPECT_EQ(camera->set_mode(Camera::Mode::PHOTO), Camera::Result::SUCCESS);
std::this_thread::sleep_for(std::chrono::seconds(1));
EXPECT_TRUE(subscription_called);

subscription_called = false;
EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "1"), Camera::Result::SUCCESS);
std::this_thread::sleep_for(std::chrono::seconds(1));
EXPECT_TRUE(subscription_called);
}

static void receive_possible_settings(bool &subscription_called,
const std::vector<Camera::SettingOptions> settings_options)
{
LogDebug() << "Received possible options:";
EXPECT_TRUE(settings_options.size() > 0);
for (auto &setting_options : settings_options) {
LogDebug() << "Got setting '" << setting_options.setting_id << "' with options:";
EXPECT_TRUE(setting_options.options.size() > 0);
for (auto &option : setting_options.options) {
LogDebug() << " - '" << option.option_id << "'";
}
}
subscription_called = true;
}

TEST(CameraTest, SubscribePossibleSettings)
{
DroneCore dc;

ConnectionResult connection_ret = dc.add_udp_connection();
ASSERT_EQ(connection_ret, ConnectionResult::SUCCESS);

// Wait for system to connect via heartbeat.
std::this_thread::sleep_for(std::chrono::seconds(2));

System &system = dc.system();
ASSERT_TRUE(system.has_camera());
auto camera = std::make_shared<Camera>(system);

// We need to wait for the camera definition to be ready
// because we don't have a check yet.
std::this_thread::sleep_for(std::chrono::seconds(2));
// Reset exposure mode
EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "0"), Camera::Result::SUCCESS);
std::this_thread::sleep_for(std::chrono::seconds(1));

bool subscription_called = false;
camera->subscribe_possible_settings(
std::bind(receive_possible_settings, std::ref(subscription_called), _1));

EXPECT_EQ(camera->set_mode(Camera::Mode::PHOTO), Camera::Result::SUCCESS);
std::this_thread::sleep_for(std::chrono::seconds(1));
EXPECT_TRUE(subscription_called);

subscription_called = false;
EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "1"), Camera::Result::SUCCESS);
std::this_thread::sleep_for(std::chrono::seconds(1));
EXPECT_TRUE(subscription_called);
}
33 changes: 33 additions & 0 deletions integration_tests/camera_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,11 @@ using namespace dronecore;
using namespace std::placeholders; // for `_1`

static void receive_camera_status(Camera::Result result, const Camera::Status status);
static void receive_camera_status_subscription(const Camera::Status status);
static void print_camera_status(const Camera::Status status);

static std::atomic<bool> _received_status{false};
static std::atomic<int> _num_received_status{0};

TEST(CameraTest, Status)
{
Expand All @@ -30,11 +33,41 @@ TEST(CameraTest, Status)
EXPECT_TRUE(_received_status);
}

TEST(CameraTest, StatusSubscription)
{
DroneCore dc;

ConnectionResult ret = dc.add_udp_connection();
ASSERT_EQ(ret, ConnectionResult::SUCCESS);

// Wait for system to connect via heartbeat.
std::this_thread::sleep_for(std::chrono::seconds(2));

System &system = dc.system();
auto camera = std::make_shared<Camera>(system);

camera->subscribe_status(std::bind(&receive_camera_status_subscription, _1));
std::this_thread::sleep_for(std::chrono::seconds(5));
EXPECT_GT(_num_received_status, 3);

// TODO: we could also test if it stops when we stop it.
}

static void receive_camera_status(Camera::Result result, const Camera::Status status)
{
EXPECT_EQ(result, Camera::Result::SUCCESS);
_received_status = true;
print_camera_status(status);
}

static void receive_camera_status_subscription(const Camera::Status status)
{
++_num_received_status;
print_camera_status(status);
}

static void print_camera_status(const Camera::Status status)
{
std::string storage_status_str = "";
switch (status.storage_status) {
case Camera::Status::StorageStatus::NOT_AVAILABLE:
Expand Down
4 changes: 2 additions & 2 deletions integration_tests/camera_take_photo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ TEST(CameraTest, TakePhoto)

std::this_thread::sleep_for(std::chrono::seconds(1));

camera->capture_info_async(std::bind(&receive_capture_info, _1));
camera->subscribe_capture_info(std::bind(&receive_capture_info, _1));

camera->take_photo_async(std::bind(&receive_camera_result, _1));
std::this_thread::sleep_for(std::chrono::seconds(5));
Expand Down Expand Up @@ -68,7 +68,7 @@ TEST(CameraTest, TakeMultiplePhotos)

std::this_thread::sleep_for(std::chrono::seconds(1));

camera->capture_info_async(std::bind(&receive_capture_info, _1));
camera->subscribe_capture_info(std::bind(&receive_capture_info, _1));

for (unsigned i = 0; i < num_photos_to_take; ++i) {
camera->take_photo_async(std::bind(&receive_camera_result, _1));
Expand Down
21 changes: 12 additions & 9 deletions integration_tests/camera_test_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,10 @@ set_setting(std::shared_ptr<Camera> camera, const std::string &setting, const st
auto prom = std::make_shared<std::promise<Camera::Result>>();
auto ret = prom->get_future();

Camera::Option new_option{};
new_option.option_id = option;
camera->set_option_async(
setting, option, [prom](Camera::Result result) { prom->set_value(result); });
setting, new_option, [prom](Camera::Result result) { prom->set_value(result); });

auto status = ret.wait_for(std::chrono::seconds(1));

Expand All @@ -87,26 +89,27 @@ dronecore::Camera::Result get_setting(std::shared_ptr<dronecore::Camera> camera,
{
struct PromiseResult {
Camera::Result result;
std::string value;
Camera::Option option;
};

auto prom = std::make_shared<std::promise<PromiseResult>>();
auto ret = prom->get_future();

camera->get_option_async(setting, [prom](Camera::Result result, const std::string &value) {
PromiseResult promise_result;
promise_result.result = result;
promise_result.value = value;
prom->set_value(promise_result);
});
camera->get_option_async(setting,
[prom](Camera::Result result, const Camera::Option &gotten_option) {
PromiseResult promise_result;
promise_result.result = result;
promise_result.option = gotten_option;
prom->set_value(promise_result);
});

auto status = ret.wait_for(std::chrono::seconds(1));

EXPECT_EQ(status, std::future_status::ready);

if (status == std::future_status::ready) {
PromiseResult promise_result = ret.get();
option = promise_result.value;
option = promise_result.option.option_id;
return promise_result.result;
}
return Camera::Result::TIMEOUT;
Expand Down
65 changes: 50 additions & 15 deletions plugins/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,16 @@ Camera::Result Camera::get_video_stream_info(VideoStreamInfo &info)
return _impl->get_video_stream_info(info);
}

void Camera::get_video_stream_info_async(const get_video_stream_info_callback_t callback)
{
_impl->get_video_stream_info_async(callback);
}

void Camera::subscribe_video_stream_info(const subscribe_video_stream_info_callback_t callback)
{
_impl->subscribe_video_stream_info(callback);
}

void Camera::stop_video_async(const result_callback_t &callback)
{
_impl->stop_video_async(callback);
Expand All @@ -92,49 +102,74 @@ void Camera::get_mode_async(const mode_callback_t &callback)
_impl->get_mode_async(callback);
}

void Camera::subscribe_mode(const subscribe_mode_callback_t callback)
{
_impl->subscribe_mode(callback);
}

void Camera::get_status_async(get_status_callback_t callback)
{
_impl->get_status_async(callback);
}

void Camera::capture_info_async(capture_info_callback_t callback)
void Camera::subscribe_status(const Camera::subscribe_status_callback_t callback)
{
_impl->capture_info_async(callback);
_impl->subscribe_status(callback);
}

void Camera::set_option_async(const std::string &setting,
const std::string &option,
void Camera::subscribe_capture_info(capture_info_callback_t callback)
{
_impl->subscribe_capture_info(callback);
}

void Camera::set_option_async(const std::string &setting_id,
const Option &option,
const result_callback_t &callback)
{
_impl->set_option_async(setting, option, callback);
_impl->set_option_async(setting_id, option, callback);
}

void Camera::get_option_async(const std::string &setting, const get_option_callback_t &callback)
Camera::Result Camera::get_option(const std::string &setting_id, Option &option)
{
_impl->get_option_async(setting, callback);
return _impl->get_option(setting_id, option);
}

void Camera::get_option_async(const std::string &setting_id, const get_option_callback_t &callback)
{
_impl->get_option_async(setting_id, callback);
}

bool Camera::get_possible_settings(std::vector<std::string> &settings)
{
return _impl->get_possible_settings(settings);
}

bool Camera::get_possible_options(const std::string &setting_name,
std::vector<std::string> &options)
bool Camera::get_possible_options(const std::string &setting_id,
std::vector<Camera::Option> &options)
{
return _impl->get_possible_options(setting_name, options);
return _impl->get_possible_options(setting_id, options);
}

bool Camera::get_setting_str(const std::string &setting_name, std::string &description)
bool Camera::get_setting_str(const std::string &setting_id, std::string &description)
{
return _impl->get_setting_str(setting_name, description);
return _impl->get_setting_str(setting_id, description);
}

bool Camera::get_option_str(const std::string &setting_name,
const std::string &option_name,
bool Camera::get_option_str(const std::string &setting_id,
const std::string &option_id,
std::string &description)
{
return _impl->get_option_str(setting_name, option_name, description);
return _impl->get_option_str(setting_id, option_id, description);
}

void Camera::subscribe_current_settings(const subscribe_current_settings_callback_t &callback)
{
_impl->subscribe_current_settings(callback);
}

void Camera::subscribe_possible_settings(const subscribe_possible_settings_callback_t &callback)
{
_impl->subscribe_possible_settings(callback);
}

std::string Camera::result_str(Result result)
Expand Down
Loading

0 comments on commit 6a36ad3

Please sign in to comment.