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 cam mode warnings #1247

Merged
merged 4 commits into from
Oct 29, 2020
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
15 changes: 6 additions & 9 deletions src/core/mavlink_commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ MavlinkCommandSender::send_command(const MavlinkCommandSender::CommandInt& comma
auto prom = std::make_shared<std::promise<Result>>();
auto res = prom->get_future();

queue_command_async(command, [&prom](Result result, float progress) {
queue_command_async(command, [prom](Result result, float progress) {
UNUSED(progress);
// We can only fulfill the promise once in C++11.
// Therefore we have to ignore the IN_PROGRESS state and wait
Expand All @@ -55,7 +55,7 @@ MavlinkCommandSender::send_command(const MavlinkCommandSender::CommandLong& comm
auto prom = std::make_shared<std::promise<Result>>();
auto res = prom->get_future();

queue_command_async(command, [&prom](Result result, float progress) {
queue_command_async(command, [prom](Result result, float progress) {
UNUSED(progress);
// We can only fulfill the promise once in C++11.
// Therefore we have to ignore the IN_PROGRESS state and wait
Expand Down Expand Up @@ -151,9 +151,8 @@ void MavlinkCommandSender::receive_command_ack(mavlink_message_t message)
return;
}

// LogDebug() << "We got an ack: " << command_ack.command
// << " after: " << _parent.get_time().elapsed_since_s(work->time_started) << "
// s";
// LogDebug() << "We got an ack: " << command_ack.command << " after: "
// << _parent.get_time().elapsed_since_s(work->time_started) << " s";
temp_callback = work->callback;

switch (command_ack.result) {
Expand Down Expand Up @@ -205,10 +204,8 @@ void MavlinkCommandSender::receive_command_ack(mavlink_message_t message)
std::bind(&MavlinkCommandSender::receive_timeout, this),
work->retries_to_do * work->timeout_s,
&_timeout_cookie);
// FIXME: We can only call callbacks with promises once, so let's not do it
// on IN_PROGRESS.
// call_callback(work->callback, Result::IN_PROGRESS, command_ack.progress /
// 100.0f);

temp_result = {Result::InProgress, command_ack.progress / 100.0f};
break;

default:
Expand Down
20 changes: 3 additions & 17 deletions src/core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,33 +451,19 @@ void MAVLinkParameters::process_param_ext_value(const mavlink_message_t& message
case WorkItem::Type::Get: {
ParamValue value;
value.set_from_mavlink_param_ext_value(param_ext_value);

if (value.is_same_type(work->param_value)) {
if (work->get_param_callback) {
work->get_param_callback(MAVLinkParameters::Result::Success, value);
}
} else if (value.is_uint8() && work->param_value.is_uint16()) {
// FIXME: workaround for mismatching type uint8_t which should be uint16_t.
ParamValue correct_type_value;
correct_type_value.set_uint16(static_cast<uint16_t>(value.get_uint8()));
if (work->get_param_callback) {
work->get_param_callback(
MAVLinkParameters::Result::Success, correct_type_value);
}
} else if (value.is_uint8() && work->param_value.is_uint32()) {
// FIXME: workaround for mismatching type uint8_t which should be uint32_t.
ParamValue correct_type_value;
correct_type_value.set_uint32(static_cast<uint32_t>(value.get_uint8()));
if (work->get_param_callback) {
work->get_param_callback(
MAVLinkParameters::Result::Success, correct_type_value);
}
} else {
LogErr() << "Param types don't match";
LogErr() << "Param types don't match for " << work->param_name;
ParamValue no_value;
if (work->get_param_callback) {
work->get_param_callback(MAVLinkParameters::Result::WrongType, no_value);
}
}

_parent.unregister_timeout_handler(_timeout_cookie);
// LogDebug() << "time taken: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
Expand Down
37 changes: 36 additions & 1 deletion src/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -581,8 +581,43 @@ void CameraImpl::save_camera_mode(const float mavlink_camera_mode)
return;
}

// If there is a camera definition (which is the case if we are
// in this function, and if CAM_MODE is defined there, then
// we reuse that type. Otherwise, we hardcode it to `uint32_t`.
// Note that it could be that the camera definition defines options
// different than {PHOTO, VIDEO}, in which case the mode received
// from CAMERA_SETTINGS will be wrong. Not sure if it means that
// it should be ignored in that case, but that may be tricky to
// maintain (what if the MAVLink CAMERA_MODE enum evolves?), so
// I am assuming here that in such a case, CAMERA_SETTINGS is
// never sent by the camera.
MAVLinkParameters::ParamValue value;
value.set_uint32(uint32_t(mavlink_camera_mode));
if (_camera_definition->get_setting("CAM_MODE", value)) {
if (value.is_uint8()) {
value.set_uint8(uint8_t(mavlink_camera_mode));
} else if (value.is_int8()) {
value.set_int8(int8_t(mavlink_camera_mode));
} else if (value.is_uint16()) {
value.set_uint16(uint16_t(mavlink_camera_mode));
} else if (value.is_int16()) {
value.set_int16(int16_t(mavlink_camera_mode));
} else if (value.is_uint32()) {
value.set_uint32(uint32_t(mavlink_camera_mode));
} else if (value.is_int32()) {
value.set_int32(int32_t(mavlink_camera_mode));
} else if (value.is_uint64()) {
value.set_uint64(uint64_t(mavlink_camera_mode));
} else if (value.is_int64()) {
value.set_int64(int64_t(mavlink_camera_mode));
} else if (value.is_float()) {
value.set_float(float(mavlink_camera_mode));
} else if (value.is_double()) {
value.set_double(double(mavlink_camera_mode));
}
} else {
value.set_uint32(uint32_t(mavlink_camera_mode));
}

_camera_definition->set_setting("CAM_MODE", value);
refresh_params();
}
Expand Down