Skip to content

Commit

Permalink
fix calibration process
Browse files Browse the repository at this point in the history
Signed-off-by: Shinnosuke Hirakawa <[email protected]>
  • Loading branch information
0x126 committed Mar 16, 2021
1 parent c0febf9 commit eb704ff
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class PandarCloud
~PandarCloud();

private:
int setupCalibration();
bool setupCalibration();
void onProcessScan(const pandar_msgs::PandarScan::ConstPtr & msg);
pcl::PointCloud<PointXYZIR>::Ptr convertPointcloud(
const pcl::PointCloud<PointXYZIRADT>::ConstPtr & input_pointcloud);
Expand Down
14 changes: 7 additions & 7 deletions pandar_pointcloud/src/pandar_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ namespace
{
const uint16_t TCP_COMMAND_PORT = 9347;
const size_t TCP_RETRY_NUM = 5;
const size_t TCP_RETRY_WAIT = 10;
const double TCP_RETRY_WAIT_SEC = 0.1;
} // namespace

namespace pandar_pointcloud
Expand All @@ -30,7 +30,7 @@ PandarCloud::PandarCloud(ros::NodeHandle node, ros::NodeHandle private_nh)
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) {
if (!setupCalibration()) {
ROS_ERROR("Unable to load calibration data");
return;
}
Expand All @@ -49,24 +49,24 @@ PandarCloud::PandarCloud(ros::NodeHandle node, ros::NodeHandle private_nh)

PandarCloud::~PandarCloud() {}

int PandarCloud::setupCalibration()
bool PandarCloud::setupCalibration()
{
if (!calibration_path_.empty() && calibration_.loadFile(calibration_path_) == 0) {
return 0;
return true;
} else if (tcp_client_) {
std::string content("");
for (size_t i = 0; i < TCP_RETRY_NUM; ++i) {
auto ret = tcp_client_->getLidarCalibration(content);
if (ret == TcpCommandClient::PTC_ErrCode::PTC_ERROR_NO_ERROR) {
break;
}
std::this_thread::sleep_for(std::chrono::milliseconds(TCP_RETRY_WAIT));
ros::Duration(TCP_RETRY_WAIT_SEC).sleep();
}
if (!content.empty()) {
calibration_.loadContent(content);
return 0;
return true;
}else{
return -1;
return false;
}
}
}
Expand Down

0 comments on commit eb704ff

Please sign in to comment.