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

camera_manager: mavlink update #1057

Merged
merged 3 commits into from
Oct 10, 2024
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
2 changes: 1 addition & 1 deletion .github/workflows/build_test_macos.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ jobs:
- name: Before Install
run: |
brew update;
git clone -b release-1.10.0 https://github.com/google/googletest
git clone -b v1.15.2 https://github.com/google/googletest
git clone https://github.com/mavlink/c_library_v2.git /usr/local/include/mavlink
- name: Install
run: |
Expand Down
87 changes: 0 additions & 87 deletions .github/workflows/firmware_build_test.yml

This file was deleted.

15 changes: 9 additions & 6 deletions src/gazebo_camera_manager_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -657,7 +657,8 @@ void CameraManagerPlugin::_handle_request_camera_settings(const mavlink_message_
0, // time_boot_ms
_mode, // Camera Mode
1.0E2 * (_zoom - 1.0)/ (_maxZoom - 1.0), // Zoom level
NAN); // Focus level
NAN, // Focus level
0); // MAVLink camera with its own component ID
_send_mavlink_message(&msg, srcaddr);
}

Expand All @@ -678,18 +679,19 @@ void CameraManagerPlugin::_handle_request_video_stream_status(const mavlink_mess
mavlink_message_t msg;
mavlink_msg_video_stream_status_pack_chan(
_systemID,
_componentID, // Component ID
_componentID, // Component ID
MAVLINK_COMM_1,
&msg,
static_cast<uint8_t>(sid), // Stream ID
VIDEO_STREAM_STATUS_FLAGS_RUNNING, // Flags (It's always running)
30, // Frame rate
_width, // Horizontal resolution
_width, // Horizontal resolution
_height, // Vertical resolution
2048, // Bit rate (made up)
0, // Rotation (none)
90 // FOV (made up)
);
90, // FOV (made up)
0); // MAVLink camera with its own component ID

_send_mavlink_message(&msg, srcaddr);
}

Expand Down Expand Up @@ -801,7 +803,8 @@ void CameraManagerPlugin::_send_capture_status(struct sockaddr* srcaddr)
interval, // image interval
recording_time_ms, // recording time in ms
available_mib, // available storage capacity
_imageCounter); // total number of images
_imageCounter, // total number of images
0); // MAVLink camera with its own component ID
_send_mavlink_message(&msg, srcaddr);
}

Expand Down
Loading