diff --git a/.gitignore b/.gitignore index 9835878..5c15165 100644 --- a/.gitignore +++ b/.gitignore @@ -105,4 +105,3 @@ AMENT_IGNORE .vscode .cache -src/modelec/src \ No newline at end of file diff --git a/src/modelec/src/lidar_controller.cpp b/src/modelec/src/lidar_controller.cpp new file mode 100644 index 0000000..63a643b --- /dev/null +++ b/src/modelec/src/lidar_controller.cpp @@ -0,0 +1,22 @@ +#include + +namespace Modelec { + LidarController::LidarController() : Node("lidar_controller") { + subscription_ = this->create_subscription( + "scan", 10, [this](const sensor_msgs::msg::LaserScan::SharedPtr msg) { + processLidarData(msg); + }); + } + + void LidarController::processLidarData(const sensor_msgs::msg::LaserScan::SharedPtr msg) { + // Process the received LiDAR data + RCLCPP_INFO(this->get_logger(), "Received LiDAR data: %s", msg->header.frame_id.c_str()); + } +} + +int main(int argc, char **argv) { + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file