Skip to content

Commit

Permalink
component_information_server: API instead of JSON
Browse files Browse the repository at this point in the history
This changes from an API to load a JSON file to one that allows to
specify parameters.

This commit also adds an integration test to use this new API.
  • Loading branch information
julianoes committed Feb 18, 2022
1 parent e546e13 commit bd3f142
Show file tree
Hide file tree
Showing 13 changed files with 3,518 additions and 554 deletions.
2 changes: 1 addition & 1 deletion proto
1 change: 1 addition & 0 deletions src/integration_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ add_executable(integration_tests_runner
camera_take_photo_interval.cpp
camera_format.cpp
camera_test_helpers.cpp
component_information.cpp
connection.cpp
follow_me.cpp
geofence_inclusion.cpp
Expand Down
77 changes: 77 additions & 0 deletions src/integration_tests/component_information.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
#include <iostream>
#include <fstream>
#include <vector>
#include <atomic>
#include <future>

#include "integration_test_helper.h"
#include "mavsdk.h"
#include "plugins/component_information_server/component_information_server.h"
#include "plugins/mavlink_passthrough/mavlink_passthrough.h"
#include "plugins/param/param.h"

using namespace mavsdk;

TEST(ComponentInformation, Connect)
{
Mavsdk mavsdk_groundstation;
mavsdk_groundstation.set_configuration(
Mavsdk::Configuration{Mavsdk::Configuration::UsageType::CompanionComputer});
ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:24550"), ConnectionResult::Success);

Mavsdk mavsdk_companion;
mavsdk_companion.set_configuration(
Mavsdk::Configuration{Mavsdk::Configuration::UsageType::CompanionComputer});
ASSERT_EQ(
mavsdk_companion.add_any_connection("udp://127.0.0.1:24550"), ConnectionResult::Success);

// Time to discover each other.
std::this_thread::sleep_for(std::chrono::seconds(2));

ASSERT_EQ(mavsdk_groundstation.systems().size(), 1);
ASSERT_EQ(mavsdk_companion.systems().size(), 1);

auto groundstation = mavsdk_groundstation.systems().at(0);
auto companion = mavsdk_companion.systems().at(0);

auto server = ComponentInformationServer{companion};

auto param = ComponentInformationServer::FloatParam{};
param.name = "ANG_RATE_ACC_MAX";
param.short_description = "Angular rate acceleration maximum.";
param.long_description = "The lower the maximum angular rate acceleration, "
"the smoother the gimbal will react to user input.";
param.unit = "rad/s^2";
param.min_value = 1.0f;
param.max_value = 10.0f;
param.default_value = 3.0f;
param.start_value = 5.0f;
param.decimal_places = 1;

server.provide_float_param(param);

server.subscribe_float_param([](ComponentInformationServer::FloatParamUpdate param_update) {
LogInfo() << "Param " << param_update.name << " changed to " << param_update.value;
});

auto passthrough_client = MavlinkPassthrough{groundstation};
auto param_client = Param{groundstation};

const auto request = MavlinkPassthrough::CommandLong{
companion->get_system_id(),
0,
MAV_CMD_REQUEST_MESSAGE,
static_cast<float>(MAVLINK_MSG_ID_COMPONENT_INFORMATION),
0.0f,
0.0f,
0.0f,
0.0f,
0.0f,
0.0f};

passthrough_client.send_command_long(request);

param_client.set_param_float("ANG_RATE_ACC_MAX", 4.0f);

std::this_thread::sleep_for(std::chrono::seconds(2));
}
12 changes: 12 additions & 0 deletions src/mavsdk/core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -838,6 +838,18 @@ void MAVLinkParameters::process_param_set(const mavlink_message_t& message)
new_work->param_value = _param_server_store.at(safe_param_id);
new_work->extended = false;
_work_queue.push_back(new_work);
std::lock_guard<std::mutex> lock(_param_changed_subscriptions_mutex);
for (const auto& subscription : _param_changed_subscriptions) {
if (subscription.param_name != safe_param_id) {
continue;
}
if (!subscription.any_type && !subscription.value_type.is_same_type(value)) {
LogErr() << "Received wrong param type in subscription for "
<< subscription.param_name;
continue;
}
subscription.callback(value);
}
} else {
LogDebug() << "Missing Param: " << safe_param_id;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,9 @@

namespace mavsdk {

using FloatParam = ComponentInformationServer::FloatParam;
using FloatParamUpdate = ComponentInformationServer::FloatParamUpdate;

ComponentInformationServer::ComponentInformationServer(System& system) :
PluginBase(),
_impl{std::make_unique<ComponentInformationServerImpl>(system)}
Expand All @@ -23,9 +26,68 @@ ComponentInformationServer::ComponentInformationServer(std::shared_ptr<System> s
ComponentInformationServer::~ComponentInformationServer() {}

ComponentInformationServer::Result
ComponentInformationServer::provide_peripheral_file(std::string path) const
ComponentInformationServer::provide_float_param(FloatParam param) const
{
return _impl->provide_float_param(param);
}

void ComponentInformationServer::subscribe_float_param(FloatParamCallback callback)
{
_impl->subscribe_float_param(callback);
}

bool operator==(
const ComponentInformationServer::FloatParam& lhs,
const ComponentInformationServer::FloatParam& rhs)
{
return (rhs.name == lhs.name) && (rhs.short_description == lhs.short_description) &&
(rhs.long_description == lhs.long_description) && (rhs.unit == lhs.unit) &&
(rhs.decimal_places == lhs.decimal_places) &&
((std::isnan(rhs.start_value) && std::isnan(lhs.start_value)) ||
rhs.start_value == lhs.start_value) &&
((std::isnan(rhs.default_value) && std::isnan(lhs.default_value)) ||
rhs.default_value == lhs.default_value) &&
((std::isnan(rhs.min_value) && std::isnan(lhs.min_value)) ||
rhs.min_value == lhs.min_value) &&
((std::isnan(rhs.max_value) && std::isnan(lhs.max_value)) ||
rhs.max_value == lhs.max_value);
}

std::ostream&
operator<<(std::ostream& str, ComponentInformationServer::FloatParam const& float_param)
{
str << std::setprecision(15);
str << "float_param:" << '\n' << "{\n";
str << " name: " << float_param.name << '\n';
str << " short_description: " << float_param.short_description << '\n';
str << " long_description: " << float_param.long_description << '\n';
str << " unit: " << float_param.unit << '\n';
str << " decimal_places: " << float_param.decimal_places << '\n';
str << " start_value: " << float_param.start_value << '\n';
str << " default_value: " << float_param.default_value << '\n';
str << " min_value: " << float_param.min_value << '\n';
str << " max_value: " << float_param.max_value << '\n';
str << '}';
return str;
}

bool operator==(
const ComponentInformationServer::FloatParamUpdate& lhs,
const ComponentInformationServer::FloatParamUpdate& rhs)
{
return (rhs.name == lhs.name) &&
((std::isnan(rhs.value) && std::isnan(lhs.value)) || rhs.value == lhs.value);
}

std::ostream& operator<<(
std::ostream& str, ComponentInformationServer::FloatParamUpdate const& float_param_update)
{
return _impl->provide_peripheral_file(path);
str << std::setprecision(15);
str << "float_param_update:" << '\n' << "{\n";
str << " name: " << float_param_update.name << '\n';
str << " value: " << float_param_update.value << '\n';
str << '}';
return str;
}

std::ostream& operator<<(std::ostream& str, ComponentInformationServer::Result const& result)
Expand All @@ -35,16 +97,14 @@ std::ostream& operator<<(std::ostream& str, ComponentInformationServer::Result c
return str << "Unknown";
case ComponentInformationServer::Result::Success:
return str << "Success";
case ComponentInformationServer::Result::NotFound:
return str << "Not Found";
case ComponentInformationServer::Result::OpenFailure:
return str << "Open Failure";
case ComponentInformationServer::Result::ReadFailure:
return str << "Read Failure";
case ComponentInformationServer::Result::FailedJsonParsing:
return str << "Failed Json Parsing";
case ComponentInformationServer::Result::FailedJsonSchema:
return str << "Failed Json Schema";
case ComponentInformationServer::Result::DuplicateParam:
return str << "Duplicate Param";
case ComponentInformationServer::Result::InvalidParamStartValue:
return str << "Invalid Param Start Value";
case ComponentInformationServer::Result::InvalidParamDefaultValue:
return str << "Invalid Param Default Value";
case ComponentInformationServer::Result::InvalidParamName:
return str << "Invalid Param Name";
default:
return str << "Unknown";
}
Expand Down
Loading

0 comments on commit bd3f142

Please sign in to comment.