Skip to content

Commit

Permalink
camera def stuff green again
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Oct 12, 2024
1 parent e6e3a71 commit 09b2e51
Show file tree
Hide file tree
Showing 8 changed files with 118 additions and 68 deletions.
2 changes: 1 addition & 1 deletion src/mavsdk/core/mavlink_parameter_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -294,6 +294,7 @@ void MavlinkParameterServer::process_param_ext_set(const mavlink_message_t& mess
LogWarn() << "Invalid Param Set ext Request: " << safe_param_id;
return;
}

process_param_set_internally(safe_param_id, value_to_set, true);
}

Expand Down Expand Up @@ -332,7 +333,6 @@ void MavlinkParameterServer::process_param_request_read(const mavlink_message_t&

void MavlinkParameterServer::process_param_ext_request_read(const mavlink_message_t& message)
{
LogDebug() << "process param_ext_request_read";
mavlink_param_ext_request_read_t read_request{};
mavlink_msg_param_ext_request_read_decode(&message, &read_request);
if (!target_matches(read_request.target_system, read_request.target_component, true)) {
Expand Down
2 changes: 1 addition & 1 deletion src/mavsdk/core/param_value.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -488,7 +488,7 @@ bool ParamValue::set_int(int new_value)
_value = static_cast<uint32_t>(new_value);
return true;
} else if (std::get_if<int32_t>(&_value)) {
_value = static_cast<int32_t>(new_value);
_value = new_value;
return true;
} else {
return false;
Expand Down
6 changes: 2 additions & 4 deletions src/mavsdk/plugins/camera/camera_definition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -458,7 +458,7 @@ void CameraDefinition::assume_default_settings()

InternalCurrentSetting new_setting;
new_setting.value = parameter.second->default_option.value;
new_setting.needs_updating = false;
new_setting.needs_updating = true;
_current_settings[parameter.first] = new_setting;

//} else {
Expand Down Expand Up @@ -574,7 +574,7 @@ bool CameraDefinition::set_setting(const std::string& name, const ParamValue& va
// needs to happen outside of this class.
for (const auto& update : _parameter_map[name]->updates) {
if (_current_settings.find(update) == _current_settings.end()) {
// LogDebug() << "Update to '" << update << "' not understood.";
LogDebug() << "Update to '" << update << "' not understood.";
continue;
}
_current_settings[update].needs_updating = true;
Expand Down Expand Up @@ -795,8 +795,6 @@ bool CameraDefinition::get_option_str(
}

for (const auto& option : _parameter_map[setting_name]->options) {
std::stringstream value_ss{};
value_ss << option->value;
if (option->value == option_name) {
description = option->name;
return true;
Expand Down
72 changes: 43 additions & 29 deletions src/mavsdk/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#include <fstream>
#include <functional>
#include <string>
#include <sstream>

namespace mavsdk {

Expand Down Expand Up @@ -44,6 +43,13 @@ CameraImpl::~CameraImpl()

void CameraImpl::init()
{
if (const char* env_p = std::getenv("MAVSDK_CAMERA_DEBUGGING")) {
if (std::string(env_p) == "1") {
LogDebug() << "Camera debugging is on.";
_debugging = true;
}
}

const auto cache_dir_option = get_cache_directory();
if (cache_dir_option) {
_file_cache.emplace(cache_dir_option.value() / "camera", 50, true);
Expand Down Expand Up @@ -1352,7 +1358,7 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca
std::lock_guard lock(_mutex);
auto maybe_potential_camera =
maybe_potential_camera_for_camera_id_with_lock(camera_id);
if (maybe_potential_camera != nullptr) {
if (maybe_potential_camera == nullptr) {
LogErr() << "Failed to find camera.";
}

Expand Down Expand Up @@ -1457,6 +1463,8 @@ void CameraImpl::load_camera_definition_with_lock(
// We assume default settings initially and then load the params one by one.
// This way we can start using it straightaway.
potential_camera.camera_definition->assume_default_settings();

refresh_params_with_lock(potential_camera);
}

void CameraImpl::process_video_information(const mavlink_message_t& message)
Expand Down Expand Up @@ -1745,35 +1753,35 @@ void CameraImpl::set_option_async(
_system_impl->call_user_callback(
[callback]() { callback(Camera::Result::Success); });
}

refresh_params_with_lock(camera_later);
},
this,
static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
camera.component_id,
true);
}

void CameraImpl::get_setting_async(
int32_t camera_id, const Camera::Setting& setting, const Camera::GetSettingCallback& callback)
{
std::lock_guard lock(_mutex);
auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id);
if (maybe_potential_camera == nullptr) {
if (callback != nullptr) {
_system_impl->call_user_callback(
[callback]() { callback(Camera::Result::CameraIdInvalid, {}); });
{
std::lock_guard lock(_mutex);
auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id);
if (maybe_potential_camera == nullptr) {
if (callback != nullptr) {
_system_impl->call_user_callback(
[callback]() { callback(Camera::Result::CameraIdInvalid, {}); });
}
return;
}
return;
}

auto& camera = *maybe_potential_camera;
auto& camera = *maybe_potential_camera;

if (camera.camera_definition == nullptr) {
if (callback != nullptr) {
_system_impl->call_user_callback(
[callback]() { callback(Camera::Result::SettingsUnavailable, {}); });
if (camera.camera_definition == nullptr) {
if (callback != nullptr) {
_system_impl->call_user_callback(
[callback]() { callback(Camera::Result::SettingsUnavailable, {}); });
}
return;
}
return;
}

get_option_async(
Expand Down Expand Up @@ -2071,6 +2079,9 @@ void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera)
const std::string& param_name = param.first;
const ParamValue& param_value_type = param.second;
const bool is_last = (count == params.size() - 1);
if (_debugging) {
LogDebug() << "Trying to get param: " << param_name;
}
_system_impl->get_param_async(
param_name,
param_value_type,
Expand All @@ -2090,6 +2101,9 @@ void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera)
auto& camera_later = *maybe_potential_camera_later;

if (camera_later.camera_definition->set_setting(param_name, value)) {
if (_debugging) {
LogDebug() << "Got setting for " << param_name << ": " << value;
}
return;
}

Expand All @@ -2099,7 +2113,7 @@ void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera)
}
},
this,
static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
potential_camera.component_id,
true);
++count;
}
Expand Down Expand Up @@ -2154,13 +2168,15 @@ Camera::Result CameraImpl::format_storage(int32_t camera_id, int32_t storage_id)
void CameraImpl::format_storage_async(
int32_t camera_id, int32_t storage_id, const Camera::ResultCallback& callback)
{


MavlinkCommandSender::CommandLong cmd_format{};

cmd_format.command = MAV_CMD_STORAGE_FORMAT;
cmd_format.params.maybe_param1 = static_cast<float>(storage_id); // storage ID
cmd_format.params.maybe_param2 = 1.0f; // format
cmd_format.params.maybe_param3 = 1.0f; // clear
cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
cmd_format.target_component_id = component_id_for_camera_id(camera_id);

_system_impl->send_command_async(
cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
Expand Down Expand Up @@ -2191,7 +2207,7 @@ void CameraImpl::reset_settings_async(int32_t camera_id, const Camera::ResultCal

cmd_format.command = MAV_CMD_RESET_CAMERA_SETTINGS;
cmd_format.params.maybe_param1 = 1.0f; // reset
cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
cmd_format.target_component_id = component_id_for_camera_id(camera_id);

_system_impl->send_command_async(
cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
Expand Down Expand Up @@ -2275,7 +2291,7 @@ void CameraImpl::list_photos_async(
}
}();

std::thread([this, start_index, callback]() {
std::thread([this, start_index, callback, camera_id]() {
std::unique_lock<std::mutex> capture_request_lock(_captured_request_mutex);

for (int i = start_index; i < _status.image_count; i++) {
Expand Down Expand Up @@ -2307,7 +2323,7 @@ void CameraImpl::list_photos_async(

_system_impl->mavlink_request_message().request(
MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED,
_camera_id + MAV_COMP_ID_CAMERA,
component_id_for_camera_id(camera_id),
nullptr,
i);
cv_status = _captured_request_cv.wait_for(
Expand Down Expand Up @@ -2358,7 +2374,7 @@ CameraImpl::get_current_settings(int32_t camera_id)

std::lock_guard lock(_mutex);
auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id);
if (maybe_potential_camera != nullptr) {
if (maybe_potential_camera == nullptr) {
result.first = Camera::Result::CameraIdInvalid;
return result;
}
Expand All @@ -2374,8 +2390,6 @@ CameraImpl::get_current_settings(int32_t camera_id)
return result;
}

std::vector<Camera::Setting> current_settings{};

auto possible_setting_options = get_possible_setting_options_with_lock(camera);
if (possible_setting_options.first != Camera::Result::Success) {
result.first = possible_setting_options.first;
Expand All @@ -2399,7 +2413,7 @@ CameraImpl::get_current_settings(int32_t camera_id)
setting.option.option_id,
setting.option.option_description);
}
current_settings.push_back(setting);
result.second.push_back(setting);
}
}

Expand All @@ -2414,7 +2428,7 @@ CameraImpl::get_current_settings(int32_t camera_id)
//
// std::lock_guard lock(_potential_cameras_mutex);
// auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id);
// if (maybe_potential_camera != nullptr) {
// if (maybe_potential_camera == nullptr) {
// result.first = Camera::Result::CameraIdInvalid;
// return result;
// }
Expand Down
7 changes: 3 additions & 4 deletions src/mavsdk/plugins/camera/camera_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ class CameraImpl : public PluginImplBase {

void check_potential_cameras_with_lock();
void check_camera_definition_with_lock(PotentialCamera& potential_camera);
static void load_camera_definition_with_lock(
void load_camera_definition_with_lock(
PotentialCamera& potential_camera, const std::filesystem::path& path);

void notify_mode();
Expand Down Expand Up @@ -336,9 +336,6 @@ class CameraImpl : public PluginImplBase {
using CameraDefinitionCallback = std::function<void(Camera::Result)>;
CameraDefinitionCallback _camera_definition_callback{};

std::atomic<size_t> _camera_id{0};
std::atomic<bool> _camera_found{false};

struct {
std::mutex mutex{};
Camera::Status data{};
Expand Down Expand Up @@ -390,6 +387,8 @@ class CameraImpl : public PluginImplBase {
std::mutex _captured_request_mutex;

std::unique_ptr<HttpLoader> _http_loader{nullptr};

bool _debugging{false};
};

} // namespace mavsdk
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,77 +1,82 @@
<?xml version="1.0" encoding="UTF-8" ?>
<mavlinkcamera>
<definition version="1">
<definition version="2">
<model>UVC Camera</model>
<vendor>Logitech C270HD Webcam</vendor>
</definition>
<parameters>
<parameter name="camera-mode" type="uint32" default="1" control="0">
<parameter name="CAM_MODE" type="uint32" default="1" control="0">
<description>Camera Mode</description>
<options>
<option name="still" value="0">
<exclusions>
<exclude>video-size</exclude>
<exclude>VIDEO_SIZE</exclude>
</exclusions>
</option>
<option name="video" value="1">
</option>
</options>
</parameter>
<parameter name="brightness" type="int32" default="128" min="0" max="225" step ="1">
<parameter name="BRIGHTNESS" type="int32" default="128" min="0" max="225" step ="1">
<description>Brightness</description>
</parameter>
<parameter name="contrast" type="int32" default="32" min="0" max="255" step ="1">
<parameter name="CONTRAST" type="int32" default="32" min="0" max="255" step ="1">
<description>Contrast</description>
</parameter>
<parameter name="saturation" type="int32" default="32" min="0" max="225" step ="1">
<parameter name="SATURATION" type="int32" default="32" min="0" max="225" step ="1">
<description>Saturation</description>
</parameter>
<parameter name="gain" type="int32" default="64" min="0" max="255" step ="1">
<parameter name="GAIN" type="int32" default="64" min="0" max="255" step ="1">
<description>Gain</description>
</parameter>
<parameter name="sharpness" type="int32" default="24" min="0" max="255" step ="1">
<parameter name="SHARPNESS" type="int32" default="24" min="0" max="255" step ="1">
<description>Sharpness </description>
</parameter>
<parameter name="backlight" type="int32" default="0" min="0" max="1" step ="1">
<parameter name="BACKLIGHT" type="int32" default="0">
<description>Backlight Compensation</description>
<options>
<option name="Off" value="0" />
<option name="On" value="1" >
</option>
</options>
</parameter>
<parameter name="power-mode" type="int32" default="0">
<parameter name="POWER_MODE" type="int32" default="0">
<description>Power Line Frequency </description>
<options>
<option name="Disabled" value="0" />
<option name="50 Hz" value="1" />
<option name="60 Hz" value="2" />
</options>
</parameter>
<parameter name="wb-mode" type="int32" default="1">
<parameter name="WB_MODE" type="int32" default="1">
<description>White Balance Mode</description>
<options>
<option name="Manual Mode" value="0" />
<option name="Auto" value="1" >
<exclusions>
<exclude>wb-temp</exclude>
<exclude>WB_TEMP</exclude>
</exclusions>
</option>
</options>
</parameter>
<parameter name="wb-temp" type="int32" default="4000" min="0" max="10000" step ="1">
<parameter name="WB_TEMP" type="int32" default="4000" min="0" max="10000" step ="1">
<description>White Balance Temperature </description>
</parameter>
<parameter name="exp-mode" type="int32" default="3">
<parameter name="EXP_MODE" type="int32" default="3">
<description>Exposure Mode</description>
<options>
<option name="Manual Mode" value="1" />
<option name="Aperture Priority Mode" value="3" >
<exclusions>
<exclude>exp-absolute</exclude>
<exclude>EXP_ABSOLUTE</exclude>
</exclusions>
</option>
</options>
</parameter>
<parameter name="exp-absolute" type="int32" default="166" min="1" max="10000" step ="1">
<parameter name="EXP_ABSOLUTE" type="int32" default="166" min="1" max="10000" step ="1">
<description>Exposure Absolute</description>
</parameter>
<parameter name="exp-priority" type="int32" default="1">
<parameter name="EXP_PRIORITY" type="int32" default="1">
<description>Exposure Auto Priority</description>
<options>
<option name="OFF" value="0" />
Expand Down
Loading

0 comments on commit 09b2e51

Please sign in to comment.