Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix possible setting options list when camera uses exclusions #1548

Merged
merged 3 commits into from
Sep 16, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 4 additions & 7 deletions src/plugins/camera/camera_definition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,22 +113,22 @@ bool CameraDefinition::parse_xml()

const char* type_str = e_parameter->Attribute("type");
if (!type_str) {
LogErr() << "type attribute missing";
LogErr() << "type attribute missing for " << param_name;
return false;
}

if (strcmp(type_str, "string") == 0) {
LogDebug() << "Ignoring string params.";
LogDebug() << "Ignoring string params: " << param_name;
continue;
}

if (strcmp(type_str, "custom") == 0) {
LogDebug() << "Ignoring custom params.";
LogDebug() << "Ignoring custom params: " << param_name;
continue;
}

if (!new_parameter->type.set_empty_type_from_xml(type_str)) {
LogErr() << "unknown type attribute";
LogErr() << "Unknown type attribute: " << type_str;
return false;
}

Expand Down Expand Up @@ -486,9 +486,6 @@ bool CameraDefinition::get_possible_settings(

for (const auto& parameter : _parameter_map) {
for (const auto& option : parameter.second->options) {
if (_current_settings[parameter.first].needs_updating) {
continue;
}
Comment on lines -489 to -491
Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I removed those lines because an exclusion does not depend on needs_updating. I could verify in the test camera_definition that the unit test below was wrong: it was exposing CAM_VIDFMT when it should actually have been excluded.

if (_current_settings[parameter.first].value == option->value) {
for (const auto& exclusion : option->exclusions) {
// LogDebug() << "found exclusion for " << parameter.first
Expand Down
20 changes: 10 additions & 10 deletions src/plugins/camera/camera_definition_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ TEST(CameraDefinition, E90CheckDefaultSettings)
{
std::unordered_map<std::string, MAVLinkParameters::ParamValue> settings{};
EXPECT_TRUE(cd.get_possible_settings(settings));
EXPECT_EQ(settings.size(), 7);
EXPECT_EQ(settings.size(), 6);
// LogDebug() << "Found settings:";
// for (const auto &setting : settings) {
// LogDebug() << " - " << setting.first;
Expand Down Expand Up @@ -111,15 +111,15 @@ TEST(CameraDefinition, E90ChangeSettings)
{
// Check default
MAVLinkParameters::ParamValue value;
EXPECT_TRUE(cd.get_setting("CAM_WBMODE", value));
ASSERT_TRUE(cd.get_setting("CAM_WBMODE", value));
EXPECT_EQ(value.get<uint32_t>(), 0);
}

{
// We can only set CAM_COLORMODE in photo mode
MAVLinkParameters::ParamValue value;
value.set<uint32_t>(0);
EXPECT_TRUE(cd.set_setting("CAM_MODE", value));
ASSERT_TRUE(cd.set_setting("CAM_MODE", value));
}

{
Expand All @@ -132,49 +132,49 @@ TEST(CameraDefinition, E90ChangeSettings)
{
// Check if WBMODE was correctly set
MAVLinkParameters::ParamValue value;
EXPECT_TRUE(cd.get_setting("CAM_WBMODE", value));
ASSERT_TRUE(cd.get_setting("CAM_WBMODE", value));
EXPECT_EQ(value.get<uint32_t>(), 1);
}

{
// Interleave COLORMODE, first check default
MAVLinkParameters::ParamValue value;
EXPECT_TRUE(cd.get_setting("CAM_COLORMODE", value));
ASSERT_TRUE(cd.get_setting("CAM_COLORMODE", value));
EXPECT_EQ(value.get<uint32_t>(), 1);
}

{
// Then set COLORMODE to 5
MAVLinkParameters::ParamValue value;
value.set<uint32_t>(5);
EXPECT_TRUE(cd.set_setting("CAM_COLORMODE", value));
ASSERT_TRUE(cd.set_setting("CAM_COLORMODE", value));
}

{
// COLORMODE should now be 5
MAVLinkParameters::ParamValue value;
EXPECT_TRUE(cd.get_setting("CAM_COLORMODE", value));
ASSERT_TRUE(cd.get_setting("CAM_COLORMODE", value));
EXPECT_EQ(value.get<uint32_t>(), 5);
}

{
// WBMODE should still be 1
MAVLinkParameters::ParamValue value;
EXPECT_TRUE(cd.get_setting("CAM_WBMODE", value));
ASSERT_TRUE(cd.get_setting("CAM_WBMODE", value));
EXPECT_EQ(value.get<uint32_t>(), 1);
}

{
// Change WBMODE to 7
MAVLinkParameters::ParamValue value;
value.set<uint32_t>(7);
EXPECT_TRUE(cd.set_setting("CAM_WBMODE", value));
ASSERT_TRUE(cd.set_setting("CAM_WBMODE", value));
}

{
// And check WBMODE again
MAVLinkParameters::ParamValue value;
EXPECT_TRUE(cd.get_setting("CAM_WBMODE", value));
ASSERT_TRUE(cd.get_setting("CAM_WBMODE", value));
EXPECT_EQ(value.get<uint32_t>(), 7);
}
}
Expand Down
5 changes: 3 additions & 2 deletions src/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1589,7 +1589,7 @@ void CameraImpl::notify_possible_setting_options()

const auto temp_callback = _subscribe_possible_setting_options.callback;

// We create a function object in order to move be able to move the settings into it.
// We create a function object in order to be able to move the settings into it.
// FIXME: Use C++14 where this is not necessary anymore.
_parent->call_user_callback(std::bind(
[temp_callback](const std::vector<Camera::SettingOptions>& options) {
Expand Down Expand Up @@ -1633,14 +1633,15 @@ void CameraImpl::refresh_params()
// any other possible settings to change. However, we still would
// like to notify the current settings with this one change.
notify_current_settings();
notify_possible_setting_options();
Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This one line is the actual fix I needed 😅

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Haha, ok!

return;
}

unsigned count = 0;
for (const auto& param : params) {
const std::string& param_name = param.first;
const MAVLinkParameters::ParamValue& param_value_type = param.second;
const bool is_last = (count + 1 == params.size());
const bool is_last = (count == params.size() - 1);
_parent->get_param_async(
param_name,
param_value_type,
Expand Down