Skip to content

Commit

Permalink
Rebase and comment fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed May 6, 2022
1 parent 69f43fe commit 011d227
Show file tree
Hide file tree
Showing 6 changed files with 20 additions and 11 deletions.
2 changes: 1 addition & 1 deletion proto
3 changes: 3 additions & 0 deletions src/mavsdk/core/include/mavsdk/mavsdk.h
Original file line number Diff line number Diff line change
Expand Up @@ -303,6 +303,9 @@ class Mavsdk {
*/
void subscribe_on_new_system(const NewSystemCallback& callback);

/**
* @brief High level type of a server component.
*/
enum class ServerComponentType {
Autopilot, /**< @brief The component identifies as an autopilot. */
GroundStation, /**< @brief The component identifies as a ground station. */
Expand Down
8 changes: 6 additions & 2 deletions src/mavsdk/core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -412,6 +412,10 @@ MAVLinkParameters::set_param_custom(const std::string& name, const std::string&
void MAVLinkParameters::get_param_custom_async(
const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
{
if (_parameter_debugging) {
LogDebug() << "getting param " << name;
}

if (name.size() > PARAM_ID_LEN) {
LogErr() << "Error: param name too long";
if (callback) {
Expand All @@ -421,7 +425,7 @@ void MAVLinkParameters::get_param_custom_async(
}

// Otherwise, push work onto queue.
auto new_work = std::make_shared<WorkItem>(_parent.timeout_s());
auto new_work = std::make_shared<WorkItem>(_timeout_s_callback());
new_work->type = WorkItem::Type::Get;
new_work->callback = callback;
new_work->param_name = name;
Expand Down Expand Up @@ -454,7 +458,7 @@ void MAVLinkParameters::set_param_custom_async(
return;
}

auto new_work = std::make_shared<WorkItem>(_parent.timeout_s());
auto new_work = std::make_shared<WorkItem>(_timeout_s_callback());

MAVLinkParameters::ParamValue value_to_set;
value_to_set.set_custom(value);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,13 @@ class CameraServer : public ServerPluginBase {
~CameraServer() override;

/**
* @brief
* @brief Possible results when taking a photo.
*/
enum class TakePhotoFeedback {
Unknown, /**< @brief. */
Ok, /**< @brief. */
Busy, /**< @brief. */
Failed, /**< @brief. */
Unknown, /**< @brief Unknown. */
Ok, /**< @brief Ok. */
Busy, /**< @brief Busy. */
Failed, /**< @brief Failed. */
};

/**
Expand All @@ -68,7 +68,7 @@ class CameraServer : public ServerPluginBase {
std::string vendor_name{}; /**< @brief Name of the camera vendor */
std::string model_name{}; /**< @brief Name of the camera model */
std::string firmware_version{}; /**< @brief Camera firmware version in
<major>[.<minor>[.<patch>[.<dev>]]] format */
major[.minor[.patch[.dev]]] format */
float focal_length_mm{}; /**< @brief Focal length */
float horizontal_sensor_size_mm{}; /**< @brief Horizontal sensor size */
float vertical_sensor_size_mm{}; /**< @brief Vertical sensor size */
Expand Down
5 changes: 3 additions & 2 deletions src/mavsdk/plugins/param_server/param_server_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ ParamServer::Result ParamServerImpl::provide_param_float(std::string name, float
std::pair<ParamServer::Result, std::string>
ParamServerImpl::retrieve_param_custom(std::string name) const
{
const auto result = _parent->retrieve_server_param_custom(name);
const auto result =
_server_component_impl->mavlink_parameters().retrieve_server_param_custom(name);

if (result.first == MAVLinkParameters::Result::Success) {
return {ParamServer::Result::Success, result.second};
Expand All @@ -77,7 +78,7 @@ ParamServerImpl::provide_param_custom(std::string name, const std::string& value
if (name.size() > 16) {
return ParamServer::Result::ParamNameTooLong;
}
_parent->provide_server_param_custom(name, value);
_server_component_impl->mavlink_parameters().provide_server_param_custom(name, value);
return ParamServer::Result::Success;
}

Expand Down
1 change: 1 addition & 0 deletions src/system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ add_executable(system_tests_runner
action_arm_disarm.cpp
system_tests_helper.cpp
param_set_and_get.cpp
param_custom_set_and_get.cpp
)

target_include_directories(system_tests_runner
Expand Down

0 comments on commit 011d227

Please sign in to comment.