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

v1.4 fix storage type translation (STORAGE_TYPE_OTHER) #2150

Merged
merged 3 commits into from
Oct 10, 2023
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
63 changes: 42 additions & 21 deletions src/mavsdk/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -894,37 +894,58 @@ void CameraImpl::process_storage_information(const mavlink_message_t& message)

{
std::lock_guard<std::mutex> lock(_status.mutex);
switch (storage_information.status) {
case STORAGE_STATUS_EMPTY:
_status.data.storage_status = Camera::Status::StorageStatus::NotAvailable;
break;
case STORAGE_STATUS_UNFORMATTED:
_status.data.storage_status = Camera::Status::StorageStatus::Unformatted;
break;
case STORAGE_STATUS_READY:
_status.data.storage_status = Camera::Status::StorageStatus::Formatted;
break;
case STORAGE_STATUS_NOT_SUPPORTED:
_status.data.storage_status = Camera::Status::StorageStatus::NotSupported;
break;
default:
_status.data.storage_status = Camera::Status::StorageStatus::NotSupported;
LogErr() << "Unknown storage status received.";
break;
}

_status.data.storage_status = storage_status_from_mavlink(storage_information.status);
_status.data.available_storage_mib = storage_information.available_capacity;
_status.data.used_storage_mib = storage_information.used_capacity;
_status.data.total_storage_mib = storage_information.total_capacity;
_status.data.storage_id = storage_information.storage_id;
_status.data.storage_type =
static_cast<Camera::Status::StorageType>(storage_information.type);
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 is the bug.

_status.data.storage_type = storage_type_from_mavlink(storage_information.type);
_status.received_storage_information = true;
}

check_status();
}

Camera::Status::StorageStatus
CameraImpl::storage_status_from_mavlink(const int storage_status) const
{
switch (storage_status) {
case STORAGE_STATUS_EMPTY:
return Camera::Status::StorageStatus::NotAvailable;
case STORAGE_STATUS_UNFORMATTED:
return Camera::Status::StorageStatus::Unformatted;
case STORAGE_STATUS_READY:
return Camera::Status::StorageStatus::Formatted;
break;
case STORAGE_STATUS_NOT_SUPPORTED:
return Camera::Status::StorageStatus::NotSupported;
default:
LogErr() << "Unknown storage status received.";
return Camera::Status::StorageStatus::NotSupported;
}
}

Camera::Status::StorageType CameraImpl::storage_type_from_mavlink(const int storage_type) const
{
switch (storage_type) {
default:
LogErr() << "Unknown storage_type enum value: " << storage_type;
// FALLTHROUGH
case STORAGE_TYPE_UNKNOWN:
return mavsdk::Camera::Status::StorageType::Unknown;
case STORAGE_TYPE_USB_STICK:
return mavsdk::Camera::Status::StorageType::UsbStick;
case STORAGE_TYPE_SD:
return mavsdk::Camera::Status::StorageType::Sd;
case STORAGE_TYPE_MICROSD:
return mavsdk::Camera::Status::StorageType::Microsd;
case STORAGE_TYPE_HD:
return mavsdk::Camera::Status::StorageType::Hd;
case STORAGE_TYPE_OTHER:
return mavsdk::Camera::Status::StorageType::Other;
}
}

void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
{
mavlink_camera_image_captured_t image_captured;
Expand Down
3 changes: 3 additions & 0 deletions src/mavsdk/plugins/camera/camera_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,9 @@ class CameraImpl : public PluginImplBase {
void process_video_stream_status(const mavlink_message_t& message);
void process_flight_information(const mavlink_message_t& message);

Camera::Status::StorageStatus storage_status_from_mavlink(const int storage_status) const;
Camera::Status::StorageType storage_type_from_mavlink(const int storage_type) const;

Camera::EulerAngle to_euler_angle_from_quaternion(Camera::Quaternion quaternion);

void notify_mode();
Expand Down
Loading