ModalAI Forum
    • Categories
    • Recent
    • Tags
    • Popular
    • Users
    • Groups
    • Register
    • Login

    voxl-camera-server more exif metadata bugs

    VOXL SDK
    4
    11
    699
    Loading More Posts
    • Oldest to Newest
    • Newest to Oldest
    • Most Votes
    Reply
    • Reply as topic
    Log in to reply
    This topic has been deleted. Only users with topic management privileges can see it.
    • Zachary Lowell 0Z
      Zachary Lowell 0 ModalAI Team
      last edited by

      Hi @AndriiHlyvko we do not ever pipe in a JPG - the raw frame gets converted and saved as a jpeg in camera-server.

      The android library does the image encoding to JPG from the raw frame. We pull the raw frame over the snapshot pipe via HAL3 and then we do the JPG conversion from the raw pipe.

      https://gitlab.com/voxl-public/voxl-sdk/services/voxl-camera-server/-/blame/dev/src/hal3_camera_mgr.cpp?ref_type=heads#L281 --> Here is where the buffers get allocated

      https://gitlab.com/voxl-public/voxl-sdk/services/voxl-camera-server/-/blob/dev/src/hal3_camera_mgr.cpp?ref_type=heads#L433 --> Here is where we define the parameters of the HAL3 pipe itself that is pulling the raw frames

      https://gitlab.com/voxl-public/voxl-sdk/services/voxl-camera-server/-/blob/dev/src/hal3_camera_mgr.cpp?ref_type=heads#L2585 --> This is where the MPA is created to actually pipe the data, etc.

      Specific to the actual jpg conversion, you are right in that it is abstracted out and we leverage an android library to handle the encoding into JPG, we just calculate the size of the frame and then feed that INTO the jpeg conversion - so the raw frame should be completely accessible to you.

      https://gitlab.com/voxl-public/voxl-sdk/services/voxl-camera-server/-/blob/dev/src/hal3_camera_mgr.cpp?ref_type=heads#L1649 --> if you follow the meta and src_data parameter here, you will see where the raw data is coming in. We do leverage the libexif library after the encoding to unpack it and update the gps data as well - that can be found here: https://gitlab.com/voxl-public/voxl-sdk/services/voxl-camera-server/-/blob/dev/src/hal3_camera_mgr.cpp?ref_type=heads#L1483

      Let me know if this helps!!
      Zach

      A 1 Reply Last reply Reply Quote 0
      • A
        AndriiHlyvko @Zachary Lowell 0
        last edited by

        @Zachary-Lowell-0 thanks!

        Just to give some context. I am trying to change the camera focal length in the exif data of the jpeg. But because somehow there are two Exif blocks in the jpeg only one is changes and not the other. There should only be one exif data block in the jpeg.

        Here is an example output of the exiftool
        Screenshot from 2024-06-28 10-55-19.png

        1 Reply Last reply Reply Quote 0
        • Zachary Lowell 0Z
          Zachary Lowell 0 ModalAI Team
          last edited by

          @AndriiHlyvko said in voxl-camera-server more exif metadata bugs:

          Just to give some context. I am trying to change the camera focal length in the exif data of the jpeg. But because somehow there are two Exif blocks in the jpeg only one is changes and not the other. There should only be one exif data block in the jpeg.

          Here is an example output of the exiftool

          Hm that is quite strange - I will do soem debugging - it could be that we are creating a new exif dataset to attach to the jpeg instead of filling the original. Will look more into it while you do as well! Let me know if you figure it out and I will do the same on the post here.

          A 2 Replies Last reply Reply Quote 0
          • A
            AndriiHlyvko @Zachary Lowell 0
            last edited by

            @Zachary-Lowell-0 what I did find out is that inside ProcessSnapshotFrame the second Exif block gets created by createExifData and written to the image. This is because the jpeg did contain an exif block (I assume it was created by the android library).
            The correct approach is to edit the already created exif block inside the jpeg. Also the find_jpeg_buffer function is wrong. I assume it tried to look for the start of the jpeg stream but it instead is looking for the SOI marker. The SOI marker and the start of the data section are not the same. The SOI actually marks the file itself as a jpeg type.

            A 1 Reply Last reply Reply Quote 0
            • A
              AndriiHlyvko @AndriiHlyvko
              last edited by

              @AndriiHlyvko an example of jpeg image structure:

              FFD8 (SOI)
              ...  (optional markers like APP0/APP1)
              FFDB (DQT)
              FFC2 (SOF0)  // Progressive DCT
              FFC4 (DHT) // huffman table
              FFDA (SOS)   // First scan
              ...  (compressed image data for first scan)
              FFDA (SOS)   // Second scan
              ...  (compressed image data for second scan)
              ...
              FFD9 (EOI)
              
              
              1 Reply Last reply Reply Quote 0
              • A
                AndriiHlyvko @Zachary Lowell 0
                last edited by

                @Zachary-Lowell-0 I managed to fix the code. Essentially I was updating the already existing jpeg exif block. Here is my solution. Its a little messy cuz I haven't had the time to clean it up. But I tested and it works.
                Would you guys be interested in pulling in my changes?

                // Function to create a new tag or update an existing one
                static ExifEntry* create_or_update_tag(ExifData* exif, ExifIfd ifd, ExifTag tag, ExifFormat fmt, unsigned int size, unsigned int components) {
                    ExifEntry* entry = exif_content_get_entry(exif->ifd[ifd], tag);
                    if (!entry) {
                        // Create a new entry if it doesn't exist
                        printf("Creating entry: %d\n", (int)tag);
                        //entry = exif_entry_new();
                        entry = create_tag(exif, ifd, tag, size);
                        entry->tag = tag;
                        entry->components = components;
                        entry->format = fmt;
                        ///entry->data = (unsigned char*)malloc(size);
                        //exif_content_add_entry(exif->ifd[ifd], entry);
                        ///exif_entry_unref(entry);
                    } else {
                        // Update the existing entry
                        if (entry->size < size) {
                            // If the existing entry size is insufficient, reallocate memory
                            entry->data = (unsigned char*)realloc(entry->data, size);
                            entry->size = size;
                        }
                        entry->components = components;
                        entry->format = fmt;
                    }
                    return entry;
                }
                
                void PerCameraMgr::ProcessSnapshotFrame(image_result result)
                {
                    BufferBlock* bufferBlockInfo = bufferGetBufferInfo(&snap_bufferGroup, result.second.buffer);
                
                    // first write to pipe if subscribed
                    camera_image_metadata_t meta;
                    if(getMeta(result.first, &meta)) {
                        M_WARN("Trying to process encode buffer without metadata\n");
                        return;
                    }
                
                    int start_index = 0;
                    //int start_index2 = 0;
                    uint8_t* src_data = (uint8_t*)bufferBlockInfo->vaddress;
                    //int extractJpgSize = bufferBlockInfo->size;
                    
                    int extractJpgSize = find_jpeg_buffer_size(src_data, bufferBlockInfo->size, &start_index);
                    
                    assert(start_index == 0);
                    
                    //int _extractJpgSize = find_jpeg_buffer(src_data, bufferBlockInfo->size, &start_index2);
                    
                    // find APP1 block start and length
                    size_t prev_exif_block_start_idx = 0;
                    size_t prev_exif_block_size = find_exif_start(src_data, bufferBlockInfo->size, &prev_exif_block_start_idx);
                
                    if(extractJpgSize == 1){
                        M_ERROR("Real Size of JPEG is incorrect");
                        return;
                    }
                
                    printf("Snapshot jpeg start: %6d len %8d\n", start_index, extractJpgSize);
                
                #ifndef APQ8096
                    // Load the EXIF data from the file
                    unsigned char *exif_data;
                    unsigned int exif_data_len;
                    ExifEntry *entry;
                   
                    // can create exif data from raw jpeg image
                    ExifData* exif = exif_data_new_from_data(src_data, extractJpgSize);
                    //ExifData *exif = createExifData();
                    if (exif == nullptr) {
                        printf("Issue getting exif data from origin\n");
                        return;
                    }
                    exif_data_fix(exif);
                    
                    //printf("Exif data before mods\n");
                    //exif_data_dump(exif);
                    //printf("End Exif data before mods\n");
                    /**
                     * @brief Good description of exif format https://www.media.mit.edu/pia/Research/deepview/exif.html 
                     * 
                     */
                    ExifByteOrder imageByteOrder = exif_data_get_byte_order(exif); /**< Each camera saves its Exif data in a different byte order */
                    //gps_data_t gps_grabbed_info = grab_gps_info();
                
                    // Code to add latitude to exif tag
                    entry = create_or_update_tag(exif, EXIF_IFD_GPS, (ExifTag)EXIF_TAG_GPS_LATITUDE_REF, (ExifFormat)EXIF_FORMAT_ASCII, 2*sizeof(char), 1);
                    if (_uav_state.lat_deg >= 0) {
                        memcpy(entry->data, "N", sizeof(char));
                    } else {
                        memcpy(entry->data, "S", sizeof(char));
                        _uav_state.lat_deg *= -1;
                    }
                    
                    
                    entry = create_or_update_tag(exif, EXIF_IFD_GPS, (ExifTag)EXIF_TAG_GPS_LATITUDE, (ExifFormat)EXIF_FORMAT_RATIONAL, 3*sizeof(ExifRational), 3);
                
                    ExifLong degrees_lat = static_cast<ExifLong>(_uav_state.lat_deg);
                    
                    double fractional = (_uav_state.lat_deg - degrees_lat);
                    ExifLong minutes_lat = static_cast<ExifLong>(fractional*60);
                    
                    fractional = (fractional*60) - minutes_lat;
                    double seconds_lat = (fractional * 60);
                    
                    ExifRational degrees_r = { degrees_lat, 1 };
                    ExifRational minutes_r = { minutes_lat, 1 };
                    ExifRational seconds_r = { static_cast<ExifLong>(seconds_lat * 1000000), 1000000 }; // Increased precision for seconds
                    
                    exif_set_rational(entry->data, imageByteOrder, degrees_r);
                    exif_set_rational(entry->data + sizeof(ExifRational), imageByteOrder, minutes_r);
                    exif_set_rational(entry->data + 2 * sizeof(ExifRational), imageByteOrder, seconds_r);
                
                    // Code to add longitude to exif tag
                    entry = create_or_update_tag(exif, EXIF_IFD_GPS, (ExifTag)EXIF_TAG_GPS_LONGITUDE_REF, (ExifFormat)EXIF_FORMAT_ASCII, 2*sizeof(char), 1);
                    if (_uav_state.lon_deg >= 0) {
                        memcpy(entry->data, "E", sizeof(char));
                    } else {
                        memcpy(entry->data, "W", sizeof(char));
                        _uav_state.lon_deg *= -1;
                    }
                
                    entry = create_or_update_tag(exif, EXIF_IFD_GPS, (ExifTag)EXIF_TAG_GPS_LONGITUDE, (ExifFormat)EXIF_FORMAT_RATIONAL, 3*sizeof(ExifRational), 3);
                
                    ExifLong degrees_lon = static_cast<ExifLong>(_uav_state.lon_deg);
                    
                    fractional = (_uav_state.lon_deg - degrees_lon);
                    ExifLong minutes_lon = static_cast<ExifLong>(fractional*60);
                    
                    fractional = (fractional*60) - minutes_lon;
                    double seconds_lon = (fractional * 60);
                    
                    degrees_r = { degrees_lon, 1 };
                    minutes_r = { minutes_lon, 1 };
                    seconds_r = { static_cast<ExifLong>(seconds_lon * 1000000), 1000000 }; // Increased precision for seconds
                    
                    exif_set_rational(entry->data, imageByteOrder, degrees_r);
                    exif_set_rational(entry->data + sizeof(ExifRational), imageByteOrder, minutes_r);
                    exif_set_rational(entry->data + 2 * sizeof(ExifRational), imageByteOrder, seconds_r); 
                
                    // Code to add altitude to exif tag
                    entry = create_or_update_tag(exif, EXIF_IFD_GPS, (ExifTag)EXIF_TAG_GPS_ALTITUDE, (ExifFormat)EXIF_FORMAT_RATIONAL, sizeof(ExifRational), 1);
                
                    double alt_lon = _uav_state.alt_msl_meters;
                    unsigned int tmp = static_cast<unsigned int>(alt_lon * 1000);
                    exif_set_rational(entry->data, imageByteOrder, (ExifRational){tmp, 1000});
                    
                    
                    entry = create_or_update_tag(exif, EXIF_IFD_GPS, (ExifTag)EXIF_TAG_GPS_ALTITUDE_REF, (ExifFormat)EXIF_FORMAT_BYTE, sizeof(uint8_t), 1);
                    entry->data[0] = 0; /**< 0 for above sea level */
                    
                    
                    // dumping all exif data
                    
                    entry = create_or_update_tag(exif, EXIF_IFD_EXIF, (ExifTag)EXIF_TAG_FOCAL_LENGTH, (ExifFormat)EXIF_FORMAT_RATIONAL, sizeof(ExifRational), 1);
                    ExifRational focal_len_r = {static_cast<ExifLong>(9.99 * 1000000), 1000000};
                    exif_set_rational(entry->data, EXIF_BYTE_ORDER_MOTOROLA, focal_len_r);
                    
                    entry = create_or_update_tag(exif, EXIF_IFD_EXIF, (ExifTag)EXIF_TAG_FNUMBER, (ExifFormat)EXIF_FORMAT_RATIONAL, sizeof(ExifRational), 1);
                    ExifRational f_number_r = {static_cast<ExifLong>(13.6 * 1000000), 1000000};
                    exif_set_rational(entry->data, EXIF_BYTE_ORDER_MOTOROLA, f_number_r);
                    
                    
                    entry = create_or_update_tag(exif, EXIF_IFD_EXIF, (ExifTag)EXIF_TAG_FOCAL_LENGTH_IN_35MM_FILM, (ExifFormat)EXIF_FORMAT_SHORT, sizeof(ExifShort), 1);
                    ExifShort f_35_mm_r = 17;
                    exif_set_short(entry->data, EXIF_BYTE_ORDER_MOTOROLA, f_35_mm_r);
                    
                    exif_data_save_data(exif, &exif_data, &exif_data_len);
                    
                    //printf("Exif data after mods\n");
                    //exif_data_dump(exif);
                    //printf("End Exif data after mods\n");
                
                    assert(exif_data != NULL);
                #endif
                
                    meta.magic_number = CAMERA_MAGIC_NUMBER;
                    meta.width        = snap_width;
                    meta.height       = snap_height;
                    meta.format       = IMAGE_FORMAT_JPG;
                    meta.size_bytes   = extractJpgSize;
                    pipe_server_write_camera_frame(snapshotPipe, meta, &src_data[start_index]);
                
                    // now, if there is a filename in the queue, write it too
                    if(snapshotQueue.size() != 0){
                        char *filename = snapshotQueue.front();
                        snapshotQueue.pop();
                
                        M_PRINT("Camera: %s writing snapshot to :\"%s\"\n", name, filename);
                        //WriteSnapshot(bufferBlockInfo, snap_halfmt, filename);
                
                        FILE* file_descriptor = fopen(filename, "wb");
                        if(! file_descriptor){
                
                            //Check to see if we were just missing parent directories
                            CreateParentDirs(filename);
                
                            file_descriptor = fopen(filename, "wb");
                
                            if(! file_descriptor){
                                M_ERROR("failed to open file descriptor for snapshot save to: %s\n", filename);
                                return;
                            }
                        }
                
                #ifndef APQ8096
                        
                        // first write the beginning of jpeg and stop where the previous exif APP1 header started
                        // this will include the FFD8 marker
                        printf("Start: 0, end:%lu\n", prev_exif_block_start_idx);
                        if (fwrite(src_data, prev_exif_block_start_idx, 1, file_descriptor) != 1) {
                            fprintf(stderr, "Error writing to file with jpeg %s\n", filename);
                        }
                        
                        if (fwrite(exif_header, exif_header_len, 1, file_descriptor) != 1) {
                           fprintf(stderr, "Error writing to file inin exif header %s\n", filename);
                        }
                        if (fputc((exif_data_len+2) >> 8, file_descriptor) < 0) {
                           fprintf(stderr, "Error writing to file in big endian order %s\n", filename);
                        }
                        if (fputc((exif_data_len+2) & 0xff, file_descriptor) < 0) {
                           fprintf(stderr, "Error writing to file with fputc %s\n", filename);
                        }
                        if (fwrite(exif_data, exif_data_len, 1, file_descriptor) != 1) {
                           fprintf(stderr, "Error writing to file with data block %s\n", filename);
                        }
                        
                        // next write from the last bits of the prev APP1 block
                        size_t jpeg_start_idx = prev_exif_block_start_idx + prev_exif_block_size;
                        size_t jpeg_size = extractJpgSize - prev_exif_block_size;
                        
                        //size_t jpeg_start_idx = prev_exif_block_start_idx + prev_exif_block_size + (exif_data_len+2+exif_header_len);
                        //size_t jpeg_size = extractJpgSize - prev_exif_block_size + (exif_data_len+2+exif_header_len);
                        
                        printf("Start: %lu, end:%lu\n", jpeg_start_idx, jpeg_size);
                        if (fwrite(src_data + jpeg_start_idx, jpeg_size, 1, file_descriptor) != 1) {
                            fprintf(stderr, "Error writing to file with jpeg %s\n", filename);
                        }
                        
                        free(exif_data);
                        exif_data_unref(exif);
                
                tomT Eric KatzfeyE 2 Replies Last reply Reply Quote 1
                • tomT
                  tom admin @AndriiHlyvko
                  last edited by

                  @AndriiHlyvko Feel free to fork the repo and create a merge request into the dev branch and the team will review

                  1 Reply Last reply Reply Quote 0
                  • Eric KatzfeyE
                    Eric Katzfey ModalAI Team @AndriiHlyvko
                    last edited by

                    @AndriiHlyvko Yes, we would definitely like to have those changes, thanks! As Tom stated, please fork the repo and then prepare a pull request.

                    A 1 Reply Last reply Reply Quote 0
                    • A
                      AndriiHlyvko @Eric Katzfey
                      last edited by

                      @Eric-Katzfey Here is the MR I made for this issue https://gitlab.com/voxl-public/voxl-sdk/services/voxl-camera-server/-/merge_requests/44

                      I also made a few related changes that should allow handling of additional UAV metadata in the images

                      Eric KatzfeyE 1 Reply Last reply Reply Quote 0
                      • Eric KatzfeyE
                        Eric Katzfey ModalAI Team @AndriiHlyvko
                        last edited by

                        @AndriiHlyvko Thanks! We have merged in those changes.

                        1 Reply Last reply Reply Quote 0
                        • First post
                          Last post
                        Powered by NodeBB | Contributors