Skip to content

Commit

Permalink
Merge pull request #57 from lge-ros2/main
Browse files Browse the repository at this point in the history
Merge into humble
  • Loading branch information
hyunseok-yang authored Jan 26, 2023
2 parents 484ae3f + f7703e2 commit fb4bb27
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 14 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
12 changes: 6 additions & 6 deletions cloisim_ros_base/src/base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ string Base::GetModelName()

string Base::GetRobotName()
{
bool is_single_mode;
bool is_single_mode = false;
get_parameter("single_mode", is_single_mode);

string robotName;
Expand All @@ -213,9 +213,9 @@ msgs::Pose Base::GetObjectTransform(zmq::Bridge* const bridge_ptr, const string

const auto reply = RequestReplyMessage(bridge_ptr, "request_transform", target_name);

if (reply.ByteSize() <= 0)
if (reply.ByteSizeLong() <= 0)
{
DBG_SIM_ERR("Faild to get object transform, length(%ld)", reply.ByteSize());
DBG_SIM_ERR("Faild to get object transform, length(%ld)", reply.ByteSizeLong());
}
else
{
Expand Down Expand Up @@ -251,9 +251,9 @@ void Base::GetRos2Parameter(zmq::Bridge* const bridge_ptr)

const auto reply = RequestReplyMessage(bridge_ptr, "request_ros2");

if (reply.ByteSize() <= 0)
if (reply.ByteSizeLong() <= 0)
{
DBG_SIM_ERR("Faild to get ROS2 common info, length(%ld)", reply.ByteSize());
DBG_SIM_ERR("Faild to get ROS2 common info, length(%ld)", reply.ByteSizeLong());
}
else
{
Expand Down Expand Up @@ -420,4 +420,4 @@ void Base::SetTime(const cloisim::msgs::Time &time)
void Base::SetTime(const int32_t seconds, const uint32_t nanoseconds)
{
m_sim_time = Convert(seconds, nanoseconds);
}
}
7 changes: 0 additions & 7 deletions cloisim_ros_realsense/src/realsense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,13 +233,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 fb4bb27

Please sign in to comment.