Skip to content

Commit

Permalink
Remove header file (#6)
Browse files Browse the repository at this point in the history
* Update CMakeLists.txt

* Remove header file
  • Loading branch information
ToshikiNakamura0412 committed May 6, 2024
1 parent 8319b47 commit 2d7fcf8
Show file tree
Hide file tree
Showing 4 changed files with 48 additions and 88 deletions.
13 changes: 3 additions & 10 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,22 +14,15 @@ find_package(catkin REQUIRED COMPONENTS
###################################
## catkin specific configuration ##
###################################
catkin_package(
INCLUDE_DIRS include
LIBRARIES scan_to_pcl_ros
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
)
catkin_package()

###########
## Build ##
###########
include_directories(include ${catkin_INCLUDE_DIRS})

add_library(${PROJECT_NAME} src/scan_to_pcl.cpp)
add_executable(scan_to_pcl src/scan_to_pcl_node.cpp)
add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(scan_to_pcl ${PROJECT_NAME} ${catkin_LIBRARIES})
add_executable(scan_to_pcl_node src/scan_to_pcl.cpp)
target_link_libraries(scan_to_pcl_node ${catkin_LIBRARIES})

#############
## Testing ##
Expand Down
36 changes: 0 additions & 36 deletions include/scan_to_pcl_ros/scan_to_pcl_ros.h

This file was deleted.

70 changes: 45 additions & 25 deletions src/scan_to_pcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,37 +5,57 @@
* @copyright Copyright (c) 2024
*/

#include <laser_geometry/laser_geometry.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl_ros/point_cloud.h>
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud2.h>
#include <string>
#include <tf/transform_listener.h>

#include "scan_to_pcl_ros/scan_to_pcl_ros.h"

ScanToPcl::ScanToPcl() : private_nh_("~")
class ScanToPcl
{
private_nh_.param<int>("hz", hz_, 10);
private_nh_.param<std::string>("frame_id", frame_id_, "base_link");
hokuyo_sub_ = nh_.subscribe("/scan", 1, &ScanToPcl::hokuyo_callback, this);
pcl_from_scan_pub_ = nh_.advertise<pcl::PointCloud<pcl::PointXYZ>>("/pcl_from_scan", 1);
}
public:
ScanToPcl() : private_nh_("~")
{
private_nh_.param<std::string>("frame_id", frame_id_, std::string("base_scan"));

void ScanToPcl::hokuyo_callback(const sensor_msgs::LaserScan::ConstPtr &scan_in)
{
laser_geometry::LaserProjection projector;
sensor_msgs::PointCloud2 cloud;
projector.projectLaser(*scan_in, cloud); // convert a sensor_msgs/LaserScan to a sensor_msgs/PointCloud

// Publish the new point cloud.
cloud.header.frame_id = frame_id_;
cloud.header.stamp = scan_in->header.stamp;
pcl_from_scan_pub_.publish(cloud);
}
cloud_pub_ = nh_.advertise<pcl::PointCloud<pcl::PointXYZ>>("/cloud", 1);
scan_sub_ = nh_.subscribe("/scan", 1, &ScanToPcl::scan_callback, this);

void ScanToPcl::process()
{
ros::Rate loop_rate(hz_);
tf_listener_.setExtrapolationLimit(ros::Duration(0.1));

ROS_INFO_STREAM(ros::this_node::getName() << " node has started..");
ROS_INFO_STREAM("frame_id: " << frame_id_);
}

while (ros::ok())
private:
void scan_callback(const sensor_msgs::LaserScan::ConstPtr &msg)
{
ros::spinOnce();
loop_rate.sleep();
laser_geometry::LaserProjection projector;
sensor_msgs::PointCloud2 cloud;
projector.transformLaserScanToPointCloud(frame_id_, *msg, cloud, tf_listener_);
cloud.header.frame_id = frame_id_;
cloud.header.stamp = ros::Time::now();
cloud_pub_.publish(cloud);
}

std::string frame_id_;

ros::NodeHandle nh_;
ros::NodeHandle private_nh_;
ros::Publisher cloud_pub_;
ros::Subscriber scan_sub_;

tf::TransformListener tf_listener_;
};

int main(int argc, char **argv)
{
ros::init(argc, argv, "scan_to_pcl");
ScanToPcl scan_to_pcl;
ros::spin();

return 0;
}
17 changes: 0 additions & 17 deletions src/scan_to_pcl_node.cpp

This file was deleted.

0 comments on commit 2d7fcf8

Please sign in to comment.