Skip to content

Commit

Permalink
Merge pull request #135 from peci1/patch-2
Browse files Browse the repository at this point in the history
Initialize is_bigendian when decoding using libjpeg turbo
  • Loading branch information
ijnek authored Feb 8, 2023
2 parents 7825def + bd52526 commit c26d149
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions compressed_image_transport/src/compressed_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <boost/endian/arithmetic.hpp>
#include "compressed_image_transport/compressed_subscriber.h"
#include <sensor_msgs/image_encodings.h>
#include <cv_bridge/cv_bridge.h>
Expand Down Expand Up @@ -111,6 +112,8 @@ sensor_msgs::ImagePtr CompressedSubscriber::decompressJPEG(const std::vector<uin
ret->width = width;
ret->height = height;
ret->encoding = source_encoding;
// consistent with cv_bridge
ret->is_bigendian = (boost::endian::order::native == boost::endian::order::big); // NOLINT

int pixelFormat;

Expand Down

0 comments on commit c26d149

Please sign in to comment.