Skip to content

Commit

Permalink
Camera-lidar calibration tools initial release (#9)
Browse files Browse the repository at this point in the history
* Changes to fix the remappings.

Also deleted unused or redundant code/parameters

* deleted unused members in structures and unused code

* The lidartag was using pandar as the lidar_frame in a hardcoded fashion.
Since we plan to use several pandar instances with different names, we must parameterize this frame from the calibration tools

* Fixed several errors and implemented several improvements to increase the detection rate and precision of the detections.
 - Fixes clusters that could not be formed correctly in one pass
 - Adds an optional rectangle estimation rather tha 4x line estimation to get the corners, it is much more stable and increases both the accuracy and detection rate
 - Refines the initial center of the tag based on the corner fitting which seems to improve the pose estimation. In many cases the nlopt optimizator is not even needed

* - Calibration tools compliance
 - Fix edge groups provided by PCA using the partial rectangle models produced by the RANSAC iterations. Provides great results.
 - Some debug drawings to help understand the previous fix
 - Parameterized min decoding score

* Truned off the verbosity that is lidartag targetting its release

* Updated linkage

* Added empty file because git does not support empty folders

* Removed comments and unused files
  • Loading branch information
knzo25 authored May 25, 2022
1 parent 6ee1e1a commit cb1f913
Show file tree
Hide file tree
Showing 30 changed files with 1,782 additions and 817 deletions.
31 changes: 26 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,8 @@ ament_auto_add_executable(lidartag_main
src/tag16h5.cpp
src/lidartag_rviz.cpp
src/lidartag_cluster.cpp
src/lidartag_prune.cpp)
src/lidartag_prune.cpp
src/rectangle_estimator.cpp)

target_link_libraries(lidartag_main
${PCL_LIBRARIES}
Expand All @@ -81,10 +82,30 @@ target_link_libraries(lidartag_main
Boost::thread
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()
#if(BUILD_TESTING)
# find_package(ament_cmake_gtest REQUIRED)
#
# include_directories(
# include
# )
#
# # Unit tests
# set(TEST_SOURCES
# test/test_rectangle_estimation.cpp
# src/rectangle_estimator.cpp
# #test/test_pid.cpp
# )
#
# #set(TEST_VELOCITY_CONTROLLER test_velocity_controller)
# ament_add_gtest(sometest_name ${TEST_SOURCES})
# #target_link_libraries(${TEST_VELOCITY_CONTROLLER} velocity_controller_core)
#
# target_link_libraries(sometest_name
# ${PCL_LIBRARIES}
#)
#
#endif()


ament_auto_package(
INSTALL_TO_SHARE
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,10 @@
* WEBSITE: https://www.brucerobot.com/
*/

#ifndef APRILTAG_UTILS_H
#define APRILTAG_UTILS_H
#ifndef APRILTAG_UTILS_HPP
#define APRILTAG_UTILS_HPP

#include "lidartag.h"
#include <lidartag/lidartag.hpp>

namespace BipedAprilLab{

Expand Down
70 changes: 53 additions & 17 deletions include/lidartag.h → include/lidartag/lidartag.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@
* WEBSITE: https://www.brucerobot.com/
*/

#ifndef LIDARTAG_H
#define LIDARTAG_H
#ifndef LIDARTAG_HPP
#define LIDARTAG_HPP

#include <fstream>
#include <memory>
Expand All @@ -49,7 +49,6 @@
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>
//#include <jsk_msgs/msg/overlay_text.hpp>

// threading
#include <boost/thread.hpp>
Expand All @@ -75,11 +74,12 @@
#include <lidartag_msgs/msg/corners_array.hpp>
#include <lidartag_msgs/msg/lidar_tag_detection.hpp>
#include <lidartag_msgs/msg/lidar_tag_detection_array.hpp>
#include "thread_pool.h"
#include "types.h"
#include "utils.h"

#include "apriltag_utils.h"
#include <lidartag/rectangle_estimator.hpp>
#include <lidartag/thread_pool.hpp>
#include <lidartag/types.hpp>
#include <lidartag/utils.hpp>
#include <lidartag/apriltag_utils.hpp>

namespace BipedLab {
class LidarTag: public rclcpp::Node {
Expand All @@ -95,7 +95,6 @@ class LidarTag: public rclcpp::Node {
double ransac_threshold;
int fine_cluster_threshold; // TODO: REPLACE WITH TAG PARAMETERS
int filling_gap_max_index; // TODO: CHECK
int filling_max_points_threshold; // TODO: REMOVE
double points_threshold_factor; // TODO: CHECK
double distance_to_plane_threshold;
double max_outlier_ratio;
Expand All @@ -108,11 +107,22 @@ class LidarTag: public rclcpp::Node {
int cluster_min_index;
int cluster_max_points_size;
int cluster_min_points_size;
double depth_bound; // Edge detection parameters
double min_rkhs_score;
bool optional_fix_cluster;
bool use_rectangle_model;
bool rectangle_model_use_ransac;
int rectangle_model_max_iterations;
float rectangle_model_max_error;
bool rectangle_fix_point_groups;
bool refine_cluster_with_intersections;
bool debug_single_pointcloud;
double debug_point_x;
double debug_point_y;
double debug_point_z;
int debug_cluster_id;
int debug_ring_id;
int debug_scan_id;
} params_;

OnSetParametersCallbackHandle::SharedPtr set_param_res_;
Expand Down Expand Up @@ -166,6 +176,7 @@ class LidarTag: public rclcpp::Node {
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr edge3_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr edge4_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr boundary_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr initial_corners_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr cluster_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr payload_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr payload3d_pub_;
Expand Down Expand Up @@ -200,6 +211,7 @@ class LidarTag: public rclcpp::Node {
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr colored_cluster_buff_pub_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr ps_cluster_buff_pub_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr in_cluster_buff_pub_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr ordered_pointcloud_markers_pub_;

// Flag
int point_cloud_received_; // check if a scan of point cloud has received or
Expand All @@ -210,12 +222,8 @@ class LidarTag: public rclcpp::Node {
std::queue<sensor_msgs::msg::PointCloud2::SharedPtr> point_cloud1_queue_;

// LiDAR parameters
bool sensor_qos_;
rclcpp::Time current_scan_time_; // store current time of the lidar scan
std::string pointcloud_topic_; // subscribe channel
std::string pub_frame_; // publish under what frame?
std::string lidartag_detections_topic_;
std::string corners_array_topic_;
std::string lidar_frame_; // publish under what frame?
// Overall LiDAR system parameters
LiDARSystem_t lidar_system_;
int max_queue_size_;
Expand All @@ -226,9 +234,6 @@ class LidarTag: public rclcpp::Node {
int point_cloud_size_;
std_msgs::msg::Header point_cloud_header_;

// Edge detection parameters
double depth_threshold_;

// If on-board processing is limited, limit range of points
double distance_bound_;
double distance_threshold_;
Expand Down Expand Up @@ -284,6 +289,9 @@ class LidarTag: public rclcpp::Node {
std::string outputs_path_;
std::string library_path_;

// Corner estimation
std::shared_ptr<RectangleEstimator> rectangle_estimator_;

/* [Main loop]
* main loop of process
*/
Expand Down Expand Up @@ -486,6 +494,25 @@ class LidarTag: public rclcpp::Node {
*/
void organizeDataPoints(ClusterFamily_t & t_cluster);

/* <A cluster>
* A function to estimate the four corners of a tag using 4x line RANSAC
*/
bool estimateCornersUsingLinesRANSAC(ClusterFamily_t & t_cluster,
pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud1, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud2,
pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud3, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud4,
Eigen::Vector3f & corner1, Eigen::Vector3f & corner2,
Eigen::Vector3f & corner3, Eigen::Vector3f & corner4);

/* <A cluster>
* A function to estimate the four corners of a tag using 1x rectangle fiting with
* optional RANSAC
*/
bool estimateCornersUsingRectangleFitting(ClusterFamily_t & t_cluster,
pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud1, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud2,
pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud3, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud4,
Eigen::Vector3f & corner1, Eigen::Vector3f & corner2,
Eigen::Vector3f & corner3, Eigen::Vector3f & corner4);

/* [Edge points and principal axes]
* A function to transform the edge points to the tag frame
*/
Expand Down Expand Up @@ -710,7 +737,8 @@ class LidarTag: public rclcpp::Node {
pcl::PointCloud<PointXYZRI>::Ptr t_edge3,
pcl::PointCloud<PointXYZRI>::Ptr t_edge4,
pcl::PointCloud<PointXYZRI>::Ptr t_boundary_pts,
visualization_msgs::msg::MarkerArray & t_marker_array);
pcl::PointCloud<PointXYZRI>::Ptr t_initial_corners_pts,
visualization_msgs::msg::MarkerArray & t_marker_array);

void plotIdealFrame();

Expand Down Expand Up @@ -804,6 +832,14 @@ class LidarTag: public rclcpp::Node {
void displayClusterPointSize(const std::vector<ClusterFamily_t> & cluster_buff);
void displayClusterIndexNumber(const std::vector<ClusterFamily_t> & cluster_buff);

void addOrderedPointcloudMarkers(std::vector<std::vector<LidarPoints_t>> & ordered_buff);
visualization_msgs::msg::MarkerArray ordered_pointcloud_markers_;

void fixClusters(
const std::vector<std::vector<LidarPoints_t>> & edge_buff,
std::vector<ClusterFamily_t> & cluster_buff);


}; // GrizTag
} // namespace BipedLab
#endif
File renamed without changes.
90 changes: 90 additions & 0 deletions include/lidartag/rectangle_estimator.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
// Copyright 2021 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RECTANGLE_ESTIMATOR_HPP
#define RECTANGLE_ESTIMATOR_HPP

#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/PCLPointCloud2.h>

class RectangleEstimator {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

RectangleEstimator();

void setInputPoints(
pcl::PointCloud<pcl::PointXYZ>::Ptr & points1,
pcl::PointCloud<pcl::PointXYZ>::Ptr & points2,
pcl::PointCloud<pcl::PointXYZ>::Ptr & points3,
pcl::PointCloud<pcl::PointXYZ>::Ptr & points4);

bool estimate();
bool estimate_ransac();
bool estimate_imlp(
pcl::PointCloud<pcl::PointXYZ>::Ptr points1,
pcl::PointCloud<pcl::PointXYZ>::Ptr points2,
pcl::PointCloud<pcl::PointXYZ>::Ptr points3,
pcl::PointCloud<pcl::PointXYZ>::Ptr points4,
Eigen::Vector2d & n_out,
Eigen::Vector4d & c_out);

std::vector<Eigen::Vector2d> getCorners();
std::vector<Eigen::Vector2d> getCorners(Eigen::Vector2d & n, Eigen::Vector4d & c);

Eigen::Vector2d getNCoefficients() const;
Eigen::Vector4d getCCoefficients() const;

void setRANSAC(bool enable);
void setFilterByCoefficients(bool enable);
void setMaxIterations(int iterations);
void setInlierError(double error);
void setFixPointGroups(bool enabe);

void preparePointsMatrix();
double getModelErrorAndInliers(Eigen::Vector2d & n, Eigen::Vector4d & c, int & inliers,
std::vector<Eigen::Vector2d> & inliers1, std::vector<Eigen::Vector2d> & inliers2,
std::vector<Eigen::Vector2d> & inliers3, std::vector<Eigen::Vector2d> & inliers4,
Eigen::VectorXd & errors1, Eigen::VectorXd & errors2,
Eigen::VectorXd & errors3, Eigen::VectorXd & errors4,
bool add_inliers);

protected:

bool checkCoefficients() const;
void fixPointGroups(Eigen::VectorXd & errors1, Eigen::VectorXd & errors2,
Eigen::VectorXd & errors3, Eigen::VectorXd & errors4);

bool use_ransac_;
bool filter_by_coefficients_;
int max_ransac_iterations_;
double max_error_;
bool fix_point_groups_;

Eigen::MatrixXd augmented_matrix_;
Eigen::MatrixXd points_matrix_;
Eigen::Vector4d estimated_c;
Eigen::Vector2d estimated_n;

pcl::PointCloud<pcl::PointXYZ>::Ptr points1_;
pcl::PointCloud<pcl::PointXYZ>::Ptr points2_;
pcl::PointCloud<pcl::PointXYZ>::Ptr points3_;
pcl::PointCloud<pcl::PointXYZ>::Ptr points4_;

pcl::PointCloud<pcl::PointXYZ> points;

};

#endif // RECTANGLE_ESTIMATOR_HPP
2 changes: 1 addition & 1 deletion include/tag16h5.h → include/lidartag/tag16h5.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#ifndef _TAG16H5
#define _TAG16H5

#include "lidartag.h"
#include <lidartag/lidartag.hpp>

BipedLab::GrizTagFamily_t *tag16h5_create();
void tag16h5_destroy(BipedLab::GrizTagFamily_t *tf);
Expand Down
2 changes: 1 addition & 1 deletion include/tag49h14.h → include/lidartag/tag49h14.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#ifndef _TAG49H14
#define _TAG49H14

#include "lidartag.h"
#include <lidartag/lidartag.hpp>

BipedLab::GrizTagFamily_t *tag49h14_create();
void tag49h14_destroy(BipedLab::GrizTagFamily_t *tf);
Expand Down
File renamed without changes.
31 changes: 25 additions & 6 deletions include/types.h → include/lidartag/types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,9 @@
* AUTHOR: Bruce JK Huang ([email protected])
* WEBSITE: https://www.brucerobot.com/
*/

#pragma once

#include "nanoflann.hpp"
#include <Eigen/Core>
#include <Eigen/Sparse>
Expand Down Expand Up @@ -194,6 +197,26 @@ typedef struct {
point right;
} corners;

enum class LidartagErrorCode //C++11 scoped enum
{
NoError = 0,
ClusterMinPointsCriteria = 1,
ClusterMinPointsCriteria2 = 2,
PlanarCheckCriteria = 3,
PlanarOutliersCriteria = 4,
DecodingPointsCriteria = 5,
DecodingRingsCriteria = 6,
CornerEstimationMinPointsCriteria = 7,
Line1EstimationCriteria = 8,
Line2EstimationCriteria = 9,
Line3EstimationCriteria = 10,
Line4EstimationCriteria = 11,
RectangleEstimationCirteria = 12,
TagSizeEstimationCriteria = 13,
OptimizationErrorCriteria = 14,
DecodingErrorCriteria = 15
};

typedef struct ClusterFamily {
// EIGEN_MAKE_ALIGNED_OPERATOR_NEW
int cluster_id;
Expand All @@ -215,6 +238,7 @@ typedef struct ClusterFamily {
pcl::PointCloud<LidarPoints_t> data; // data doesn't have edge points
pcl::PointCloud<LidarPoints_t> edge_points;
pcl::PointCloud<LidarPoints_t> transformed_edge_points;
pcl::PointCloud<PointXYZRI> initial_corners;

// If the first point of the ring is the cluster.
// If so, the the indices fo the two sides will be far away
Expand Down Expand Up @@ -279,15 +303,10 @@ typedef struct ClusterFamily {
*/
std::vector<Eigen::VectorXf>
line_coeff; // Upper, left, bottom, right line (count-clockwise)
int detail_valid;
LidartagErrorCode detail_valid;
int pose_estimation_status;
int expected_points;

corners tag_corners; // KL: adding here for now
corners tag_boundary_corners;
std::vector<point> corner_offset_array;
std::vector<point> boundary_corner_offset_array;

} ClusterFamily_t;

typedef struct GrizTagFamily {
Expand Down
Loading

0 comments on commit cb1f913

Please sign in to comment.