Skip to content

Commit

Permalink
fix bug
Browse files Browse the repository at this point in the history
Signed-off-by: Shinnosuke Hirakawa <[email protected]>
  • Loading branch information
0x126 committed Feb 25, 2021
1 parent 1e74417 commit 56a50d9
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 1 deletion.
2 changes: 1 addition & 1 deletion pandar_pointcloud/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ catkin_package(
CATKIN_DEPENDS
pandar_msgs
LIBRARIES
pandar_pointcloud
pandar_cloud
)

include_directories(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ class PandarCloud
const pcl::PointCloud<PointXYZIRADT>::ConstPtr & input_pointcloud);

std::string model_;
std::string device_ip_;
std::string calibration_path_;
double scan_phase_;

Expand Down
2 changes: 2 additions & 0 deletions pandar_pointcloud/src/pandar_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,13 +21,15 @@ PandarCloud::PandarCloud(ros::NodeHandle node, ros::NodeHandle private_nh)
private_nh.getParam("scan_phase", scan_phase_);
private_nh.getParam("calibration", calibration_path_);
private_nh.getParam("model", model_);
private_nh.getParam("device_ip", device_ip_);

pandar_packet_sub_ = node.subscribe(
"pandar_packets", 10, &PandarCloud::onProcessScan, this,
ros::TransportHints().tcpNoDelay(true));
pandar_points_pub_ = node.advertise<sensor_msgs::PointCloud2>("pandar_points", 10);
pandar_points_ex_pub_ = node.advertise<sensor_msgs::PointCloud2>("pandar_points_ex", 10);

tcp_client_ = std::make_shared<TcpCommandClient>(device_ip_, TCP_COMMAND_PORT);
if (setupCalibration() != 0) {
ROS_ERROR("Unable to load calibration data");
return;
Expand Down

0 comments on commit 56a50d9

Please sign in to comment.