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

AP_Mount, AP_Camera: Load CAMERA_INFORMATION from JSON #27594

Conversation

nexton-winjeel
Copy link
Contributor

This PR allows us to add a *.json file to the SD card (or ROMFS) that is used to populate the CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION MAVLink messages. These messages are sent for AP_Mount backends that do not already implement these messages.

Sending these messages allows a GCS to auto-configure the video stream to receive video from the payload.

@rmackay9
Copy link
Contributor

really great to see this!

@nexton-winjeel
Copy link
Contributor Author

Two issues:

  1. the test vectors in the new tests fail the formatter; and
  2. the shutil.copy() calls in the new tests fail if the intermediate directories aren't present.

I'll fix them now...

@nexton-winjeel nexton-winjeel force-pushed the upstream/create-camera_information-msg-from-json branch from 01583e5 to fd46a2f Compare July 22, 2024 04:44
@nexton-winjeel nexton-winjeel marked this pull request as ready for review July 22, 2024 04:46
@nexton-winjeel
Copy link
Contributor Author

@rmackay9: I'll jump on the dev call tomorrow if you want to discuss this.

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should make sure that when compiled out these new features take up approximately no space.

Won't be able to be no space given different return values for some methods now

@@ -462,6 +462,10 @@ bool AP_Camera::send_mavlink_message(GCS_MAVLINK &link, const enum ap_message ms
CHECK_PAYLOAD_SIZE2(CAMERA_CAPTURE_STATUS);
send_camera_capture_status(chan);
break;
case MSG_VIDEO_STREAM_INFO:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
case MSG_VIDEO_STREAM_INFO:
AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
case MSG_VIDEO_STREAM_INFO:

.... and generally use it elsewhere. These are defined in GCS_config.h

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done.

#endif

#if AP_CAMERA_JSON_INFO_ENABLED
#include <AP_Filesystem/AP_Filesystem.h>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We don't usually indent these lines

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed.

// fall back to looking for the same folder in ROMFS.
//
// This allocates a AP_JSON::value object that will need to be freed.
AP_JSON::value * AP_Camera_Backend::_load_mount_msg_json(const char* json_filename) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
AP_JSON::value * AP_Camera_Backend::_load_mount_msg_json(const char* json_filename) {
AP_JSON::value * AP_Camera_Backend::_load_mount_msg_json(const char* json_filename)
{

similarly elsewhere

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed.

// This allocates a AP_JSON::value object that will need to be freed.
AP_JSON::value * AP_Camera_Backend::_load_mount_msg_json(const char* json_filename) {
char* romfs_json_path = nullptr;
int alloc = asprintf(&romfs_json_path, "@ROMFS/mav_msg_def/AP_Camera/%s", json_filename);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do without the local here?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I find it more readable with the local.

}

// helper function to copy a JSON double into a msg struct
template <typename T> bool AP_Camera_Backend::_copy_json_field_double(const AP_JSON::value* obj, const char* key, T& dst) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
template <typename T> bool AP_Camera_Backend::_copy_json_field_double(const AP_JSON::value* obj, const char* key, T& dst) {
template <typename T>
bool AP_Camera_Backend::_copy_json_field_double(const AP_JSON::value* obj, const char* key, T& dst) {

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed.

if (!_copy_json_field_string(obj, "cam_definition_uri", camera_info.msg.cam_definition_uri, sizeof(camera_info.msg.cam_definition_uri))) goto err;

// Populate the fields that shouldn't change.
camera_info.msg.time_boot_ms = AP_HAL::millis();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Errr.. this one should definitely change

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed.

Comment on lines 620 to 622
#undef GET_JSON_DOUBLE
#undef GET_JSON_STR

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Were these replaced by the template function?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, they were. Fixed.

@@ -87,7 +87,16 @@ void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->send_camera_information(get_mount_instance(), chan);
bool sent_by_mount = mount->send_camera_information(get_mount_instance(), chan);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
bool sent_by_mount = mount->send_camera_information(get_mount_instance(), chan);
const bool sent_by_mount = mount->send_camera_information(get_mount_instance(), chan);

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed.

Comment on lines 124 to 125
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
AP_Mount* mount = AP::mount();
if (mount == nullptr) {
return;
}

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed.

@@ -0,0 +1,20 @@
# This file is used to populate the VIDEO_STREAM_INFORMATION message sent by
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

SHould we put these under an "examples" subdirectory as we do for a lot of other things?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd prefer they live in the AP_Camera folder. The code in the backend makes assumptions about what fields are and aren't present in the JSON.

@nexton-winjeel nexton-winjeel force-pushed the upstream/create-camera_information-msg-from-json branch from fd46a2f to 230a5ca Compare July 24, 2024 03:15
@nexton-winjeel nexton-winjeel marked this pull request as draft July 24, 2024 23:31
@nexton-winjeel
Copy link
Contributor Author

Temporarily back to draft -- I need to confirm that this still works on hardware.

@nexton-winjeel nexton-winjeel force-pushed the upstream/create-camera_information-msg-from-json branch from 230a5ca to 40a132f Compare July 25, 2024 00:47
@nexton-winjeel
Copy link
Contributor Author

Running on a CubeOrange with debug enabled:

STABILIZE> reboot
STABILIZE> Got COMMAND_ACK: PREFLIGHT_REBOOT_SHUTDOWN: ACCEPTED
Device /dev/serial/by-id/usb-Hex_ProfiCNC_CubeOrange_24004E001351313139383237-if00 is dead
Device /dev/serial/by-id/usb-Hex_ProfiCNC_CubeOrange_24004E001351313139383237-if00 reopened OK
AP_Logger_File: buffer size=204800
MS5611 found on bus 4 address 0x02
MS5611 found on bus 1 address 0x03
AP: Initialising ArduPilot
disabling flow control on serial 1
_load_mount_msg_json:479: failed to load 'mav_msg_def/AP_Camera/camera_information.json'
init_camera_information_from_json:616: Loaded camera_info from 'camera_information.json'
init_camera_information_from_json:617:     camera_info.msg.time_boot_ms=0
init_camera_information_from_json:618:     camera_info.msg.vendor_name='Unknown'
init_camera_information_from_json:619:     camera_info.msg.model_name='Camera'
init_camera_information_from_json:620:     camera_info.msg.firmware_version=0
init_camera_information_from_json:621:     camera_info.msg.focal_length=1.600000
init_camera_information_from_json:622:     camera_info.msg.sensor_size_h=3840.000
init_camera_information_from_json:623:     camera_info.msg.sensor_size_v=2160.000
init_camera_information_from_json:624:     camera_info.msg.resolution_h=1920
init_camera_information_from_json:625:     camera_info.msg.resolution_v=1080
init_camera_information_from_json:626:     camera_info.msg.lens_id=1
init_camera_information_from_json:627:     camera_info.msg.flags=256
init_camera_information_from_json:628:     camera_info.msg.cam_definition_version=0
init_camera_information_from_json:629:     camera_info.msg.cam_definition_uri=''
init_camera_information_from_json:630:     camera_info.msg.gimbal_device_id=1
_load_mount_msg_json:479: failed to load 'mav_msg_def/AP_Camera/video_stream_information.json'
init_video_stream_information_from_json:560: Loaded video_stream_info from 'video_stream_information.json'
init_video_stream_information_from_json:561:     video_stream_info.msg.stream_id=1
init_video_stream_information_from_json:562:     video_stream_info.msg.count=1
init_video_stream_information_from_json:563:     video_stream_info.msg.type=1
init_video_stream_information_from_json:564:     video_stream_info.msg.flags=1
init_video_stream_information_from_json:565:     video_stream_info.msg.framerate=30.00000
init_video_stream_information_from_json:566:     video_stream_info.msg.resolution_h=1920
init_video_stream_information_from_json:567:     video_stream_info.msg.resolution_v=1080
init_video_stream_information_from_json:568:     video_stream_info.msg.bitrate=1500
init_video_stream_information_from_json:569:     video_stream_info.msg.rotation=0
init_video_stream_information_from_json:570:     video_stream_info.msg.hfov=50
init_video_stream_information_from_json:572:     video_stream_info.msg.name='Video'
init_video_stream_information_from_json:573:     video_stream_info.msg.uri='127.0.0.1:5600'
AP: Calibrating barometer
AP: Barometer 1 calibration complete
AP: Barometer 2 calibration complete
Init Gyro**
AP: ArduPilot Ready

@nexton-winjeel
Copy link
Contributor Author

@rmackay9, @peterbarker: Closing in favour of #27794

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants