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

ROS2 Galactic Compatibility #44

Open
wants to merge 13 commits into
base: ROS2
Choose a base branch
from
33 changes: 28 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,16 @@
cmake_minimum_required(VERSION 3.5)
project(hesai_lidar)

# Default to C++14
# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()

if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -fPIC")
endif()
set( CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -fPIC" )

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
Expand All @@ -14,6 +20,9 @@ find_package(Boost REQUIRED COMPONENTS system)
find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(rclcpp REQUIRED)
find_package(pcl_conversions REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rosidl_typesupport_c REQUIRED)
find_package(rosidl_default_generators REQUIRED)
Expand Down Expand Up @@ -99,14 +108,19 @@ ament_target_dependencies(hesai_lidar_node
"sensor_msgs"
"std_msgs"
"tf2_geometry_msgs"
"tf2_ros"
)

target_include_directories(hesai_lidar_node PRIVATE
src/HesaiLidar_General_SDK/include
src/HesaiLidar_General_SDK/src/PandarGeneralRaw/include
${PCL_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
)
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)



target_link_libraries(hesai_lidar_node
${PCL_IO_LIBRARIES}
Expand All @@ -115,10 +129,19 @@ target_link_libraries(hesai_lidar_node
)

rosidl_target_interfaces(hesai_lidar_node ${PROJECT_NAME} "rosidl_typesupport_cpp")

install(TARGETS PandarGeneralSDK
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
PUBLIC_HEADER DESTINATION ${CMAKE_INSTALL_INCLUDEDIR})

install(TARGETS hesai_lidar_node
DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME})

ament_package()
install(DIRECTORY config
DESTINATION share/${PROJECT_NAME})

ament_export_include_directories(include)
ament_package()
57 changes: 47 additions & 10 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,31 +12,68 @@ Developed based on [HesaiLidar_General_SDK](https://github.com/HesaiTechnology/H
## Environment and Dependencies
**System environment requirement: Linux + ROS2**

 Recommanded:
 Ubuntu - with ROS2 dashing desktop-full installed or
Check resources on http://ros.org for installation guide

**Library Dependencies: libpcap-dev + libpcl-dev + libboost-dev**
 Recommended:
 Ubuntu - with ROS2 galactic desktop-full installed or
use the `rosdep` tool and ROS2 galactic base to install all the dependencies

### Install ROS2 dependencies

#### Install and configure rosdep

```.bash
# install rosdep ROS2 Galactic
sudo apt-get install python3-rosdep
```
or on non ubuntu platforms

```.bash
# install rosdep ROS2 Galactic
sudo pip3 install -U rosdep
```

**Configure:**
```.bash
sudo rosdep init
rosdep update
```

**Install ROS dependencies:**
```.bash
# Go to the top of your workspace
rosdep install --from-paths src/HesaiLidar_General_ROS --ignore-src -r -y
```
$sudo apt install libpcl-dev libpcap-dev libboost-dev

**Library Dependencies: libpcap-dev + libpcl-dev + libboost-dev**
```.bash
sudo apt install libpcl-dev libpcap-dev libboost-dev
```


## Download and Build

**Download code**
```
$ mkdir -p rosworkspace/src
$ cd rosworkspace/src
$ git clone https://github.com/HesaiTechnology/HesaiLidar_General_ROS.git --recursive
mkdir -p rosworkspace/src
cd rosworkspace/src
git clone --branch ros2-galactic https://github.com/HesaiTechnology/HesaiLidar_General_ROS.git --recursive
```
**Build**
```
$ cd ..
$ source /opt/ros/dashing/setup.bash
$ source /opt/ros/galactic/setup.bash
$ colcon build --symlink-install
```

## Configuration

Use a defined IP address and port to connect to the Lidar.

```.bash
sudo ifconfig eno2 192.168.1.100 # (replace eno2 with the local Ethernet port name)
```
or simply use the default IP address and port defined by your system. But change the `server_ip` parameter in the `hesai_lidar_launch.py` file.


```
$ gedit install/hesai_lidar/share/hesai_lidar/launch/hesai_lidar_launch.py
```
Expand Down
25 changes: 13 additions & 12 deletions launch/hesai_lidar_launch.py
Original file line number Diff line number Diff line change
@@ -1,32 +1,33 @@
from launch import LaunchDescription
import launch_ros.actions
from os import path


def generate_launch_description():
return LaunchDescription([
launch_ros.actions.Node(
package ='hesai_lidar',
node_namespace ='hesai',
node_executable ='hesai_lidar_node',
namespace ='hesai',
executable ='hesai_lidar_node',
name ='hesai_node',
output ="screen",
parameters=[
{"pcap_file": "''"},
{"server_ip" : "192.168.1.201"},
{"pcap_file": ""},
{"server_ip" : "192.168.1.100"},
{"lidar_recv_port" : 2368},
{"gps_port" : 10110},
{"start_angle" : 0.0},
{"lidar_type" : "PandarXT-16"},
{"frame_id" : "PandarXT-16"},
{"lidar_type" : "PandarXT-32"},
{"frame_id" : "PandarXT-32"},
{"pcldata_type" : 0},
{"publish_type" : "both"},
{"timestamp_type" : "''"},
{"data_type" : "''"},
{"lidar_correction_file" : "./src/ROS/HesaiLidar_General_ROS/config/PandarXT-16.csv"},
{"multicast_ip" : "''"},
{"timestamp_type" : ""},
{"data_type" : ""},
{"lidar_correction_file" : path.dirname(path.abspath(__file__))+"/../config/PandarXT-32.csv"},
{"multicast_ip" : ""},
{"coordinate_correction_flag" : False},
{"fixed_frame" : "''"},
{"target_frame_frame" : "''"}
{"fixed_frame" : ""},
{"target_frame_frame" : ""}
]
)
])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,7 @@ bool PandarGeneral::GetCorrectionFileFlag(){
if (internal_) {
return internal_->GetCorrectionFileFlag();
}
return false;
}

void PandarGeneral::SetCorrectionFileFlag(bool flag){
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -688,6 +688,7 @@ int PandarGeneral_Internal::Start() {
} else {
pcap_reader_->start(boost::bind(&PandarGeneral_Internal::FillPacket, this, _1, _2, _3));
}
return 0;
}

void PandarGeneral_Internal::Stop() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,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
1 change: 1 addition & 0 deletions src/HesaiLidar_General_SDK/src/pandarGeneral_sdk.cc
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ int PandarGeneralSDK::Start() {
enable_get_calibration_thr_ = true;
get_calibration_thr_ = new boost::thread(
boost::bind(&PandarGeneralSDK::GetCalibrationFromDevice, this));
return 0;
}

void PandarGeneralSDK::Stop() {
Expand Down
8 changes: 5 additions & 3 deletions src/main_ros2.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,9 @@ class HesaiLidarClient: public rclcpp::Node
this->declare_parameter<bool>("coordinate_correction_flag", false);
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");
rclcpp::QoS qos(rclcpp::KeepLast(7));
auto sensor_qos = rclcpp::QoS(rclcpp::SensorDataQoS());
lidarPublisher = this->create_publisher<sensor_msgs::msg::PointCloud2>("pandar", sensor_qos);
packetPublisher = this->create_publisher<hesai_lidar::msg::PandarScan>("pandar_packets", qos);
this->timer_callback();
}
Expand All @@ -51,7 +52,8 @@ class HesaiLidarClient: public rclcpp::Node
void lidarCallback(boost::shared_ptr<PPointCloud> cld, double timestamp, hesai_lidar::msg::PandarScan::SharedPtr scan) // the timestamp from first point cloud of cld
{
if(m_sPublishType == "both" || m_sPublishType == "points"){
pcl_conversions::toPCL(rclcpp::Time(timestamp), cld->header.stamp);
rclcpp::Time now = this->now();
pcl_conversions::toPCL(now, cld->header.stamp);
sensor_msgs::msg::PointCloud2 output;
pcl::toROSMsg(*cld, output);
lidarPublisher->publish(output);
Expand Down