Skip to content

Commit

Permalink
Use C-style strings.
Browse files Browse the repository at this point in the history
As of ros2/rclcpp#1442 , the RCLCPP_
macros no longer accept std::string arguments, and only C-style
strings.

https://index.ros.org/doc/ros2/Releases/Release-Galactic-Geochelone/#change-in-rclcpp-s-logging-macros
has more information about it.

This PR changes all of the use of std::string to C-style strings,
which will allow this package to build against Rolling (and
hence Galactic).

Note that this change is entirely backwards compatible, so it
can be used for both Foxy and Rolling.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Jan 26, 2021
1 parent 65b0725 commit 5713681
Show file tree
Hide file tree
Showing 3 changed files with 38 additions and 40 deletions.
19 changes: 9 additions & 10 deletions src/v4l2_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ void V4L2Camera::createParameters()
if (cinfo_->validateURL(camera_info_url)) {
cinfo_->loadCameraInfo(camera_info_url);
} else {
RCLCPP_WARN(get_logger(), std::string{"Invalid camera info URL: "} + camera_info_url);
RCLCPP_WARN(get_logger(), "Invalid camera info URL: %s", camera_info_url.c_str());
}
}

Expand Down Expand Up @@ -245,8 +245,8 @@ void V4L2Camera::createParameters()
default:
RCLCPP_WARN(
get_logger(),
std::string{"Control type not currently supported: "} + std::to_string(unsigned(c.type)) +
", for control: " + c.name);
"Control type not currently supported: %s, for control: %s", std::to_string(unsigned(c.type)).c_str(),
c.name.c_str());
continue;
}
control_name_to_id_[name] = c.id;
Expand Down Expand Up @@ -276,9 +276,8 @@ bool V4L2Camera::handleParameter(rclcpp::Parameter const & param)
default:
RCLCPP_WARN(
get_logger(),
std::string{"Control parameter type not currently supported: "} +
std::to_string(unsigned(param.get_type())) +
", for parameter: " + param.get_name());
"Control parameter type not currently supported: %s, for parameter: %s",
std::to_string(unsigned(param.get_type())).c_str(), param.get_name().c_str());
}
} else if (param.get_name() == "output_encoding") {
output_encoding_ = param.as_string();
Expand All @@ -298,7 +297,7 @@ bool V4L2Camera::handleParameter(rclcpp::Parameter const & param)
if (cinfo_->validateURL(camera_info_url)) {
return cinfo_->loadCameraInfo(camera_info_url);
} else {
RCLCPP_WARN(get_logger(), std::string{"Invalid camera info URL: "} + camera_info_url);
RCLCPP_WARN(get_logger(), "Invalid camera info URL: %s", camera_info_url.c_str());
return false;
}
}
Expand Down Expand Up @@ -330,7 +329,7 @@ bool V4L2Camera::requestImageSize(std::vector<int64_t> const & size)
if (size.size() != 2) {
RCLCPP_WARN(
get_logger(),
"Invalid image size; expected dimensions: 2, actual: " + std::to_string(size.size()));
"Invalid image size; expected dimensions: 2, actual: %s", std::to_string(size.size()).c_str());
return false;
}

Expand Down Expand Up @@ -425,7 +424,7 @@ sensor_msgs::msg::Image::UniquePtr V4L2Camera::convert(sensor_msgs::msg::Image c
{
RCLCPP_DEBUG(
get_logger(),
std::string{"Converting: "} + img.encoding + " -> " + output_encoding_);
"Converting: %s -> %s", img.encoding.c_str(), output_encoding_.c_str());

// TODO(sander): temporary until cv_bridge and image_proc are available in ROS 2
if (img.encoding == sensor_msgs::image_encodings::YUV422 &&
Expand All @@ -446,7 +445,7 @@ sensor_msgs::msg::Image::UniquePtr V4L2Camera::convert(sensor_msgs::msg::Image c
} else {
RCLCPP_WARN_ONCE(
get_logger(),
std::string{"Conversion not supported yet: "} + img.encoding + " -> " + output_encoding_);
"Conversion not supported yet: %s -> %s", img.encoding.c_str(), output_encoding_.c_str());
return nullptr;
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/v4l2_camera_compose_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class ComposeTest : public rclcpp::Node
[this](sensor_msgs::msg::Image::UniquePtr img) {
std::stringstream ss;
ss << "Image message address [RECEIVE]:\t" << img.get();
RCLCPP_DEBUG(get_logger(), ss.str());
RCLCPP_DEBUG(get_logger(), "%s", ss.str().c_str());
});
}

Expand Down
57 changes: 28 additions & 29 deletions src/v4l2_camera_device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ bool V4l2CameraDevice::open()
if (fd_ < 0) {
auto msg = std::ostringstream{};
msg << "Failed opening device " << device_ << ": " << strerror(errno) << " (" << errno << ")";
RCLCPP_ERROR(rclcpp::get_logger("v4l2_camera"), msg.str());
RCLCPP_ERROR(rclcpp::get_logger("v4l2_camera"), "%s", msg.str().c_str());
return false;
}

Expand All @@ -57,26 +57,26 @@ bool V4l2CameraDevice::open()

RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
std::string{"Driver: "} + (char *)capabilities_.driver);
"Driver: %s", capabilities_.driver);
RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
std::string{"Version: "} + std::to_string(capabilities_.version));
"Version: %s", std::to_string(capabilities_.version).c_str());
RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
std::string{"Device: "} + (char *)capabilities_.card);
"Device: %s", capabilities_.card);
RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
std::string{"Location: "} + (char *)capabilities_.bus_info);
"Location: %s", capabilities_.bus_info);

RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
"Capabilities:");
RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
std::string{" Read/write: "} + (canRead ? "YES" : "NO"));
" Read/write: %s", (canRead ? "YES" : "NO"));
RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
std::string{" Streaming: "} + (canStream ? "YES" : "NO"));
" Streaming: %s", (canStream ? "YES" : "NO"));

// Get current data (pixel) format
auto formatReq = v4l2_format{};
Expand All @@ -86,8 +86,8 @@ bool V4l2CameraDevice::open()

RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
"Current pixel format: " + FourCC::toString(cur_data_format_.pixelFormat) +
" @ " + std::to_string(cur_data_format_.width) + "x" + std::to_string(cur_data_format_.height));
"Current pixel format: %s @ %sx%s", FourCC::toString(cur_data_format_.pixelFormat).c_str(),
std::to_string(cur_data_format_.width).c_str(), std::to_string(cur_data_format_.height).c_str());

// List all available image formats and controls
listImageFormats();
Expand All @@ -98,15 +98,15 @@ bool V4l2CameraDevice::open()
for (auto const & format : image_formats_) {
RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
" " + FourCC::toString(format.pixelFormat) + " - " + format.description);
" %s - %s", FourCC::toString(format.pixelFormat).c_str(), format.description.c_str());
}

RCLCPP_INFO(rclcpp::get_logger("v4l2_camera"), "Available controls: ");
for (auto const & control : controls_) {
RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
" " + control.name + " (" + std::to_string(static_cast<unsigned>(control.type)) + ") = " +
std::to_string(getControlValue(control.id)));
" %s (%s) = %s", control.name.c_str(), std::to_string(static_cast<unsigned>(control.type)).c_str(),
std::to_string(getControlValue(control.id)).c_str());
}

return true;
Expand All @@ -129,8 +129,8 @@ bool V4l2CameraDevice::start()
if (-1 == ioctl(fd_, VIDIOC_QBUF, &buf)) {
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Buffer failure on capture start: "} +
strerror(errno) + " (" + std::to_string(errno) + ")");
"Buffer failure on capture start: %s (%s)", strerror(errno),
std::to_string(errno).c_str());
return false;
}
}
Expand All @@ -140,8 +140,8 @@ bool V4l2CameraDevice::start()
if (-1 == ioctl(fd_, VIDIOC_STREAMON, &type)) {
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Failed stream start: "} +
strerror(errno) + " (" + std::to_string(errno) + ")");
"Failed stream start: %s (%s)", strerror(errno),
std::to_string(errno).c_str());
return false;
}
return true;
Expand All @@ -155,7 +155,7 @@ bool V4l2CameraDevice::stop()
if (-1 == ioctl(fd_, VIDIOC_STREAMOFF, &type)) {
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Failed stream stop"});
"Failed stream stop");
return false;
}

Expand Down Expand Up @@ -196,17 +196,17 @@ Image::UniquePtr V4l2CameraDevice::capture()
if (-1 == ioctl(fd_, VIDIOC_DQBUF, &buf)) {
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Error dequeueing buffer: "} +
strerror(errno) + " (" + std::to_string(errno) + ")");
"Error dequeueing buffer: %s (%s)", strerror(errno),
std::to_string(errno).c_str());
return nullptr;
}

// Requeue buffer to be reused for new captures
if (-1 == ioctl(fd_, VIDIOC_QBUF, &buf)) {
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Error re-queueing buffer: "} +
strerror(errno) + " (" + std::to_string(errno) + ")");
"Error re-queueing buffer: %s (%s)", strerror(errno),
std::to_string(errno).c_str());
return nullptr;
}

Expand Down Expand Up @@ -236,8 +236,8 @@ int32_t V4l2CameraDevice::getControlValue(uint32_t id)
if (-1 == ioctl(fd_, VIDIOC_G_CTRL, &ctrl)) {
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Failed getting value for control "} + std::to_string(id) +
": " + strerror(errno) + " (" + std::to_string(errno) + "); returning 0!");
"Failed getting value for control %s: %s (%s); returning 0!", std::to_string(id).c_str(),
strerror(errno), std::to_string(errno).c_str());
return 0;
}
return ctrl.value;
Expand All @@ -254,9 +254,8 @@ bool V4l2CameraDevice::setControlValue(uint32_t id, int32_t value)
[id](Control const & c) {return c.id == id;});
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Failed setting value for control "} + control->name + " to " +
std::to_string(value) +
": " + strerror(errno) + " (" + std::to_string(errno) + ")");
"Failed setting value for control %s to %s: %s (%s)", control->name.c_str(),
std::to_string(value).c_str(), strerror(errno), std::to_string(errno).c_str());
return false;
}
return true;
Expand All @@ -272,14 +271,14 @@ bool V4l2CameraDevice::requestDataFormat(const PixelFormat & format)

RCLCPP_INFO(
rclcpp::get_logger("v4l2_camera"),
"Requesting format: " + std::to_string(format.width) + "x" + std::to_string(format.height));
"Requesting format: %sx%s", std::to_string(format.width).c_str(), std::to_string(format.height).c_str());

// Perform request
if (-1 == ioctl(fd_, VIDIOC_S_FMT, &formatReq)) {
RCLCPP_ERROR(
rclcpp::get_logger("v4l2_camera"),
std::string{"Failed requesting pixel format"} +
": " + strerror(errno) + " (" + std::to_string(errno) + ")");
"Failed requesting pixel format: %s (%s)", strerror(errno),
std::to_string(errno).c_str());
return false;
}

Expand Down

0 comments on commit 5713681

Please sign in to comment.