diff --git a/cloisim_ros_base/include/cloisim_ros_base/camera_helper.h b/cloisim_ros_base/include/cloisim_ros_base/camera_helper.h index a455400a..73d33c75 100644 --- a/cloisim_ros_base/include/cloisim_ros_base/camera_helper.h +++ b/cloisim_ros_base/include/cloisim_ros_base/camera_helper.h @@ -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: diff --git a/cloisim_ros_realsense/src/realsense.cpp b/cloisim_ros_realsense/src/realsense.cpp index db682e9f..371ae0f3 100644 --- a/cloisim_ros_realsense/src/realsense.cpp +++ b/cloisim_ros_realsense/src/realsense.cpp @@ -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(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();