Skip to content

Commit

Permalink
camera_definition: added some getters/setters
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Apr 4, 2018
1 parent 68b70c4 commit 32f7b53
Show file tree
Hide file tree
Showing 4 changed files with 106 additions and 42 deletions.
115 changes: 83 additions & 32 deletions plugins/camera/camera_definition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,20 +40,23 @@ std::string CameraDefinition::get_vendor() const
return _vendor;
}

bool CameraDefinition::get_current_parameters(std::map<std::string, std::string> &parameters)
bool CameraDefinition::get_all_settings(std::map<std::string, MavlinkParameters::ParamValue>
&settings) const
{
for (const auto &setting : _settings) {
settings.clear();

for (const auto &option : setting.second->options) {
bool added_parameters = false;

LogDebug() << setting.first << ": " << option->name;
for (const auto &parameter : _parameter_map) {
for (const auto &option : parameter.second->options) {
settings.insert(
std::pair<std::string, MavlinkParameters::ParamValue>(
parameter.first, option->value));
added_parameters = true;
}
}


// TODO: actually update parameters of method call

return true;
return added_parameters;
}

bool CameraDefinition::parse_xml()
Expand Down Expand Up @@ -153,14 +156,12 @@ bool CameraDefinition::parse_xml()

new_parameter->description = e_description->GetText();

//LogDebug() << "Found: " << new_parameter->description
// << " (" << param_name
// << ", control: " << (new_parameter->is_control ? "yes" : "no")
// << ", readonly: " << (new_parameter->is_readonly ? "yes" : "no")
// << ", writeonly: " << (new_parameter->is_writeonly ? "yes" : "no")
// << ")";

// TODO: parse default which is of param type.
// LogDebug() << "Found: " << new_parameter->description
// << " (" << param_name
// << ", control: " << (new_parameter->is_control ? "yes" : "no")
// << ", readonly: " << (new_parameter->is_readonly ? "yes" : "no")
// << ", writeonly: " << (new_parameter->is_writeonly ? "yes" : "no")
// << ")";

auto e_updates = e_parameter->FirstChildElement("updates");
if (e_updates) {
Expand All @@ -173,12 +174,20 @@ bool CameraDefinition::parse_xml()
}
}


auto e_options = e_parameter->FirstChildElement("options");
if (!e_options) {
continue;
}

// We only need a default if we have options.
const char *default_str = e_parameter->Attribute("default");
if (!default_str) {
LogErr() << "Default missing.";
return false;
}

bool found_default = false;

for (auto e_option = e_options->FirstChildElement("option");
e_option != nullptr;
e_option = e_option->NextSiblingElement("option")) {
Expand All @@ -189,11 +198,22 @@ bool CameraDefinition::parse_xml()
return false;
}

const char *option_value = e_option->Attribute("value");
if (!option_value) {
LogErr() << "no option value given";
return false;
}

auto new_option = std::make_shared<Option>();

new_option->name = option_name;

new_option->value.set_from_xml(type_str, option_name);
new_option->value.set_from_xml(type_str, option_value);

if (std::strcmp(option_value, default_str) == 0) {
new_option->is_default = true;
found_default = true;
}

// LogDebug() << "Type: " << type_str << ", name: " << option_name;

Expand Down Expand Up @@ -252,28 +272,59 @@ bool CameraDefinition::parse_xml()
new_parameter->options.push_back(new_option);
}

_settings.insert(std::pair<std::string, std::shared_ptr<Parameter>>(
param_name, new_parameter));
if (!found_default) {
LogErr() << "Default not found.";
return false;
}

_parameter_map.insert(std::pair<std::string, std::shared_ptr<Parameter>>(
param_name, new_parameter));
}

return true;
}

void CameraDefinition::update_setting(const std::string &name,
const MavlinkParameters::ParamValue &value)
void CameraDefinition::assume_default_settings()
{
_current_settings.clear();

for (const auto &parameter : _parameter_map) {
for (const auto &option : parameter.second->options) {

if (!option->is_default) {
continue;
}

_current_settings.insert(
std::pair<std::string, MavlinkParameters::ParamValue>(parameter.first,
option->value));
}
}
}

bool CameraDefinition::set_setting(const std::string &name,
const MavlinkParameters::ParamValue &value)
{
UNUSED(name);
UNUSED(value);
#if 0
if (_current_settings.find(name) == _current_settings.end()) {
_current_settings.insert(
std::pair<std::string, ParameterValue>
(name, value));
} else {
_current_settings[name] = value;
if (_parameter_map.find(name) != _parameter_map.end()) {
LogErr() << "Unknown setting to set";
return false;
}
#endif

_current_settings.at(name) = value;
return true;
}

bool CameraDefinition::get_setting(const std::string &name,
MavlinkParameters::ParamValue &value) const
{
if (_current_settings.find(name) != _current_settings.end()) {
LogErr() << "Unknown setting to get";
return false;
}

value = _current_settings.at(name);

return true;
}

} // namespace dronecore
17 changes: 13 additions & 4 deletions plugins/camera/camera_definition.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,17 +21,24 @@ class CameraDefinition
std::string get_vendor() const;
std::string get_model() const;

void update_setting(const std::string &name, const MavlinkParameters::ParamValue &value);
void assume_default_settings();

bool get_current_parameters(std::map<std::string, std::string> &parameters);
struct Setting {
std::string name;
MavlinkParameters::ParamValue value;
};

bool set_setting(const std::string &name, const MavlinkParameters::ParamValue &value);
bool get_setting(const std::string &name, MavlinkParameters::ParamValue &value) const;

bool get_all_settings(std::map<std::string, MavlinkParameters::ParamValue> &settings) const;

// Non-copyable
CameraDefinition(const CameraDefinition &) = delete;
const CameraDefinition &operator=(const CameraDefinition &) = delete;

private:
typedef std::map<std::string, MavlinkParameters::ParamValue> roption_t;

typedef std::map<std::string, roption_t> parameter_range_t;

struct Option {
Expand All @@ -54,7 +61,9 @@ class CameraDefinition

tinyxml2::XMLDocument _doc {};

std::map<std::string, std::shared_ptr<Parameter>> _settings;
std::map<std::string, std::shared_ptr<Parameter>> _parameter_map;

std::map<std::string, MavlinkParameters::ParamValue> _current_settings;

std::string _model;
std::string _vendor;
Expand Down
12 changes: 8 additions & 4 deletions plugins/camera/camera_definition_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,15 @@ using namespace dronecore;

static const char *e90_unit_test_file = "plugins/camera/e90_unit_test.xml";

TEST(CameraDefinition, LoadE90InfoFile)
TEST(CameraDefinition, E90LoadInfoFile)
{
CameraDefinition cd;
ASSERT_TRUE(cd.load_file(e90_unit_test_file));
EXPECT_STREQ(cd.get_vendor().c_str(), "Yuneec");
EXPECT_STREQ(cd.get_model().c_str(), "E90");
}

TEST(CameraDefinition, LoadE90InfoString)
TEST(CameraDefinition, E90LoadInfoString)
{
std::ifstream file_stream(e90_unit_test_file);
ASSERT_TRUE(file_stream.is_open());
Expand All @@ -33,17 +33,21 @@ TEST(CameraDefinition, LoadE90InfoString)
EXPECT_STREQ(cd.get_model().c_str(), "E90");
}

TEST(CameraDefinition, LoadE90All)
TEST(CameraDefinition, E90ShowDefaultSettings)
{
// Run this from root.
CameraDefinition cd;
ASSERT_TRUE(cd.load_file(e90_unit_test_file));

cd.assume_default_settings();

std::map<std::string, MavlinkParameters::ParamValue> settings {};
EXPECT_TRUE(cd.get_all_settings(settings));
#if 0
std::map<std::string, std::string> parameters {};
ASSERT_TRUE(cd.get_current_parameters(parameters));

//auto before = steady_time();
#if 0
for (auto &parameter : parameters) {
LogDebug() << parameter.first << " => " << parameter.second->description;
for (auto &option : parameter.second->options) {
Expand Down
4 changes: 2 additions & 2 deletions plugins/camera/e90_unit_test.xml
Original file line number Diff line number Diff line change
Expand Up @@ -836,7 +836,7 @@
</option>
</options>
</parameter>
<parameter name="CAM_VIDFMT" type="uint32" default="0">
<parameter name="CAM_VIDFMT" type="uint32" default="1">
<description>Video Format</description>
<updates>
<update>CAM_SHUTTERSPD</update>
Expand Down Expand Up @@ -880,7 +880,7 @@
</option>
</options>
</parameter>
<parameter name="CAM_PHOTORATIO" type="uint8" default="0">
<parameter name="CAM_PHOTORATIO" type="uint8" default="1">
<description>Photo Aspect Ratio</description>
<updates>
<update>CAM_ASPECTRATIO</update>
Expand Down

0 comments on commit 32f7b53

Please sign in to comment.