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 Mar 17, 2021
1 parent 2e1340c commit 1c2c969
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions pandar_pointcloud/src/pandar_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,6 @@ PandarCloud::PandarCloud(ros::NodeHandle node, ros::NodeHandle private_nh)
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()) {
ROS_ERROR("Unable to load calibration data");
Expand All @@ -45,6 +39,12 @@ PandarCloud::PandarCloud(ros::NodeHandle node, ros::NodeHandle private_nh)
ROS_ERROR("Invalid model name");
return;
}

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);
}

PandarCloud::~PandarCloud() {}
Expand Down

0 comments on commit 1c2c969

Please sign in to comment.