Skip to content

Commit

Permalink
cpplint
Browse files Browse the repository at this point in the history
  • Loading branch information
roncapat authored Nov 16, 2023
1 parent 617d367 commit 06101df
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions src/SensorMsgPointCloud2_PCLPointCloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,23 +9,23 @@ Copyright 2023 Patrick Roncagliolo

StampedPointCloud_PCL::StampedPointCloud_PCL(const StampedPointCloud_PCL & other)
{
//RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Copy constructor called");
// RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Copy constructor called");
// raise(SIGTRAP);
this->header = other.header;
this->cloud = other.cloud;
}

StampedPointCloud_PCL::StampedPointCloud_PCL(StampedPointCloud_PCL && other)
{
//RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Move constructor called");
// RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Move constructor called");
// raise(SIGTRAP);
this->header = std::move(other.header);
this->cloud = std::move(other.cloud);
}

StampedPointCloud_PCL & StampedPointCloud_PCL::operator=(const StampedPointCloud_PCL & other)
{
//RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Assignment operator called");
// RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Assignment operator called");
// raise(SIGTRAP);
if (this == &other) {return *this;}
this->header = other.header;
Expand Down Expand Up @@ -67,7 +67,7 @@ void rclcpp::TypeAdapter<StampedPointCloud_PCL,
const StampedPointCloud_PCL & source,
sensor_msgs::msg::PointCloud2 & destination)
{
//RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Conversion to message");
// RCLCPP_WARN(rclcpp::get_logger("PointCloud2 Adapter"), "Conversion to message");
// raise(SIGTRAP);

std::visit([&](auto && cloud) {pcl::toROSMsg(cloud, destination);}, source.cloud);
Expand Down

0 comments on commit 06101df

Please sign in to comment.