Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Minimal changes required to build ROS2 branch on ROS2 Humble #76

Open
wants to merge 1 commit into
base: ROS2
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@ find_package(rosidl_default_generators REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(pcl_conversions REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(image_transport REQUIRED)
# install(FILES DESTINATION share/${PROJECT_NAME})
# ament_export_dependencies(rosidl_default_runtime)
# ament_export_dependencies(rosidl_default_runtime)
Expand Down Expand Up @@ -47,6 +51,7 @@ target_include_directories(PandarGeneral PRIVATE
src/HesaiLidar_General_SDK/src/PandarGeneralRaw/
${Boost_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${tf2_ros_INCLUDE_DIRS}
# ${ament_INCLUDE_DIRS}
)
target_link_libraries(PandarGeneral
Expand All @@ -55,6 +60,7 @@ target_link_libraries(PandarGeneral
Boost::thread
pcap
# ${ament_LIBRARIES}
${tf2_ros_LIBRARIES}
)

rosidl_target_interfaces(PandarGeneral ${PROJECT_NAME} "rosidl_typesupport_cpp")
Expand Down Expand Up @@ -99,6 +105,9 @@ ament_target_dependencies(hesai_lidar_node
"sensor_msgs"
"std_msgs"
"tf2_geometry_msgs"
"tf2_ros"
"image_transport"
"rclcpp_components"
)

target_include_directories(hesai_lidar_node PRIVATE
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <string>

#include <boost/function.hpp>
#include <boost/bind.hpp>

#include "pandarGeneral/point_types.h"
#include "src/input.h"
Expand All @@ -35,6 +36,7 @@
#include <hesai_lidar/msg/pandar_scan.hpp>
#include <hesai_lidar/msg/pandar_packet.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
// #include <geometry_msgs/TransformStamped.h>
#include <Eigen/Dense>

Expand Down
2 changes: 1 addition & 1 deletion src/cloud_nodelet.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
*/

#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/io/pcd_io.h>
Expand Down
2 changes: 1 addition & 1 deletion src/main.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/io/pcd_io.h>
Expand Down
7 changes: 4 additions & 3 deletions src/main_ros2.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,18 @@
#include <rclcpp/rclcpp.hpp>
#include <hesai_lidar/msg/pandar_scan.hpp>
#include <hesai_lidar/msg/pandar_packet.hpp>
#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include "pandarGeneral_sdk/pandarGeneral_sdk.h"
#include <fstream>
#include <memory>
#include <chrono>
#include <string>
#include <functional>
#include "std_msgs/msg/string.hpp"
#include "boost/bind.hpp"
// #define PRINT_FLAG

using namespace std;
Expand Down Expand Up @@ -40,7 +41,7 @@ class HesaiLidarClient: public rclcpp::Node
this->declare_parameter<std::string>("target_frame", "");
this->declare_parameter<std::string>("fixed_frame", "");
rclcpp::QoS qos(rclcpp::KeepLast(7));
lidarPublisher = this->create_publisher<sensor_msgs::msg::PointCloud2>("pandar");
lidarPublisher = this->create_publisher<sensor_msgs::msg::PointCloud2>("pandar", qos);
packetPublisher = this->create_publisher<hesai_lidar::msg::PandarScan>("pandar_packets", qos);
this->timer_callback();
}
Expand Down