Skip to content

Commit

Permalink
Modify closiim_ros_realsens
Browse files Browse the repository at this point in the history
- isbigendian = false

Modify encoding type for L_INT8
-> TYPE_8UC1
  • Loading branch information
hyunseok-yang committed Jan 26, 2023
1 parent 50b9deb commit f858121
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 8 deletions.
2 changes: 1 addition & 1 deletion cloisim_ros_base/include/cloisim_ros_base/camera_helper.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ static std::string GetImageEncondingType(const uint32_t pixel_format)
switch (pixel_format)
{
case 1:
encoding = sensor_msgs::image_encodings::MONO8;
encoding = sensor_msgs::image_encodings::TYPE_8UC1;
break;

case 2:
Expand Down
7 changes: 0 additions & 7 deletions cloisim_ros_realsense/src/realsense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,13 +232,6 @@ void RealSense::PublishImgData(const zmq::Bridge* const bridge_ptr, const std::s
sensor_msgs::fillImage(*msg_img, encoding_arg, rows_arg, cols_arg, step_arg,
reinterpret_cast<const void *>(pb_buf_.image().data().data()));

if ((encoding_arg.compare(sensor_msgs::image_encodings::TYPE_16UC1) == 0) ||
(encoding_arg.compare(sensor_msgs::image_encodings::TYPE_16SC1) == 0) ||
(encoding_arg.compare(sensor_msgs::image_encodings::TYPE_32FC1) == 0))
{
msg_img->is_bigendian = true;
}

// Publish camera info
auto camera_info_msg = camera_info_managers_[bridge_ptr]->getCameraInfo();
camera_info_msg.header.stamp = GetTime();
Expand Down

0 comments on commit f858121

Please sign in to comment.