add guangpo yolo lidar project

This commit is contained in:
gxt_kt 2024-08-12 16:05:34 +00:00
parent 611e9b1637
commit d5cc3aae62
69 changed files with 10436 additions and 0 deletions

View File

@ -1,3 +1,4 @@
return()
cmake_minimum_required(VERSION 3.0.2)
project(guangpo_lidar)

View File

@ -1,3 +1,4 @@
return()
cmake_minimum_required(VERSION 3.0.2)
project(guangpo_yolo)

View File

@ -0,0 +1,254 @@
cmake_minimum_required(VERSION 3.0.2)
project(guangpo_yolo_lidar)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_BUILD_TYPE Release) # Debug Release RelWithDebInfo
add_compile_options(-O3 -fopenmp)
find_package(OpenMP REQUIRED)
if(OPENMP_FOUND)
message("OPENMP FOUND")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
endif()
add_subdirectory(dbscan)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
std_msgs
pcl_ros
image_transport
cv_bridge
)
find_package(yaml-cpp REQUIRED)
find_package(PCL REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
list(REMOVE_ITEM PCL_LIBRARIES "vtkproj4")
#
set(LIB_PATH "./lib")
#
file(GLOB LIB_FILES "${LIB_PATH}/*.a" "${LIB_PATH}/*.so")
# gxt: add eigen
include_directories(/usr/include/eigen3)
find_package(OpenCV REQUIRED)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# sensor_msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES guangpo_yolo
# CATKIN_DEPENDS roscpp sensor_msgs
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
include
include/rga/include
${catkin_INCLUDE_DIRS}
yaml_config
dbscan
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/guangpo_yolo.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(${PROJECT_NAME}_node src/main.cpp src/postprocess.cc src/preprocess.cc yaml_config/yaml_config.cpp)
# add_executable(${PROJECT_NAME}_test_node src/main_test.cc src/postprocess.cc src/preprocess.cc yaml_config/yaml_config.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
target_link_libraries(${PROJECT_NAME}_node
${catkin_LIBRARIES}
${OpenCV_LIBS}
${LIB_FILES}
yaml-cpp
${PCL_LIBRARIES}
dbscan
)
# target_link_libraries(${PROJECT_NAME}_test_node
# ${catkin_LIBRARIES}
# ${OpenCV_LIBS}
# ${LIB_FILES}
# yaml-cpp
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_guangpo_yolo.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

View File

@ -0,0 +1,88 @@
# #############################################################################
# LIBRARY NAME
# #############################################################################
cmake_minimum_required(VERSION 3.12.4)
project(dbscan
VERSION 1.0.3
DESCRIPTION "dbscan library"
LANGUAGES CXX
)
set(Eigen3_DIR /usr/share/cmake/Modules)
find_package(Eigen3 REQUIRED)
find_package(PCL 1.8 REQUIRED QUIET COMPONENTS octree kdtree)
if(PCL_FOUND)
message(STATUS "PCL status:")
message(STATUS " version: ${PCL_VERSION}")
message(STATUS " directory: ${PCL_DIR}")
else()
message(FATAL_ERROR " ERROR: PCL minimum required version 1.8. Not found")
endif()
# #############################################################################
# COMPILE LIBRARY
# #############################################################################
add_library(${PROJECT_NAME} SHARED
src/cluster.cpp
src/dbScan.cpp
src/OctreeGenerator.cpp
)
# #############################################################################
# LIBRARY PROPERTIES
# #############################################################################
set_target_properties(${PROJECT_NAME} PROPERTIES
VERSION ${PROJECT_VERSION}
SOVERSION 1
PUBLIC_HEADER ${CMAKE_CURRENT_LIST_DIR}/include/dbscan/dbScan.h
)
# #############################################################################
# LIBRARY HEADERS
# #############################################################################
target_include_directories(${PROJECT_NAME} PUBLIC
${CMAKE_CURRENT_LIST_DIR}/include
${PCL_INCLUDE_DIRS}
)
# #############################################################################
# LIBRARY DEPENDENCIES
# #############################################################################
# target_link_libraries(${PROJECT_NAME} PUBLIC ${PCL_LIBRARIES})
target_link_libraries(${PROJECT_NAME} PUBLIC ${PCL_KDTREE_LIBRARY} ${PCL_OCTREE_LIBRARY} Eigen3::Eigen)
# #############################################################################
# COMPILATION FLAGS: MMX, SSE(1, 2, 3, 3S, 4.1, 4.2), CLMUL, RdRand, VT-x, x86-64
# #############################################################################
# target_compile_options(${PROJECT_NAME} PRIVATE -Wno-cpp
# -mmmx
# -msse
# -msse2
# -msse3
# -mssse3
# -msse4.2
# -msse4.1
# -mno-sse4a
# -mno-avx
# -mno-avx2
# -mno-fma
# -mno-fma4
# -mno-f16c
# -mno-xop
# -mno-bmi
# -mno-bmi2
# -mrdrnd
# -mno-3dnow
# -mlzcnt
# -mfsgsbase
# -mpclmul
# )
# #############################################################################
# INSTALL DIRECTORY
# #############################################################################
install(TARGETS ${PROJECT_NAME}
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
PUBLIC_HEADER DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}
)

View File

@ -0,0 +1,83 @@
/**
*@file HTRBasicDataStructures.h
*Data structures that do not depend on external classes.
* https://pointclouds.org/documentation/tutorials/adding_custom_ptype.html#adding-your-own-custom-pointt-type
*/
#ifndef HTR_BASIC_DATA_STRUCTURES_H
#define HTR_BASIC_DATA_STRUCTURES_H
#define PCL_NO_PRECOMPILE
#include <pcl/point_types.h>
/// Modified pcl point to include an id.
namespace pcl {
class mod_pointXYZ : public PointXYZRGB {
public:
mod_pointXYZ() {
x = y = z = 0;
id = 0;
}
mod_pointXYZ(float x, float y, float z) : PointXYZRGB(x, y, z) { id = 0; }
/*
mod_pointXYZ(unsigned int r, unsigned int g, unsigned int b) : PointXYZRGB(r,g,b){
id = 0;
}
*/
int id;
};
} // namespace pcl
namespace htr {
struct Index2D {
int x;
int y;
// Index2D():x(0),y(0){}
};
struct Point3D {
float x;
float y;
float z;
unsigned int r;
unsigned int g;
unsigned int b;
void initRandom() {
x = (rand() % 40);
y = (rand() % 40);
z = (rand() % 40);
}
};
struct FlaggedPoint3D {
Point3D point;
int flag;
};
struct DepthPixel {
int x;
int y;
float z;
};
struct LabeledPoint {
Point3D point;
int label;
};
struct CubeBoundary {
Point3D start;
Point3D end;
};
struct LinearBoundary {
float start;
float end;
};
} // namespace htr
#endif

View File

@ -0,0 +1,111 @@
/**
*@class OctreeGenerator
*Creates an octree from the point cloud data provided.
*
*/
#ifndef OCTREE_GENERATOR_H
#define OCTREE_GENERATOR_H
// #include <pcl/octree/octree_impl.h>
#include <pcl/common/centroid.h>
#include <pcl/octree/octree.h>
#include <pcl/octree/octree_search.h>
#include <pcl/point_cloud.h>
#include <Eigen/Core>
#include <vector>
#include "HTRBasicDataStructures.h"
namespace htr {
class OctreeGenerator {
public:
typedef pcl::PointCloud<pcl::mod_pointXYZ> CloudXYZ;
typedef pcl::octree::OctreePointCloudSearch<pcl::mod_pointXYZ> OctreeXYZSearch;
typedef pcl::octree::OctreePointCloudSearch<pcl::mod_pointXYZ>::LeafNode LeafNode;
typedef pcl::octree::OctreePointCloudSearch<pcl::mod_pointXYZ>::LeafNodeIterator LeafNodeIterator;
typedef htr::Point3D Point3D;
struct Voxel {
Point3D position;
float size;
};
OctreeGenerator();
~OctreeGenerator();
/// This is needed to remove the warning about alignment: object allocated on the heap may not be
/// aligned 16
/// Solution specific to microsoft.
#ifdef _MSC_VER
void *operator new(size_t size) {
void *p = _aligned_malloc(size, 16);
if (!p) throw std::bad_alloc();
return p;
}
void operator delete(void *p) {
OctreeGenerator *ptr = static_cast<OctreeGenerator *>(p);
_aligned_free(p);
}
#endif
inline CloudXYZ::Ptr getCloud() { return cloud; }
inline pcl::mod_pointXYZ getCloudCentroid() { return cloudCentroid; }
inline std::vector<Voxel> &getVoxels() { return octreeVoxels; }
inline std::vector<Point3D> &getCentroids() { return octreeCentroids; }
inline OctreeXYZSearch::Ptr getOctree() { return octree_p; }
void initRandomCloud(const float width, const float height, const float depth, const int numOfPoints);
template <typename T>
void initCloudFromVector(const std::vector<T> &points, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &input_cloud);
void initOctree(const int resolution);
void extractPointsAtLevel(const int depth);
void stepExtractionLevel(const int step);
private:
unsigned int currentExtractionLevel;
pcl::PointCloud<pcl::mod_pointXYZ>::Ptr cloud;
OctreeXYZSearch::Ptr octree_p;
pcl::mod_pointXYZ cloudCentroid;
std::vector<Voxel> octreeVoxels;
std::vector<Point3D> octreeCentroids;
void calculateCloudCentroid();
};
/// Initializes pcl's cloud data structure from a vector of any type containing x, y, and z member variables.
///@param[in] points The input data vector.
template <typename T>
void OctreeGenerator::initCloudFromVector(const std::vector<T> &points, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &input_cloud) {
// Note: Width and Height are only used to store the cloud as an image.
// Source width and height can be used instead of a linear representation.
cloud->width = input_cloud->points.size();
cloud->height = 1;
cloud->points.resize(cloud->width * cloud->height);
for (size_t i = 0; i < cloud->points.size(); ++i) {
cloud->points[i].x = input_cloud->points[i].x;
cloud->points[i].y = input_cloud->points[i].y;
cloud->points[i].z = input_cloud->points[i].z;
uint8_t r_, g_, b_;
r_ = uint8_t(input_cloud->points[i].r);
g_ = uint8_t(input_cloud->points[i].g);
b_ = uint8_t(input_cloud->points[i].b);
uint32_t rgb_ = ((uint32_t)r_ << 16 | (uint32_t)g_ << 8 | (uint32_t)b_);
cloud->points[i].rgb = *reinterpret_cast<float *>(&rgb_);
}
calculateCloudCentroid();
}
} // namespace htr
#endif

View File

@ -0,0 +1,30 @@
/**
*@file cluster.h
*Cluster for 3d points.
*/
#ifndef CLUSTER
#define CLUSTER
#include "HTRBasicDataStructures.h"
#include "OctreeGenerator.h"
namespace dbScanSpace {
class cluster {
public:
std::vector<pcl::mod_pointXYZ> clusterPoints;
std::vector<htr::Point3D> clusterPoints3D;
pcl::mod_pointXYZ centroid;
htr::Point3D centroid3D;
bool visited;
cluster();
void calculateCentroid();
void toPoint3D();
private:
};
} // namespace dbScanSpace
#endif // CLUSTER

View File

@ -0,0 +1,88 @@
#ifndef DBSCAN
#define DBSCAN
#include "HTRBasicDataStructures.h"
#include "OctreeGenerator.h"
#include "cluster.h"
namespace dbScanSpace {
class dbscan {
public:
dbscan(const char *filename, const int octreeResolution_, const float eps_, const int minPtsAux_, const int minPts_);
dbscan();
~dbscan();
template <typename T>
void init(const std::vector<T> &points, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &input_cloud, const int octreeResolution_, const float eps_, const int minPtsAux_,
const int minPts_);
inline std::vector<cluster> &getClusters() { return clusters; }
inline htr::OctreeGenerator::CloudXYZ::Ptr getCloudPoints() { return octreeGenIn->getCloud(); }
inline pcl::mod_pointXYZ getCentroid() { return centroid; }
template <typename T>
void generateClusters(std::vector<std::vector<T>> *clusters);
void generateClusters_one_step();
void generateClusters();
void generateClusters_fast();
private:
float eps;
int minPtsAux, minPts, octreeResolution;
std::vector<cluster> clustersAux, clusters;
htr::OctreeGenerator *octreeGenIn, *octreeGen;
std::vector<pcl::mod_pointXYZ> clustersCentroids;
pcl::mod_pointXYZ centroid;
void calculateCentroid(std::vector<pcl::mod_pointXYZ> group);
void octreeRegionQuery(htr::OctreeGenerator *octreeGen, pcl::mod_pointXYZ &searchPoint, double eps, std::vector<int> *retKeys);
void DBSCAN_Octree_merge(htr::OctreeGenerator *octreeGen, float eps, int minPts);
void DBSCAN_Octree(htr::OctreeGenerator *octreeGen, float eps, int minPts);
void DBSCAN_Octree_fast(htr::OctreeGenerator *octreeGen, float eps, int minPts);
void DBSCAN_Octree_fast_one_step(htr::OctreeGenerator *octreeGen, float eps, int minPts);
void DBSCAN_Octree_fast2(htr::OctreeGenerator *octreeGen, int minPts);
};
/// Initializes the point cloud from a vector, and the octree.
///@param[in] points Points from which the cloud will be initialized.
///@param[in] octreeResolution_ Resolution with which the octree is initialized.
///@param[in] eps_ The search radius for the octree.
///@param[in] minPtsAux_ Minimum points for the initial clusters.
///@param[in] minPts_ Minimum points for the final clusters.
template <typename T>
void dbscan::init(const std::vector<T> &points, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &input_cloud, const int octreeResolution_, const float eps_, const int minPtsAux_,
const int minPts_) {
eps = eps_;
minPts = minPts_;
minPtsAux = minPtsAux_;
octreeResolution = octreeResolution_;
octreeGenIn->initCloudFromVector<T>(points, input_cloud);
octreeGenIn->initOctree(octreeResolution);
// centroid = octreeGenIn->getCloudCentroid();
}
template <typename T>
void dbscan::generateClusters(std::vector<std::vector<T>> *clustersOut) {
// A first set of clusters is generated. This first set has a large number of small clusters.
DBSCAN_Octree(octreeGenIn, eps, minPtsAux);
// The clusters centroids are calculated and used to generate a second octree.
for (dbScanSpace::cluster cluster : clustersAux) clustersCentroids.push_back(cluster.centroid);
// octreeGen->initCloudFromVector<pcl::mod_pointXYZ>(clustersCentroids);
octreeGen->initOctree(octreeResolution);
// Using the second octree and the centroids of the clusters, a new set of clusters is generated.
// These are the final clusters.
DBSCAN_Octree_merge(octreeGen, 2 * eps, minPts);
// for(int i = 0; i<clusters.size(); i++)
// clusters[i].toPoint3D();
}
} // namespace dbScanSpace
#endif

View File

@ -0,0 +1,109 @@
#include <dbscan/OctreeGenerator.h>
namespace htr {
/// The default constructor.
OctreeGenerator::OctreeGenerator()
: cloud(new CloudXYZ),
octree_p(new OctreeXYZSearch(20)),
// octree(56),
currentExtractionLevel(0) {}
/// The default destructor.
OctreeGenerator::~OctreeGenerator() {}
/// Initializes pcl's cloud data structure with random values centered at 0,0,0.
///@param[in] width The width of the point cloud.
///@param[in] height The height of the point cloud.
///@param[in] depth The depth of the point cloud.
///@param[in] numOfPoints The num of points in the point cloud.
void OctreeGenerator::initRandomCloud(const float width, const float height, const float depth, const int numOfPoints) {
srand((unsigned int)time(NULL));
// Generate pointcloud data
cloud->width = numOfPoints;
cloud->height = 1;
cloud->points.resize(cloud->width * cloud->height);
for (size_t i = 0; i < cloud->points.size(); ++i) {
cloud->points[i].x = (width * rand() / ((float)RAND_MAX + 1.0f)) - width / 2;
cloud->points[i].y = (height * rand() / ((float)RAND_MAX + 1.0f)) - height / 2;
cloud->points[i].z = (depth * rand() / ((float)RAND_MAX + 1.0f)) - depth / 2;
}
}
/// Calculates the entire cloud centroid
void OctreeGenerator::calculateCloudCentroid() {
Eigen::Matrix<float, 4, 1> centroid_original;
pcl::compute3DCentroid(*cloud, centroid_original);
cloudCentroid.x = centroid_original[0];
cloudCentroid.y = centroid_original[1];
cloudCentroid.z = centroid_original[2];
}
/// Initializes the octree from the cloud data provided at the specified resolution.
///@param[in] resolution The voxel edge size at the minimum subdivision level.
void OctreeGenerator::initOctree(const int resolution) {
//************************************
// octree_p.reset(new OctreeXYZSearch(resolution));
octree_p->deleteTree();
octree_p->setResolution(resolution);
// octree_p->setInputCloud(cloud);
octree_p->setInputCloud(cloud);
octree_p->addPointsFromInputCloud();
currentExtractionLevel = octree_p->getTreeDepth();
extractPointsAtLevel(currentExtractionLevel);
//************************************
// octree.setInputCloud (cloud);
// octree.addPointsFromInputCloud ();
// octree.setResolution(resolution);
// currentExtractionLevel = octree.getTreeDepth();
// extractPointsAtLevel(currentExtractionLevel);
}
/// Calculates the position of each voxel that exists at a specified tree depth.
///@param[in] depth The selected tree depth in the octree.
void OctreeGenerator::extractPointsAtLevel(const int depth) {
if (depth >= 0 && depth <= octree_p->getTreeDepth()) {
currentExtractionLevel = depth;
OctreeXYZSearch::Iterator tree_it;
OctreeXYZSearch::Iterator tree_it_end = octree_p->end();
pcl::PointXYZRGB pt;
// cout << "===== Extracting data at depth " << depth << "... " << endl;
// double start = pcl::getTime ();
octreeVoxels.clear();
octreeCentroids.clear();
// Check if end iterator can be substituted for the corresponding level so
// further level checking is avoided
for (tree_it = octree_p->begin(depth); tree_it != tree_it_end; ++tree_it) {
// Level check, discards all nodes that do not belong to desired level
if (tree_it.getCurrentOctreeDepth() == depth) {
Eigen::Vector3f voxel_min, voxel_max;
octree_p->getVoxelBounds(tree_it, voxel_min, voxel_max);
// Get voxel center point
Point3D p = {(voxel_min.x() + voxel_max.x()) / 2.0f, (voxel_min.y() + voxel_max.y()) / 2.0f, (voxel_min.z() + voxel_max.z()) / 2.0f};
Voxel v = {p, voxel_max.x() - voxel_min.x()};
// TODO: remove redundant info
octreeVoxels.push_back(v);
octreeCentroids.push_back(p);
}
}
// cout<<"Extracted Points: "<<displayPoints.size()<<endl;
// double end = pcl::getTime ();
// printf("%zu pts, %.4gs. %.4gs./pt. =====\n", displayCloud->points.size (), end - start,
//(end - start) / static_cast<double> (displayCloud->points.size ()));
}
}
///@deprecated
void OctreeGenerator::stepExtractionLevel(const int step) { extractPointsAtLevel(currentExtractionLevel + step); }
} // namespace htr

View File

@ -0,0 +1,31 @@
#include <dbscan/cluster.h>
namespace dbScanSpace {
cluster::cluster() { visited = false; }
void cluster::calculateCentroid() {
if (clusterPoints.size() > 0) {
for (auto &point : clusterPoints) {
centroid.x += point.x;
centroid.y += point.y;
centroid.z += point.z;
}
centroid3D.x = centroid.x /= clusterPoints.size();
centroid3D.y = centroid.y /= clusterPoints.size();
centroid3D.z = centroid.z /= clusterPoints.size();
}
}
/// Converts the PCL points to htr points.
void cluster::toPoint3D() {
if (clusterPoints.size() > 0) {
for (pcl::mod_pointXYZ point : clusterPoints) {
htr::Point3D pointAux;
pointAux.x = point.x;
pointAux.y = point.y;
pointAux.z = point.z;
clusterPoints3D.push_back(pointAux);
}
}
}
} // namespace dbScanSpace

View File

@ -0,0 +1,681 @@
#include <dbscan/dbScan.h>
namespace dbScanSpace {
dbscan::dbscan() {
octreeGenIn = new htr::OctreeGenerator();
octreeGen = new htr::OctreeGenerator();
}
dbscan::~dbscan() {
delete octreeGenIn;
delete octreeGen;
}
/// Initializes the point cloud from a file, and the octree.
///@param[in] filename Location of the file that has the data.
///@param[in] octreeResolution_ Resolution with which the octree is initialized.
///@param[in] eps_ The search radius for the octree.
///@param[in] minPtsAux_ Minimum points for the initial clusters.
///@param[in] minPts_ Minimum points for the final clusters.
void dbscan::generateClusters_one_step() {
clusters.clear();
clustersAux.clear();
clustersCentroids.clear();
// A first set of clusters is generated. This first set has a large number of small clusters.
DBSCAN_Octree_fast_one_step(octreeGenIn, eps, minPts);
//// The clusters centroids are calculated and used to generate a second octree.
// for (dbScanSpace::cluster cluster : clustersAux)
// clustersCentroids.push_back(cluster.centroid);
// octreeGen->initCloudFromVector<pcl::mod_pointXYZ>(clustersCentroids);
// octreeGen->initOctree(octreeResolution);
//// Using the second octree and the centroids of the clusters, a new set of clusters is
/// generated.
//// These are the final clusters.
// DBSCAN_Octree_merge(octreeGen, 2 * eps, minPts);
for (int i = 0; i < clusters.size(); i++) clusters[i].toPoint3D();
}
void CloudToVector(const std::vector<pcl::mod_pointXYZ> &inPointVector, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &outPointCloud) {
for (const pcl::mod_pointXYZ &point : inPointVector) {
outPointCloud->points.push_back(point);
}
}
/// Generates the clusters from the loaded data.
void dbscan::generateClusters() {
clusters.clear();
clustersAux.clear();
clustersCentroids.clear();
// A first set of clusters is generated. This first set has a large number of small clusters.
DBSCAN_Octree(octreeGenIn, eps, minPtsAux);
// The clusters centroids are calculated and used to generate a second octree.
for (dbScanSpace::cluster cluster : clustersAux) clustersCentroids.push_back(cluster.centroid);
// octreeGen->initCloudFromVector<pcl::mod_pointXYZ>(clustersCentroids);
octreeGen->initOctree(octreeResolution);
// Using the second octree and the centroids of the clusters, a new set of clusters is generated.
// These are the final clusters.
DBSCAN_Octree_merge(octreeGen, 2 * eps, minPts);
for (int i = 0; i < clusters.size(); i++) clusters[i].toPoint3D();
}
/// Generates the clusters from the loaded data.
void dbscan::generateClusters_fast() {
clusters.clear();
clustersAux.clear();
clustersCentroids.clear();
// A first set of clusters is generated. This first set has a large number of small clusters.
// DBSCAN_Octree_fast2(octreeGenIn, minPtsAux);
DBSCAN_Octree_fast(octreeGenIn, eps, minPtsAux);
// printf("\n Aux clusters size:%d\n\n", clustersAux.size());
// The clusters centroids are calculated and used to generate a second octree.
for (dbScanSpace::cluster cluster : clustersAux) clustersCentroids.push_back(cluster.centroid);
pcl::PointCloud<pcl::PointXYZRGB>::Ptr new_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
CloudToVector(clustersCentroids, new_cloud);
octreeGen->initCloudFromVector<pcl::mod_pointXYZ>(clustersCentroids, new_cloud);
octreeGen->initOctree(octreeResolution);
// Using the second octree and the centroids of the clusters, a new set of clusters is generated.
// These are the final clusters.
// DBSCAN_Octree_merge(octreeGen, 2*eps, minPts);
DBSCAN_Octree_merge(octreeGen, 2 * eps, minPts);
// printf("\n Clusters size:%d\n\n", clusters.size());
for (int i = 0; i < clusters.size(); i++) clusters[i].toPoint3D();
}
/// Calculates the centroid form a vector of points.
///@param[in] group Vector that contains the point that will be processed.
void dbscan::calculateCentroid(std::vector<pcl::mod_pointXYZ> group) {
for (pcl::mod_pointXYZ point : group) {
centroid.x += point.x;
centroid.y += point.y;
centroid.z += point.z;
}
centroid.x /= group.size();
centroid.y /= group.size();
centroid.z /= group.size();
}
/// Does a radius search for the K nearest neighbors of a point.
///@param[in] octreeGen The octree to be searched.
///@param[in] searchPoint The point around which the search will be conducted.
///@param[in] eps_ The search radius for the octree.
///@param[in] retKeys_ Vector that stores the indices of the nearest points.
void dbscan::octreeRegionQuery(htr::OctreeGenerator *octreeGen, pcl::mod_pointXYZ &searchPoint, double eps, std::vector<int> *retKeys) {
retKeys->clear();
std::vector<int> pointIdxRadiusSearch;
std::vector<float> pointRadiusSquaredDistance;
octreeGen->getOctree()->radiusSearch(searchPoint, eps, *retKeys, pointRadiusSquaredDistance);
}
/// Merges a set of clusters.
///@param[in] octreeGen The octree to be searched.
///@param[in] eps_ The search radius for the octree.
///@param[in] clustersIn The clusters that will be merged.
///@param[in] clustersOut Vector that stores all merged clusters.
void dbscan::DBSCAN_Octree_merge(htr::OctreeGenerator *octreeGen, float eps, int minPts) {
clusters.clear();
cluster pointQueue;
std::vector<pcl::mod_pointXYZ> clusterPoints;
// The amount of aux clusters
int noKeys = clustersAux.size();
std::vector<bool> visited(noKeys, false);
std::vector<int> noise;
std::vector<int> neighborPts(noKeys, -1);
for (int i = 0; i < noKeys; i++) {
if (!visited[i]) {
clusterPoints.push_back(clustersAux.at(i).centroid);
pointQueue.clusterPoints.insert(pointQueue.clusterPoints.end(), clustersAux.at(i).clusterPoints.begin(), clustersAux.at(i).clusterPoints.end());
visited[i] = true;
for (int j = 0; j < clusterPoints.size(); j++) {
octreeRegionQuery(octreeGen, clusterPoints.at(j), eps, &neighborPts);
for (int k = 0; k < neighborPts.size(); k++) {
if (!visited[neighborPts[k]]) {
visited[neighborPts[k]] = true;
clusterPoints.push_back(clustersAux.at(neighborPts[k]).centroid);
pointQueue.clusterPoints.insert(pointQueue.clusterPoints.end(), clustersAux.at(neighborPts[k]).clusterPoints.begin(),
clustersAux.at(neighborPts[k]).clusterPoints.end());
}
}
}
if (pointQueue.clusterPoints.size() >= minPts) {
pointQueue.calculateCentroid();
clusters.push_back(pointQueue);
pointQueue.clusterPoints.clear();
}
}
}
// clustersAux.clear();
}
/// Generates a set of clusters.
///@param[in] octreeGen The octree to be searched.
///@param[in] eps_ The search radius for the octree.
///@param[in] clusters Vector that stores all the generated clusters.
void dbscan::DBSCAN_Octree(htr::OctreeGenerator *octreeGen, float eps, int minPts) {
clustersAux.clear();
cluster pointQueue;
pcl::mod_pointXYZ auxCentroid;
int noKeys = octreeGen->getCloud()->points.size();
std::vector<bool> visited(noKeys, false);
std::vector<int> classification(noKeys, 0);
std::vector<int> noise;
std::vector<int> neighborPts;
for (int i = 0; i < noKeys; i++) {
if (!visited[i]) {
pointQueue.clusterPoints.push_back(octreeGen->getCloud()->points.at(i));
visited[i] = true;
octreeRegionQuery(octreeGen, pointQueue.clusterPoints.at(0), eps, &neighborPts);
if (neighborPts.size() < minPtsAux)
noise.push_back(i);
else {
for (int k = 0; k < neighborPts.size(); k++) {
if (!visited[neighborPts[k]]) {
visited[neighborPts[k]] = true;
pcl::mod_pointXYZ auxPoint = octreeGen->getCloud()->points.at(neighborPts[k]);
pointQueue.clusterPoints.push_back(auxPoint);
}
}
if (pointQueue.clusterPoints.size() >= minPtsAux) {
pointQueue.calculateCentroid();
clustersAux.push_back(pointQueue);
pointQueue.clusterPoints.clear();
}
}
}
}
}
/// Generates a set of clusters.
///@param[in] octreeGen The octree to be searched.
///@param[in] eps_ The search radius for the octree.
///@param[in] clusters Vector that stores all the generated clusters.
void dbscan::DBSCAN_Octree_fast(htr::OctreeGenerator *octreeGen, float eps, int minPts) // O(nlogn)
{
clustersAux.clear();
cluster pointQueue;
pcl::mod_pointXYZ auxCentroid;
// The number of points
int noKeys = octreeGen->getCloud()->points.size();
std::vector<bool> visited(noKeys, false);
std::vector<int> classification(noKeys, 0);
std::vector<int> noise;
std::vector<int> neighborPts;
for (int i = 0; i < noKeys; i++) // O(n)
{
if (!visited[i]) // O(log n)
{
pointQueue.clusterPoints.push_back(octreeGen->getCloud()->points.at(i));
visited[i] = true;
octreeGen->getOctree()->voxelSearch(pointQueue.clusterPoints.at(0), neighborPts);
if (neighborPts.size() < minPtsAux)
noise.push_back(i);
else {
for (int k = 0; k < neighborPts.size(); k++) {
if (!visited[neighborPts[k]]) {
visited[neighborPts[k]] = true;
pcl::mod_pointXYZ auxPoint = octreeGen->getCloud()->points.at(neighborPts[k]);
pointQueue.clusterPoints.push_back(auxPoint);
}
}
if (pointQueue.clusterPoints.size() >= minPtsAux) {
pointQueue.calculateCentroid();
clustersAux.push_back(pointQueue);
pointQueue.clusterPoints.clear();
}
}
}
}
}
/// Generates a set of clusters.
///@param[in] octreeGen The octree to be searched.
///@param[in] eps_ The search radius for the octree.
///@param[in] clusters Vector that stores all the generated clusters.
void dbscan::DBSCAN_Octree_fast_one_step(htr::OctreeGenerator *octreeGen, float eps, int minPts) {
int noKeys = octreeGen->getCloud()->points.size();
std::vector<bool> clustered(noKeys, false);
std::vector<bool> visited(noKeys, false);
std::vector<int> noise;
std::vector<int> neighborPts;
std::vector<int> neighborPts_;
int c = 0;
// for each unvisted point P in dataset keypoints
for (int i = 0; i < noKeys; i++) {
if (!visited[i]) {
// Mark P as visited
visited[i] = true;
octreeRegionQuery(octreeGen, octreeGen->getCloud()->points.at(i), eps, &neighborPts);
if (neighborPts.size() < minPts)
// Mark P as Noise
noise.push_back(i);
else {
clusters.push_back(cluster());
// expand cluster, add P to cluster c
clustered[i] = true;
clusters.at(c).clusterPoints.push_back(octreeGen->getCloud()->points.at(i));
// for each point P' in neighborPts, Expand cluster
for (int j = 0; j < neighborPts.size(); j++) {
// if P' is not visited
if (!visited[neighborPts[j]]) {
// Mark P' as visited
visited[neighborPts[j]] = true;
octreeRegionQuery(octreeGen, octreeGen->getCloud()->points.at(neighborPts[j]), eps, &neighborPts_);
//
if (neighborPts_.size() >= minPts) neighborPts.insert(neighborPts.end(), neighborPts_.begin(), neighborPts_.end());
}
// if P' is not yet a member of any cluster, add P' to cluster c
if (!clustered[neighborPts[j]]) {
clustered[neighborPts[j]] = true;
clusters.at(c).clusterPoints.push_back(octreeGen->getCloud()->points.at(neighborPts[j]));
}
}
c++;
}
}
}
}
/// Generates a set of clusters.
///@param[in] octreeGen The octree to be searched.
///@param[in] eps_ The search radius for the octree.
///@param[in] clusters Vector that stores all the generated clusters.
void dbscan::DBSCAN_Octree_fast2(htr::OctreeGenerator *octreeGen, int minPts) {
// Clear aux clusters
clustersAux.clear();
if (!octreeGen->getCloud()->points.empty()) {
// Create array of tree iterators
std::vector<htr::OctreeGenerator::LeafNodeIterator> leafIterators;
std::vector<int> tempVec;
cluster tempPointCluster;
std::vector<std::vector<int>> neighborPts;
htr::OctreeGenerator::LeafNodeIterator it(octreeGen->getOctree().get());
while (*(it)) {
neighborPts.push_back(tempVec);
clustersAux.push_back(tempPointCluster);
it.getLeafContainer().getPointIndices(neighborPts.back());
for (int k = 0; k < neighborPts.back().size(); ++k) {
clustersAux.back().clusterPoints.push_back(octreeGen->getCloud()->points.at(neighborPts.back().at(k)));
}
clustersAux.back().calculateCentroid();
++it;
}
}
}
} // namespace dbScanSpace
//#include "dbScan.h"
//
// namespace dbScanSpace
//{
//
// dbscan::dbscan()
//{
// octreeGenIn = new htr::OctreeGenerator();
// octreeGen = new htr::OctreeGenerator();
//}
//
// dbscan::~dbscan()
//{
// delete octreeGenIn;
// delete octreeGen;
//}
//
// ///Initializes the point cloud from a file, and the octree.
/////@param[in] filename Location of the file that has the data.
/////@param[in] octreeResolution_ Resolution with which the octree is initialized.
/////@param[in] eps_ The search radius for the octree.
/////@param[in] minPtsAux_ Minimum points for the initial clusters.
/////@param[in] minPts_ Minimum points for the final clusters.
// dbscan::dbscan(const char* filename, const int octreeResolution_, const float eps_, const int
// minPtsAux_, const int minPts_ )
// {
// octreeGenIn = new htr::OctreeGenerator();
// octreeGen = new htr::OctreeGenerator();
//
// eps = eps_;
// minPts = minPts_;
// minPtsAux = minPtsAux_;
// octreeResolution = octreeResolution_;
//
// octreeGenIn->readCloudFromFile(filename);
// octreeGenIn->initOctree(octreeResolution);
//
// centroid = octreeGenIn->getCloudCentroid();
// }
//
// ///Generates the clusters from the loaded data.
// void dbscan::generateClusters()
// {
// clusters.clear();
// clustersAux.clear();
// clustersCentroids.clear();
//
// // A first set of clusters is generated. This first set has a large number of small
// clusters.
// DBSCAN_Octree(octreeGenIn, eps, minPtsAux);
//
// // The clusters centroids are calculated and used to generate a second octree.
// for(dbScanSpace::cluster cluster:clustersAux)
// clustersCentroids.push_back(cluster.centroid);
//
// octreeGen->initCloudFromVector<pcl::PointXYZ>(clustersCentroids);
// octreeGen->initOctree(octreeResolution);
//
// // Using the second octree and the centroids of the clusters, a new set of clusters is
// generated.
// // These are the final clusters.
// DBSCAN_Octree_merge(octreeGen, 2*eps, minPts);
//
// for(int i = 0; i<clusters.size(); i++)
// clusters[i].toPoint3D();
// }
//
// ///Generates the clusters from the loaded data.
// void dbscan::generateClusters_fast()
// {
// clusters.clear();
// clustersAux.clear();
// clustersCentroids.clear();
//
// // A first set of clusters is generated. This first set has a large number of small
// clusters.
// DBSCAN_Octree_fast2(octreeGenIn, minPtsAux);
//
//// printf("\n Aux clusters size:%d\n\n", clustersAux.size());
// // The clusters centroids are calculated and used to generate a second octree.
// for(dbScanSpace::cluster cluster:clustersAux)
// clustersCentroids.push_back(cluster.centroid);
//
// octreeGen->initCloudFromVector<pcl::PointXYZ>(clustersCentroids);
// octreeGen->initOctree(octreeResolution);
//
// // Using the second octree and the centroids of the clusters, a new set of clusters is
// generated.
// // These are the final clusters.
// //DBSCAN_Octree_merge(octreeGen, 2*eps, minPts);
// DBSCAN_Octree_merge(octreeGen, 2*eps, minPts);
//
//// printf("\n Clusters size:%d\n\n", clusters.size());
// for(int i = 0; i<clusters.size(); i++)
// clusters[i].toPoint3D();
// }
//
// ///Calculates the centroid form a vector of points.
/////@param[in] group Vector that contains the point that will be processed.
// void dbscan::calculateCentroid(vector<pcl::PointXYZ> group)
// {
// for(pcl::PointXYZ point:group)
// {
// centroid.x+=point.x;
// centroid.y+=point.y;
// centroid.z+=point.z;
// }
// centroid.x/=group.size();
// centroid.y/=group.size();
// centroid.z/=group.size();
// }
//
// ///Does a radius search for the K nearest neighbors of a point.
/////@param[in] octreeGen The octree to be searched.
/////@param[in] searchPoint The point around which the search will be conducted.
/////@param[in] eps_ The search radius for the octree.
/////@param[in] retKeys_ Vector that stores the indices of the nearest points.
// void dbscan::octreeRegionQuery(htr::OctreeGenerator *octreeGen, pcl::PointXYZ & searchPoint,
// double eps, vector<int> *retKeys)
// {
// retKeys->clear();
// vector<int> pointIdxRadiusSearch;
// vector<float> pointRadiusSquaredDistance;
//
// octreeGen->getOctree()->radiusSearch(searchPoint, eps, *retKeys,
// pointRadiusSquaredDistance);
// }
//
// ///Merges a set of clusters.
/////@param[in] octreeGen The octree to be searched.
/////@param[in] eps_ The search radius for the octree.
/////@param[in] clustersIn The clusters that will be merged.
/////@param[in] clustersOut Vector that stores all merged clusters.
// void dbscan::DBSCAN_Octree_merge(htr::OctreeGenerator *octreeGen, float eps, int minPts)
// {
// clusters.clear();
// cluster pointQueue;
// vector<pcl::PointXYZ> clusterPoints;
//
// int noKeys = clustersAux.size();
// vector<bool> visited(noKeys, false);
//
// vector<int> noise;
// vector<int> neighborPts(noKeys, -1);
//
// for(int i = 0; i < noKeys; i++)
// {
// if(!visited[i])
// {
// clusterPoints.push_back(clustersAux.at(i).centroid);
// pointQueue.clusterPoints.insert(pointQueue.clusterPoints.end(),
// clustersAux.at(i).clusterPoints.begin(),
// clustersAux.at(i).clusterPoints.end());
// visited[i] = true;
//
// for(int j = 0; j < clusterPoints.size(); j++)
// {
// octreeRegionQuery(octreeGen, clusterPoints.at(j), eps, &neighborPts);
//
// for(int k =0; k < neighborPts.size(); k++)
// {
// if(!visited[neighborPts[k]])
// {
// visited[neighborPts[k]] = true;
//
// clusterPoints.push_back(clustersAux.at(neighborPts[k]).centroid);
//
// pointQueue.clusterPoints.insert(pointQueue.clusterPoints.end(),
// clustersAux.at(neighborPts[k]).clusterPoints.begin(),
// clustersAux.at(neighborPts[k]).clusterPoints.end());
// }
// }
// }
//
// if(pointQueue.clusterPoints.size() >= minPts)
// {
// pointQueue.calculateCentroid();
// clusters.push_back(pointQueue);
// }
//
// pointQueue.clusterPoints.clear();
// }
// }
//
//// clustersAux.clear();
// }
//
// ///Generates a set of clusters.
/////@param[in] octreeGen The octree to be searched.
/////@param[in] eps_ The search radius for the octree.
/////@param[in] clusters Vector that stores all the generated clusters.
// void dbscan::DBSCAN_Octree(htr::OctreeGenerator *octreeGen, float eps, int minPts)
// {
// clustersAux.clear();
// cluster pointQueue;
// pcl::PointXYZ auxCentroid;
//
// int noKeys = octreeGen->getCloud()->points.size();
// vector<bool> visited(noKeys, false);
// vector<int> classification(noKeys, 0);
//
// vector<int> noise;
// vector<int> neighborPts;
//
// for(int i = 0; i < noKeys; i++)
// {
// if(!visited[i])
// {
// pointQueue.clusterPoints.push_back(octreeGen->getCloud()->points.at(i));
// visited[i] = true;
//
// octreeRegionQuery(octreeGen, pointQueue.clusterPoints.at(0),eps, &neighborPts);
//
// for(int k =0; k < neighborPts.size(); k++)
// {
// if(!visited[neighborPts[k]])
// {
// visited[neighborPts[k]] = true;
// pcl::PointXYZ auxPoint =
// octreeGen->getCloud()->points.at(neighborPts[k]);
// pointQueue.clusterPoints.push_back(auxPoint);
// }
// }
//
// if(pointQueue.clusterPoints.size() >= minPtsAux)
// {
// pointQueue.calculateCentroid();
// clustersAux.push_back(pointQueue);
// }
//
// pointQueue.clusterPoints.clear();
// }
// }
// }
//
// ///Generates a set of clusters.
/////@param[in] octreeGen The octree to be searched.
/////@param[in] eps_ The search radius for the octree.
/////@param[in] clusters Vector that stores all the generated clusters.
// void dbscan::DBSCAN_Octree_fast(htr::OctreeGenerator *octreeGen, float eps, int minPts)
// {
// clustersAux.clear();
//
// cluster pointQueue;
// pcl::PointXYZ auxCentroid;
//
// int noKeys = octreeGen->getCloud()->points.size();
// vector<bool> visited(noKeys, false);
// vector<int> classification(noKeys, 0);
//
// vector<int> noise;
// vector<int> neighborPts;
//
// for(int i = 0; i < noKeys; i++)
// {
// if(!visited[i])
// {
// pointQueue.clusterPoints.push_back(octreeGen->getCloud()->points.at(i));
// visited[i] = true;
//
// octreeGen->getOctree()->voxelSearch(pointQueue.clusterPoints.at(0), neighborPts);
//
// for(int k =0; k < neighborPts.size(); k++)
// {
// if(!visited[neighborPts[k]])
// {
// visited[neighborPts[k]] = true;
// pcl::PointXYZ auxPoint =
// octreeGen->getCloud()->points.at(neighborPts[k]);
// pointQueue.clusterPoints.push_back(auxPoint);
// }
// }
//
// if(pointQueue.clusterPoints.size() >= minPtsAux)
// {
// pointQueue.calculateCentroid();
// clustersAux.push_back(pointQueue);
// }
//
// pointQueue.clusterPoints.clear();
// }
// }
// }
//
//
// ///Generates a set of clusters.
// ///@param[in] octreeGen The octree to be searched.
// ///@param[in] eps_ The search radius for the octree.
// ///@param[in] clusters Vector that stores all the generated clusters.
// void dbscan::DBSCAN_Octree_fast2(htr::OctreeGenerator *octreeGen, int minPts)
// {
// //Clear aux clusters
// clustersAux.clear();
//
// if(!octreeGen->getCloud()->points.empty())
// {
// //Create array of tree iterators
// vector<htr::OctreeGenerator::LeafNodeIterator> leafIterators;
//
// vector<int> tempVec;
// cluster tempPointCluster;
// vector<vector<int>> neighborPts;
//
// htr::OctreeGenerator::LeafNodeIterator it(octreeGen->getOctree().get());
//
// while ( *(it) )
// {
// neighborPts.push_back(tempVec);
// clustersAux.push_back(tempPointCluster);
//
// it.getLeafContainer().getPointIndices(neighborPts.back());
// for(int k=0; k<neighborPts.back().size(); ++k)
// {
// clustersAux.back().clusterPoints.push_back(octreeGen->getCloud()->points.at(neighborPts.back().at(k)));
// }
// clustersAux.back().calculateCentroid();
//
// ++it;
// }
// }
//
// }
//}

View File

@ -0,0 +1,190 @@
#pragma once
#include "debugstream.hpp"
// #include "include/dbscan/dbScan.h"
#include "yaml_config.h"
// inline pcl::PointCloud<pcl::PointXYZ>::Ptr
// DbScanCluster(const pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud) {
// dbScanSpace::dbscan dbscan;
// std::vector<htr::Point3D> groupA;
// // 创建一个新的 pcl::PointCloud<pcl::PointXYZRGB>::Ptr 类型的点云
// pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
// new pcl::PointCloud<pcl::PointXYZRGB>);
// // 遍历输入点云,并将每个点转换为 pcl::PointXYZRGB 类型
// for (const auto &point : input_cloud->points) {
// pcl::PointXYZRGB new_point;
// new_point.x = point.x;
// new_point.y = point.y;
// new_point.z = point.z;
// new_point.r = 255; // 设置 RGB 颜色
// new_point.g = 255;
// new_point.b = 255;
// cloud->points.push_back(new_point);
// }
// // 设置输出点云的其他属性
// cloud->width = cloud->points.size();
// cloud->height = 1;
// cloud->is_dense = true;
// static int octreeResolution =
// yaml_config["cluster"]["octreeResolution"].as<int>();
// static float epsilon = yaml_config["cluster"]["epsilon"].as<float>();
// static int minPtsAux = yaml_config["cluster"]["minPtsAux"].as<int>();
// static int minPts = yaml_config["cluster"]["minPts"].as<int>();
// dbscan.init(groupA, cloud, 120, 40, 5, 5);
// dbscan.generateClusters();
// gDebug(dbscan.getClusters().size());
// std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> store;
// std::vector<dbScanSpace::cluster> cloud_cluster = dbscan.getClusters();
// std::sort(cloud_cluster.begin(), cloud_cluster.end(),
// [](dbScanSpace::cluster &l, dbScanSpace::cluster &r) {
// return l.clusterPoints.size() > r.clusterPoints.size();
// });
// pcl::PointCloud<pcl::PointXYZ>::Ptr cluster(
// new pcl::PointCloud<pcl::PointXYZ>);
// if (!cloud_cluster.empty()) {
// auto &clusterPoints = cloud_cluster[0].clusterPoints;
// cluster->points.resize(clusterPoints.size());
// for (size_t i = 0; i < clusterPoints.size(); ++i) {
// cluster->points[i].x = clusterPoints[i].x;
// cluster->points[i].y = clusterPoints[i].y;
// cluster->points[i].z = clusterPoints[i].z;
// }
// gDebugCol4() << VAR(input_cloud->points.size(), cluster->points.size());
// return cluster;
// } else {
// gDebugCol4() << VAR(input_cloud->points.size(), "nullptr");
// return cluster;
// }
// // for (int i = 0; i < cloud_cluster.size(); i++) {
// // auto &clusterPoints = cloud_cluster[i].clusterPoints;
// // // 将 std::vector<pcl::PointXYZ> 拷贝到
// pcl::PointCloud<pcl::PointXYZ>
// // cluster->points.resize(clusterPoints.size());
// // for (size_t i = 0; i < clusterPoints.size(); ++i) {
// // cluster->points[i].x = clusterPoints[i].x;
// // cluster->points[i].y = clusterPoints[i].y;
// // cluster->points[i].z = clusterPoints[i].z;
// // }
// // store.emplace_back(cluster);
// // cluster->points.clear();
// // }
// // return res;
// }
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/search/kdtree.h>
#include <pcl/segmentation/extract_clusters.h>
#include <vector>
inline pcl::PointCloud<pcl::PointXYZ>::Ptr
EuclideanCluster(const pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud) {
// Create a kdtree for the input cloud
pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(
new pcl::search::KdTree<pcl::PointXYZ>);
tree->setInputCloud(input_cloud);
// Extract the Euclidean clusters
std::vector<pcl::PointIndices> cluster_indices;
pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
ec.setClusterTolerance(
static_cast<double>(yaml_config["cluster"]["epsilon"].as<float>()));
ec.setMinClusterSize(
static_cast<int>(yaml_config["cluster"]["minPts"].as<int>()));
ec.setMaxClusterSize(input_cloud->size());
ec.setSearchMethod(tree);
ec.setInputCloud(input_cloud);
ec.extract(cluster_indices);
// Find the largest cluster
size_t largest_cluster_size = 0;
size_t largest_cluster_index = 0;
for (size_t i = 0; i < cluster_indices.size(); ++i) {
if (cluster_indices[i].indices.size() > largest_cluster_size) {
largest_cluster_size = cluster_indices[i].indices.size();
largest_cluster_index = i;
}
}
// Create a new point cloud for the largest cluster
pcl::PointCloud<pcl::PointXYZ>::Ptr largest_cluster(
new pcl::PointCloud<pcl::PointXYZ>);
if (!cluster_indices.empty()) {
for (int index : cluster_indices[largest_cluster_index].indices) {
largest_cluster->push_back(input_cloud->at(index));
}
}
largest_cluster->width = largest_cluster->points.size();
largest_cluster->height = 1;
largest_cluster->is_dense = true;
gDebugCol4() << VAR(input_cloud->points.size(),
largest_cluster->points.size());
return largest_cluster;
}
/**
* 使
* @param input_cloud
// * @param cluster_tolerance 聚类距离阈值(单位:米)
// * @param min_cluster_size 最小聚类尺寸
// * @param max_cluster_size 最大聚类尺寸
* @param output_clouds
*/
template <typename PointT = pcl::PointXYZ>
typename pcl::PointCloud<PointT>::Ptr
GxtEuclideanClustering(typename pcl::PointCloud<PointT>::Ptr input_cloud) {
auto startTime = std::chrono::steady_clock::now();
// 创建欧式聚类对象
pcl::EuclideanClusterExtraction<PointT> ec;
static double cluster_tolerance = static_cast<double>(
yaml_config["cluster"]["cluster_tolerance"].as<float>());
static double min_cluster_size = static_cast<double>(
yaml_config["cluster"]["min_cluster_size"].as<float>());
static double max_cluster_size = static_cast<double>(
yaml_config["cluster"]["max_cluster_size"].as<float>());
ec.setClusterTolerance(cluster_tolerance);
ec.setMinClusterSize(min_cluster_size);
ec.setMaxClusterSize(max_cluster_size);
ec.setSearchMethod(
pcl::search::KdTree<pcl::PointXYZ>::Ptr(new pcl::search::KdTree<PointT>));
// 提取聚类
std::vector<pcl::PointIndices> cluster_indices;
ec.setInputCloud(input_cloud);
ec.extract(cluster_indices);
size_t largest_cluster_size = 0;
size_t largest_cluster_index = 0;
for (size_t i = 0; i < cluster_indices.size(); ++i) {
if (cluster_indices[i].indices.size() > largest_cluster_size) {
largest_cluster_size = cluster_indices[i].indices.size();
largest_cluster_index = i;
}
}
// 生成聚类结果点云
typename pcl::PointCloud<PointT>::Ptr output_clouds;
for (int idx : cluster_indices[largest_cluster_index].indices) {
output_clouds->points.push_back(input_cloud->points[idx]);
}
output_clouds->width = output_clouds->points.size();
output_clouds->height = 1;
output_clouds->is_dense = true;
auto endTime = std::chrono::steady_clock::now();
auto elapsedTime = std::chrono::duration_cast<std::chrono::milliseconds>(
endTime - startTime);
std::cout << "euclidean clustering took " << elapsedTime.count()
<< " milliseconds" << std::endl;
return output_clouds;
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,201 @@
#pragma once
#include "postprocess.h"
#include <Eigen/Core>
#include <cmath>
#include <iostream>
#include <opencv2/opencv.hpp>
#include <unordered_map>
#include "debugstream.hpp"
const double DISTANCE_THRESHOLD = 6;
// 检测框的坐标 (归一化平面坐标)
struct Box {
// 中心点的坐标
double x;
double y;
// 框的宽高
double w;
double h;
};
class DistanceEstimator {
public:
DistanceEstimator(const Eigen::Matrix3d &camera_matrix, int img_width,
int img_height)
: img_width(img_width), img_height(img_height),
camera_matrix(camera_matrix) {
// 不同类别的平均身高 (单位: 米)
height_lookup = {{"person", 1.70}, {"Ren", 1.75}, {"Dianti", 2.2}};
}
double EstimateDistance(double x, double y, double w, double h,
const std::string &class_name) {
// 计算检测框的中心点坐标 (像素)
double center_x = x * img_width;
double center_y = y * img_height;
// 计算图像平面上的检测框高度(像素)
double bbox_height_px = h * img_height;
// 根据目标类别查找平均身高
if (height_lookup.find(class_name) == height_lookup.end()) {
std::cerr << "error: " << class_name << " not found" << std::endl;
std::terminate();
return -1;
}
double target_height = height_lookup[class_name];
// 根据相似三角形原理计算距离
double distance = (target_height * camera_matrix(0, 0)) / bbox_height_px;
return distance;
}
Eigen::Vector3d Get3DPosition(double x, double y, double w, double h,
const std::string &class_name) {
// 计算检测框的中心点坐标 (像素)
double center_x = x * img_width;
double center_y = y * img_height;
// 计算距离
double distance = EstimateDistance(x, y, w, h, class_name);
if (distance < 0) {
return Eigen::Vector3d::Zero();
}
// 根据相机内参和距离计算3D位置
double Z = distance;
double X = (center_x - camera_matrix(0, 2)) * Z / camera_matrix(0, 0);
double Y = (center_y - camera_matrix(1, 2)) * Z / camera_matrix(1, 1);
return Eigen::Vector3d(X, Y, Z);
}
// 批量处理一系列的3D点返回值是对应到相机坐标系的3D点
// 注意这个批量只能是同一个类别
// 如果有多个类别,需要多次执行处理
std::vector<Eigen::Vector3d> Get3DPosition(const std::vector<double> &x,
const std::vector<double> &y,
const std::vector<double> &w,
const std::vector<double> &h,
const std::string &class_name) {
assert(x.size() == y.size() && x.size() == w.size() &&
x.size() == h.size());
std::vector<Eigen::Vector3d> res(x.size());
for (int i = 0; i < x.size(); i++) {
res[i] = Get3DPosition(x[i], y[i], w[i], h[i], class_name);
}
return res;
}
// 批量处理一系列的3D点返回值是对应到相机坐标系的3D点
// 注意这个批量只能是同一个类别
// 如果有多个类别,需要多次执行处理
std::vector<Eigen::Vector3d> Get3DPosition(const std::vector<Box> &boxes,
const std::string &class_name) {
std::vector<Eigen::Vector3d> res(boxes.size());
for (int i = 0; i < boxes.size(); i++) {
res[i] = Get3DPosition(boxes[i].x, boxes[i].y, boxes[i].w, boxes[i].h,
class_name);
}
return res;
}
private:
int img_width;
int img_height;
Eigen::Matrix3d camera_matrix;
std::unordered_map<std::string, double> height_lookup;
};
inline double CalculateDistance(const Eigen::Vector3d &point1,
const Eigen::Vector3d &point2) {
return std::sqrt((point1 - point2).squaredNorm());
}
inline void DealImage(DistanceEstimator &es, cv::Mat &image,
const std::vector<Box> &rens,
const std::vector<Box> &diantis) {
gDebug(rens);
gDebug(diantis);
static std::vector<cv::Scalar> colors{{0, 255, 0}, {0, 0, 255},
{255, 0, 0}, {255, 255, 0},
{255, 0, 255}, {0, 255, 255}};
auto positions_ren = es.Get3DPosition(rens, "Ren");
gDebug(positions_ren);
auto positions_dianti = es.Get3DPosition(diantis, "Dianti");
gDebug(positions_dianti);
std::vector<int> relate_ren(diantis.size(), 0);
for (int i = 0; i < diantis.size(); i++) {
cv::Point p_dianti(diantis[i].x * image.cols, diantis[i].y * image.rows);
for (int j = 0; j < rens.size(); j++) {
auto distance = CalculateDistance(positions_dianti[i], positions_ren[j]);
gDebug(distance);
if (distance > DISTANCE_THRESHOLD) {
continue;
}
relate_ren[i]++;
cv::Point p_ren(rens[j].x * image.cols, rens[j].y * image.rows);
cv::arrowedLine(image, p_dianti, p_ren, colors.at(i % colors.size()), 2);
}
}
}
inline int Test() {
int img_width = 1280; // 图像宽度 (像素)
int img_height = 640; // 图像高度 (像素)
// 相机内参
Eigen::Matrix3d camera_matrix;
camera_matrix << 787.22316869, 0.0, 628.91534144, 0.0, 793.45182,
313.46301416, 0.0, 0.0, 1.0;
DistanceEstimator estimator(camera_matrix, img_width, img_height);
// 估算人的距离
// Eigen::Vector4d bbox1(0.4, 0.3, 0.2, 0.5); // 检测框的归一化坐标 (x, y, w,
// h)
double distance_person =
estimator.EstimateDistance(0.4, 0.3, 0.2, 0.5, "Ren");
std::cout << "估算的人距离: " << distance_person << "" << std::endl;
Eigen::Vector3d position_person =
estimator.Get3DPosition(0.4, 0.3, 0.2, 0.5, "Ren");
std::cout << "估算的人位置: " << position_person.transpose() << ""
<< std::endl;
// 估算车的距离
// Eigen::Vector4d bbox2(0.8, 0.3, 0.2, 0.1); // 检测框的归一化坐标 (x, y, w,
// h)
double distance_vehicle =
estimator.EstimateDistance(0.8, 0.3, 0.2, 0.1, "Dianti");
std::cout << "估算的车距离: " << distance_vehicle << "" << std::endl;
Eigen::Vector3d position_vehicle =
estimator.Get3DPosition(0.8, 0.3, 0.2, 0.1, "Dianti");
std::cout << "估算的车位置: " << position_vehicle.transpose() << ""
<< std::endl;
double distance = CalculateDistance(position_person, position_vehicle);
std::cout << "两点之间的距离: " << distance << "" << std::endl;
std::vector<Box> rens;
rens.push_back({0.4, 0.3, 0.2, 0.1});
rens.push_back({0.5, 0.4, 0.2, 0.5});
std::vector<Box> diantis;
diantis.push_back({0.5, 0.3, 0.2, 0.5});
diantis.push_back({0.6, 0.4, 0.2, 0.5});
cv::Mat image = cv::Mat::zeros(640, 1280, CV_8UC3);
DealImage(estimator, image, rens, diantis);
cv::imwrite("output.jpg", image);
// cv::imshow("Image", image);
// cv::waitKey(0);
// cv::destroyAllWindows();
// gDebug(relate_ren);
return 0;
}

View File

@ -0,0 +1,53 @@
#ifndef __DRM_FUNC_H__
#define __DRM_FUNC_H__
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/fcntl.h>// open function
#include <unistd.h> // close function
#include <errno.h>
#include <sys/mman.h>
#include <linux/input.h>
#include "libdrm/drm_fourcc.h"
#include "xf86drm.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef int (* FUNC_DRM_IOCTL)(int fd, unsigned long request, void *arg);
typedef struct _drm_context{
void *drm_handle;
FUNC_DRM_IOCTL io_func;
} drm_context;
/* memory type definitions. */
enum drm_rockchip_gem_mem_type
{
/* Physically Continuous memory and used as default. */
ROCKCHIP_BO_CONTIG = 1 << 0,
/* cachable mapping. */
ROCKCHIP_BO_CACHABLE = 1 << 1,
/* write-combine mapping. */
ROCKCHIP_BO_WC = 1 << 2,
ROCKCHIP_BO_SECURE = 1 << 3,
ROCKCHIP_BO_MASK = ROCKCHIP_BO_CONTIG | ROCKCHIP_BO_CACHABLE |
ROCKCHIP_BO_WC | ROCKCHIP_BO_SECURE
};
int drm_init(drm_context *drm_ctx);
void* drm_buf_alloc(drm_context *drm_ctx,int drm_fd, int TexWidth, int TexHeight,int bpp,int *fd,unsigned int *handle,size_t *actual_size);
int drm_buf_destroy(drm_context *drm_ctx,int drm_fd,int buf_fd, int handle,void *drm_buf,size_t size);
void drm_deinit(drm_context *drm_ctx, int drm_fd);
#ifdef __cplusplus
}
#endif
#endif /*__DRM_FUNC_H__*/

View File

@ -0,0 +1,43 @@
#ifndef _RKNN_YOLOV5_DEMO_POSTPROCESS_H_
#define _RKNN_YOLOV5_DEMO_POSTPROCESS_H_
#include <stdint.h>
#include <vector>
#include <string>
#define OBJ_NAME_MAX_SIZE 16
#define OBJ_NUMB_MAX_SIZE 64
#define OBJ_CLASS_NUM 2
#define NMS_THRESH 0.45
#define BOX_THRESH 0.25
#define PROP_BOX_SIZE (5 + OBJ_CLASS_NUM)
typedef struct _BOX_RECT
{
int left;
int right;
int top;
int bottom;
} BOX_RECT;
typedef struct __detect_result_t
{
char name[OBJ_NAME_MAX_SIZE];
BOX_RECT box;
float prop;
} detect_result_t;
typedef struct _detect_result_group_t
{
int id;
int count;
detect_result_t results[OBJ_NUMB_MAX_SIZE];
} detect_result_group_t;
int post_process(int8_t *input0, int8_t *input1, int8_t *input2, int model_in_h, int model_in_w,
float conf_threshold, float nms_threshold, BOX_RECT pads, float scale_w, float scale_h,
std::vector<int32_t> &qnt_zps, std::vector<float> &qnt_scales,
detect_result_group_t *group, const std::vector<std::string>& labels);
// void deinitPostProcess();
#endif //_RKNN_YOLOV5_DEMO_POSTPROCESS_H_

View File

@ -0,0 +1,16 @@
#ifndef _RKNN_YOLOV5_DEMO_PREPROCESS_H_
#define _RKNN_YOLOV5_DEMO_PREPROCESS_H_
#include <stdio.h>
#include "im2d.h"
#include "rga.h"
#include "opencv2/core/core.hpp"
#include "opencv2/imgcodecs.hpp"
#include "opencv2/imgproc.hpp"
#include "postprocess.h"
void letterbox(const cv::Mat &image, cv::Mat &padded_image, BOX_RECT &pads, const float scale, const cv::Size &target_size, const cv::Scalar &pad_color = cv::Scalar(128, 128, 128));
int resize_rga(rga_buffer_t &src, rga_buffer_t &dst, const cv::Mat &image, cv::Mat &resized_image, const cv::Size &target_size);
#endif //_RKNN_YOLOV5_DEMO_PREPROCESS_H_

View File

@ -0,0 +1,2 @@
# RGA
The RGA libraries and docs are obtained from https://github.com/airockchip/librga

View File

@ -0,0 +1,59 @@
/*
* Copyright (C) 2016 Rockchip Electronics Co., Ltd.
* Authors:
* Zhiqin Wei <wzq@rock-chips.com>
*
* 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 _rk_graphic_buffer_h_
#define _rk_graphic_buffer_h_
#ifdef ANDROID
#include <stdint.h>
#include <vector>
#include <sys/types.h>
#include <system/graphics.h>
#include <utils/Thread.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <errno.h>
#include <time.h>
#include <unistd.h>
#include <sys/mman.h>
#include <linux/stddef.h>
#include <utils/Atomic.h>
#include <utils/Errors.h>
#include <android/log.h>
#include <utils/Log.h>
#include <log/log_main.h>
#include "drmrga.h"
#include "rga.h"
// -------------------------------------------------------------------------------
int RkRgaGetHandleFd(buffer_handle_t handle, int *fd);
int RkRgaGetHandleAttributes(buffer_handle_t handle,
std::vector<int> *attrs);
int RkRgaGetHandleMapAddress(buffer_handle_t handle,
void **buf);
#endif //Android
#endif //_rk_graphic_buffer_h_

View File

@ -0,0 +1,81 @@
/*
* Copyright (C) 2016 Rockchip Electronics Co., Ltd.
* Authors:
* Zhiqin Wei <wzq@rock-chips.com>
*
* 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 _rockchip_rga_c_h_
#define _rockchip_rga_c_h_
#include <stdint.h>
#include <sys/types.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <errno.h>
#include <time.h>
#include <unistd.h>
#include <sys/mman.h>
#include <linux/stddef.h>
#include "drmrga.h"
#include "rga.h"
#ifdef __cplusplus
extern "C"{
#endif
/*
* Compatible with the old version of C interface.The new
* version of the C interface no longer requires users to
* initialize rga, so RgaInit and RgaDeInit are just for
* compatibility with the old C interface, so please do
* not use ctx, because it is usually a NULL.
*/
#define RgaInit(ctx) ({ \
int ret = 0; \
ret = c_RkRgaInit(); \
c_RkRgaGetContext(ctx); \
ret;\
})
#define RgaDeInit(ctx) { \
(void)ctx; /* unused */ \
c_RkRgaDeInit(); \
}
#define RgaBlit(...) c_RkRgaBlit(__VA_ARGS__)
#define RgaCollorFill(...) c_RkRgaColorFill(__VA_ARGS__)
#define RgaFlush() c_RkRgaFlush()
int c_RkRgaInit();
void c_RkRgaDeInit();
void c_RkRgaGetContext(void **ctx);
int c_RkRgaBlit(rga_info_t *src, rga_info_t *dst, rga_info_t *src1);
int c_RkRgaColorFill(rga_info_t *dst);
int c_RkRgaFlush();
#ifndef ANDROID /* linux */
int c_RkRgaGetAllocBuffer(bo_t *bo_info, int width, int height, int bpp);
int c_RkRgaGetAllocBufferCache(bo_t *bo_info, int width, int height, int bpp);
int c_RkRgaGetMmap(bo_t *bo_info);
int c_RkRgaUnmap(bo_t *bo_info);
int c_RkRgaFree(bo_t *bo_info);
int c_RkRgaGetBufferFd(bo_t *bo_info, int *fd);
#endif /* #ifndef ANDROID */
#ifdef __cplusplus
}
#endif
#endif /* #ifndef _rockchip_rga_c_h_ */

View File

@ -0,0 +1,193 @@
/*
* Copyright (C) 2020 Rockchip Electronics Co., Ltd.
* Authors:
* PutinLee <putin.lee@rock-chips.com>
*
* 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 _LIBS_RGA_MUTEX_H
#define _LIBS_RGA_MUTEX_H
#ifndef ANDROID
#include <stdint.h>
#include <sys/types.h>
#include <time.h>
#include <pthread.h>
// Enable thread safety attributes only with clang.
// The attributes can be safely erased when compiling with other compilers.
#if defined(__clang__) && (!defined(SWIG))
#define THREAD_ANNOTATION_ATTRIBUTE__(x) __attribute__((x))
#else
#define THREAD_ANNOTATION_ATTRIBUTE__(x) // no-op
#endif
#define CAPABILITY(x) THREAD_ANNOTATION_ATTRIBUTE__(capability(x))
#define SCOPED_CAPABILITY THREAD_ANNOTATION_ATTRIBUTE__(scoped_lockable)
#define GUARDED_BY(x) THREAD_ANNOTATION_ATTRIBUTE__(guarded_by(x))
#define PT_GUARDED_BY(x) THREAD_ANNOTATION_ATTRIBUTE__(pt_guarded_by(x))
#define ACQUIRED_BEFORE(...) THREAD_ANNOTATION_ATTRIBUTE__(acquired_before(__VA_ARGS__))
#define ACQUIRED_AFTER(...) THREAD_ANNOTATION_ATTRIBUTE__(acquired_after(__VA_ARGS__))
#define REQUIRES(...) THREAD_ANNOTATION_ATTRIBUTE__(requires_capability(__VA_ARGS__))
#define REQUIRES_SHARED(...) THREAD_ANNOTATION_ATTRIBUTE__(requires_shared_capability(__VA_ARGS__))
#define ACQUIRE(...) THREAD_ANNOTATION_ATTRIBUTE__(acquire_capability(__VA_ARGS__))
#define ACQUIRE_SHARED(...) THREAD_ANNOTATION_ATTRIBUTE__(acquire_shared_capability(__VA_ARGS__))
#define RELEASE(...) THREAD_ANNOTATION_ATTRIBUTE__(release_capability(__VA_ARGS__))
#define RELEASE_SHARED(...) THREAD_ANNOTATION_ATTRIBUTE__(release_shared_capability(__VA_ARGS__))
#define TRY_ACQUIRE(...) THREAD_ANNOTATION_ATTRIBUTE__(try_acquire_capability(__VA_ARGS__))
#define TRY_ACQUIRE_SHARED(...) \
THREAD_ANNOTATION_ATTRIBUTE__(try_acquire_shared_capability(__VA_ARGS__))
#define EXCLUDES(...) THREAD_ANNOTATION_ATTRIBUTE__(locks_excluded(__VA_ARGS__))
#define ASSERT_CAPABILITY(x) THREAD_ANNOTATION_ATTRIBUTE__(assert_capability(x))
#define ASSERT_SHARED_CAPABILITY(x) THREAD_ANNOTATION_ATTRIBUTE__(assert_shared_capability(x))
#define RETURN_CAPABILITY(x) THREAD_ANNOTATION_ATTRIBUTE__(lock_returned(x))
#define NO_THREAD_SAFETY_ANALYSIS THREAD_ANNOTATION_ATTRIBUTE__(no_thread_safety_analysis)
class Condition;
/*
* NOTE: This class is for code that builds on Win32. Its usage is
* deprecated for code which doesn't build for Win32. New code which
* doesn't build for Win32 should use std::mutex and std::lock_guard instead.
*
* Simple mutex class. The implementation is system-dependent.
*
* The mutex must be unlocked by the thread that locked it. They are not
* recursive, i.e. the same thread can't lock it multiple times.
*/
class CAPABILITY("mutex") Mutex {
public:
enum {
PRIVATE = 0,
SHARED = 1
};
Mutex();
explicit Mutex(const char* name);
explicit Mutex(int type, const char* name = nullptr);
~Mutex();
// lock or unlock the mutex
int32_t lock() ACQUIRE();
void unlock() RELEASE();
// lock if possible; returns 0 on success, error otherwise
int32_t tryLock() TRY_ACQUIRE(0);
int32_t timedLock(int64_t timeoutNs) TRY_ACQUIRE(0);
// Manages the mutex automatically. It'll be locked when Autolock is
// constructed and released when Autolock goes out of scope.
class SCOPED_CAPABILITY Autolock {
public:
inline explicit Autolock(Mutex& mutex) ACQUIRE(mutex) : mLock(mutex) {
mLock.lock();
}
inline explicit Autolock(Mutex* mutex) ACQUIRE(mutex) : mLock(*mutex) {
mLock.lock();
}
inline ~Autolock() RELEASE() {
mLock.unlock();
}
private:
Mutex& mLock;
// Cannot be copied or moved - declarations only
Autolock(const Autolock&);
Autolock& operator=(const Autolock&);
};
private:
friend class Condition;
// A mutex cannot be copied
Mutex(const Mutex&);
Mutex& operator=(const Mutex&);
pthread_mutex_t mMutex;
};
// ---------------------------------------------------------------------------
inline Mutex::Mutex() {
pthread_mutex_init(&mMutex, nullptr);
}
inline Mutex::Mutex(__attribute__((unused)) const char* name) {
pthread_mutex_init(&mMutex, nullptr);
}
inline Mutex::Mutex(int type, __attribute__((unused)) const char* name) {
if (type == SHARED) {
pthread_mutexattr_t attr;
pthread_mutexattr_init(&attr);
pthread_mutexattr_setpshared(&attr, PTHREAD_PROCESS_SHARED);
pthread_mutex_init(&mMutex, &attr);
pthread_mutexattr_destroy(&attr);
} else {
pthread_mutex_init(&mMutex, nullptr);
}
}
inline Mutex::~Mutex() {
pthread_mutex_destroy(&mMutex);
}
inline int32_t Mutex::lock() {
return -pthread_mutex_lock(&mMutex);
}
inline void Mutex::unlock() {
pthread_mutex_unlock(&mMutex);
}
inline int32_t Mutex::tryLock() {
return -pthread_mutex_trylock(&mMutex);
}
inline int32_t Mutex::timedLock(int64_t timeoutNs) {
timespec now;
clock_gettime(CLOCK_REALTIME, &now);
timeoutNs += now.tv_sec*1000000000 + now.tv_nsec;
const struct timespec ts = {
/* .tv_sec = */ static_cast<time_t>(timeoutNs / 1000000000),
/* .tv_nsec = */ static_cast<long>(timeoutNs % 1000000000),
};
return -pthread_mutex_timedlock(&mMutex, &ts);
}
// ---------------------------------------------------------------------------
/*
* Automatic mutex. Declare one of these at the top of a function.
* When the function returns, it will go out of scope, and release the
* mutex.
*/
typedef Mutex::Autolock AutoMutex;
#endif // __ANDROID_VNDK__
#endif // _LIBS_RGA_MUTEX_H

View File

@ -0,0 +1,70 @@
/*
* Copyright (C) 2016 Rockchip Electronics Co., Ltd.
* Authors:
* Zhiqin Wei <wzq@rock-chips.com>
*
* 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 _LIBS_RGA_SINGLETON_H
#define _LIBS_RGA_SINGLETON_H
#ifndef ANDROID
#include "RgaMutex.h"
#if defined(__clang__)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wundefined-var-template"
#endif
template <typename TYPE>
class Singleton {
public:
static TYPE& getInstance() {
Mutex::Autolock _l(sLock);
TYPE* instance = sInstance;
if (instance == nullptr) {
instance = new TYPE();
sInstance = instance;
}
return *instance;
}
static bool hasInstance() {
Mutex::Autolock _l(sLock);
return sInstance != nullptr;
}
protected:
~Singleton() { }
Singleton() { }
private:
Singleton(const Singleton&);
Singleton& operator = (const Singleton&);
static Mutex sLock;
static TYPE* sInstance;
};
#if defined(__clang__)
#pragma clang diagnostic pop
#endif
#define RGA_SINGLETON_STATIC_INSTANCE(TYPE) \
template<> ::Mutex \
(::Singleton< TYPE >::sLock)(::Mutex::PRIVATE); \
template<> TYPE* ::Singleton< TYPE >::sInstance(nullptr); /* NOLINT */ \
template class ::Singleton< TYPE >;
#endif //ANDROID
#endif //_LIBS_RGA_SINGLETON_H

View File

@ -0,0 +1,31 @@
/*
* Copyright (C) 2016 Rockchip Electronics Co., Ltd.
* Authors:
* Zhiqin Wei <wzq@rock-chips.com>
*
* 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 _rga_utils_h_
#define _rga_utils_h_
// -------------------------------------------------------------------------------
float get_bpp_from_format(int format);
int get_perPixel_stride_from_format(int format);
int get_buf_from_file(void *buf, int f, int sw, int sh, int index);
int output_buf_data_to_file(void *buf, int f, int sw, int sh, int index);
const char *translate_format_str(int format);
int get_buf_from_file_FBC(void *buf, int f, int sw, int sh, int index);
int output_buf_data_to_file_FBC(void *buf, int f, int sw, int sh, int index);
#endif

View File

@ -0,0 +1,110 @@
/*
* Copyright (C) 2016 Rockchip Electronics Co., Ltd.
* Authors:
* Zhiqin Wei <wzq@rock-chips.com>
*
* 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 _rockchip_rga_h_
#define _rockchip_rga_h_
#include <stdint.h>
#include <sys/types.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <errno.h>
#include <time.h>
#include <unistd.h>
#include <sys/mman.h>
#include <linux/stddef.h>
#include "drmrga.h"
#include "GrallocOps.h"
#include "RgaUtils.h"
#include "rga.h"
//////////////////////////////////////////////////////////////////////////////////
#ifndef ANDROID
#include "RgaSingleton.h"
#endif
#ifdef ANDROID
#include <utils/Singleton.h>
#include <utils/Thread.h>
#include <hardware/hardware.h>
namespace android {
#endif
class RockchipRga :public Singleton<RockchipRga> {
public:
static inline RockchipRga& get() {
return getInstance();
}
int RkRgaInit();
void RkRgaDeInit();
void RkRgaGetContext(void **ctx);
#ifndef ANDROID /* LINUX */
int RkRgaAllocBuffer(int drm_fd /* input */, bo_t *bo_info,
int width, int height, int bpp, int flags);
int RkRgaFreeBuffer(int drm_fd /* input */, bo_t *bo_info);
int RkRgaGetAllocBuffer(bo_t *bo_info, int width, int height, int bpp);
int RkRgaGetAllocBufferExt(bo_t *bo_info, int width, int height, int bpp, int flags);
int RkRgaGetAllocBufferCache(bo_t *bo_info, int width, int height, int bpp);
int RkRgaGetMmap(bo_t *bo_info);
int RkRgaUnmap(bo_t *bo_info);
int RkRgaFree(bo_t *bo_info);
int RkRgaGetBufferFd(bo_t *bo_info, int *fd);
#else
int RkRgaGetBufferFd(buffer_handle_t handle, int *fd);
int RkRgaGetHandleMapCpuAddress(buffer_handle_t handle, void **buf);
#endif
int RkRgaBlit(rga_info *src, rga_info *dst, rga_info *src1);
int RkRgaCollorFill(rga_info *dst);
int RkRgaCollorPalette(rga_info *src, rga_info *dst, rga_info *lut);
int RkRgaFlush();
void RkRgaSetLogOnceFlag(int log) {
mLogOnce = log;
}
void RkRgaSetAlwaysLogFlag(bool log) {
mLogAlways = log;
}
void RkRgaLogOutRgaReq(struct rga_req rgaReg);
int RkRgaLogOutUserPara(rga_info *rgaInfo);
inline bool RkRgaIsReady() {
return mSupportRga;
}
RockchipRga();
~RockchipRga();
private:
bool mSupportRga;
int mLogOnce;
int mLogAlways;
void * mContext;
friend class Singleton<RockchipRga>;
};
#ifdef ANDROID
}; // namespace android
#endif
#endif

View File

@ -0,0 +1,362 @@
/*
* Copyright (C) 2016 Rockchip Electronics Co., Ltd.
* Authors:
* Zhiqin Wei <wzq@rock-chips.com>
*
* 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 _rk_drm_rga_
#define _rk_drm_rga_
#include <stdint.h>
#include <errno.h>
#include <sys/cdefs.h>
#include "rga.h"
#ifdef ANDROID
#define DRMRGA_HARDWARE_MODULE_ID "librga"
#include <hardware/gralloc.h>
#include <hardware/hardware.h>
#include <system/graphics.h>
#include <cutils/native_handle.h>
#if defined(ANDROID_12) || defined(USE_HARDWARE_ROCKCHIP)
#include <hardware/hardware_rockchip.h>
#endif
#endif
#define RGA_BLIT_SYNC 0x5017
#define RGA_BLIT_ASYNC 0x5018
#ifndef ANDROID /* LINUX */
/* flip source image horizontally (around the vertical axis) */
#define HAL_TRANSFORM_FLIP_H 0x01
/* flip source image vertically (around the horizontal axis)*/
#define HAL_TRANSFORM_FLIP_V 0x02
/* rotate source image 90 degrees clockwise */
#define HAL_TRANSFORM_ROT_90 0x04
/* rotate source image 180 degrees */
#define HAL_TRANSFORM_ROT_180 0x03
/* rotate source image 270 degrees clockwise */
#define HAL_TRANSFORM_ROT_270 0x07
#endif
#define HAL_TRANSFORM_FLIP_H_V 0x08
/*****************************************************************************/
/* for compatibility */
#define DRM_RGA_MODULE_API_VERSION HWC_MODULE_API_VERSION_0_1
#define DRM_RGA_DEVICE_API_VERSION HWC_DEVICE_API_VERSION_0_1
#define DRM_RGA_API_VERSION HWC_DEVICE_API_VERSION
#define DRM_RGA_TRANSFORM_ROT_MASK 0x0000000F
#define DRM_RGA_TRANSFORM_ROT_0 0x00000000
#define DRM_RGA_TRANSFORM_ROT_90 HAL_TRANSFORM_ROT_90
#define DRM_RGA_TRANSFORM_ROT_180 HAL_TRANSFORM_ROT_180
#define DRM_RGA_TRANSFORM_ROT_270 HAL_TRANSFORM_ROT_270
#define DRM_RGA_TRANSFORM_FLIP_MASK 0x00000003
#define DRM_RGA_TRANSFORM_FLIP_H HAL_TRANSFORM_FLIP_H
#define DRM_RGA_TRANSFORM_FLIP_V HAL_TRANSFORM_FLIP_V
enum {
AWIDTH = 0,
AHEIGHT,
ASTRIDE,
AFORMAT,
ASIZE,
ATYPE,
};
/*****************************************************************************/
#ifndef ANDROID /* LINUX */
/* memory type definitions. */
enum drm_rockchip_gem_mem_type {
/* Physically Continuous memory and used as default. */
ROCKCHIP_BO_CONTIG = 1 << 0,
/* cachable mapping. */
ROCKCHIP_BO_CACHABLE = 1 << 1,
/* write-combine mapping. */
ROCKCHIP_BO_WC = 1 << 2,
ROCKCHIP_BO_SECURE = 1 << 3,
ROCKCHIP_BO_MASK = ROCKCHIP_BO_CONTIG | ROCKCHIP_BO_CACHABLE |
ROCKCHIP_BO_WC | ROCKCHIP_BO_SECURE
};
typedef struct bo {
int fd;
void *ptr;
size_t size;
size_t offset;
size_t pitch;
unsigned handle;
} bo_t;
#endif
/*
@value size: user not need care about.For avoid read/write out of memory
*/
typedef struct rga_rect {
int xoffset;
int yoffset;
int width;
int height;
int wstride;
int hstride;
int format;
int size;
} rga_rect_t;
typedef struct rga_nn {
int nn_flag;
int scale_r;
int scale_g;
int scale_b;
int offset_r;
int offset_g;
int offset_b;
} rga_nn_t;
typedef struct rga_dither {
int enable;
int mode;
int lut0_l;
int lut0_h;
int lut1_l;
int lut1_h;
} rga_dither_t;
struct rga_mosaic_info {
uint8_t enable;
uint8_t mode;
};
struct rga_pre_intr_info {
uint8_t enable;
uint8_t read_intr_en;
uint8_t write_intr_en;
uint8_t read_hold_en;
uint32_t read_threshold;
uint32_t write_start;
uint32_t write_step;
};
/* MAX(min, (max - channel_value)) */
struct rga_osd_invert_factor {
uint8_t alpha_max;
uint8_t alpha_min;
uint8_t yg_max;
uint8_t yg_min;
uint8_t crb_max;
uint8_t crb_min;
};
struct rga_color {
union {
struct {
uint8_t red;
uint8_t green;
uint8_t blue;
uint8_t alpha;
};
uint32_t value;
};
};
struct rga_osd_bpp2 {
uint8_t ac_swap; // ac swap flag
// 0: CA
// 1: AC
uint8_t endian_swap; // rgba2bpp endian swap
// 0: Big endian
// 1: Little endian
struct rga_color color0;
struct rga_color color1;
};
struct rga_osd_mode_ctrl {
uint8_t mode; // OSD cal mode:
// 0b'1: statistics mode
// 1b'1: auto inversion overlap mode
uint8_t direction_mode; // horizontal or vertical
// 0: horizontal
// 1: vertical
uint8_t width_mode; // using @fix_width or LUT width
// 0: fix width
// 1: LUT width
uint16_t block_fix_width; // OSD block fixed width
// real width = (fix_width + 1) * 2
uint8_t block_num; // OSD block num
uint16_t flags_index; // auto invert flags index
/* invertion config */
uint8_t color_mode; // selete color
// 0: src1 color
// 1: config data color
uint8_t invert_flags_mode; // invert flag selete
// 0: use RAM flag
// 1: usr last result
uint8_t default_color_sel; // default color mode
// 0: default is bright
// 1: default is dark
uint8_t invert_enable; // invert channel enable
// 1 << 0: aplha enable
// 1 << 1: Y/G disable
// 1 << 2: C/RB disable
uint8_t invert_mode; // invert cal mode
// 0: normal(max-data)
// 1: swap
uint8_t invert_thresh; // if luma > thresh, osd_flag to be 1
uint8_t unfix_index; // OSD width config index
};
struct rga_osd_info {
uint8_t enable;
struct rga_osd_mode_ctrl mode_ctrl;
struct rga_osd_invert_factor cal_factor;
struct rga_osd_bpp2 bpp2_info;
union {
struct {
uint32_t last_flags1;
uint32_t last_flags0;
};
uint64_t last_flags;
};
union {
struct {
uint32_t cur_flags1;
uint32_t cur_flags0;
};
uint64_t cur_flags;
};
};
/*
@value fd: use fd to share memory, it can be ion shard fd,and dma fd.
@value virAddr:userspace address
@value phyAddr:use phy address
@value hnd: use buffer_handle_t
*/
typedef struct rga_info {
int fd;
void *virAddr;
void *phyAddr;
#ifndef ANDROID /* LINUX */
unsigned hnd;
#else /* Android */
buffer_handle_t hnd;
#endif
int format;
rga_rect_t rect;
unsigned int blend;
int bufferSize;
int rotation;
int color;
int testLog;
int mmuFlag;
int colorkey_en;
int colorkey_mode;
int colorkey_max;
int colorkey_min;
int scale_mode;
int color_space_mode;
int sync_mode;
rga_nn_t nn;
rga_dither_t dither;
int rop_code;
int rd_mode;
unsigned short is_10b_compact;
unsigned short is_10b_endian;
int in_fence_fd;
int out_fence_fd;
int core;
int priority;
unsigned short enable;
int handle;
struct rga_mosaic_info mosaic_info;
struct rga_osd_info osd_info;
struct rga_pre_intr_info pre_intr;
int mpi_mode;
union {
int ctx_id;
int job_handle;
};
uint16_t rgba5551_flags;
uint8_t rgba5551_alpha0;
uint8_t rgba5551_alpha1;
char reserve[398];
} rga_info_t;
typedef struct drm_rga {
rga_rect_t src;
rga_rect_t dst;
} drm_rga_t;
/*
@fun rga_set_rect:For use to set the rects esayly
@param rect:The rect user want to set,like setting the src rect:
drm_rga_t rects;
rga_set_rect(rects.src,0,0,1920,1080,1920,NV12);
mean to set the src rect to the value.
*/
static inline int rga_set_rect(rga_rect_t *rect,
int x, int y, int w, int h, int sw, int sh, int f) {
if (!rect)
return -EINVAL;
rect->xoffset = x;
rect->yoffset = y;
rect->width = w;
rect->height = h;
rect->wstride = sw;
rect->hstride = sh;
rect->format = f;
return 0;
}
#ifndef ANDROID /* LINUX */
static inline void rga_set_rotation(rga_info_t *info, int angle) {
if (angle == 90)
info->rotation = HAL_TRANSFORM_ROT_90;
else if (angle == 180)
info->rotation = HAL_TRANSFORM_ROT_180;
else if (angle == 270)
info->rotation = HAL_TRANSFORM_ROT_270;
}
#endif
/*****************************************************************************/
#endif

View File

@ -0,0 +1,32 @@
/*
* Copyright (C) 2020 Rockchip Electronics Co., Ltd.
* Authors:
* PutinLee <putin.lee@rock-chips.com>
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_h_
#define _im2d_h_
#include "im2d_version.h"
#include "im2d_type.h"
#include "im2d_common.h"
#include "im2d_buffer.h"
#include "im2d_single.h"
#include "im2d_task.h"
#include "im2d_mpi.h"
#endif /* #ifndef _im2d_h_ */

View File

@ -0,0 +1,27 @@
/*
* Copyright (C) 2020 Rockchip Electronics Co., Ltd.
* Authors:
* PutinLee <putin.lee@rock-chips.com>
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_hpp_
#define _im2d_hpp_
#include "im2d.h"
#include "im2d_expand.h"
#endif /* #ifndef _im2d_hpp_ */

View File

@ -0,0 +1,183 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_buffer_h_
#define _im2d_buffer_h_
#include "im2d_type.h"
/**
* Import external buffers into RGA driver.
*
* @param fd/va/pa
* Select dma_fd/virtual_address/physical_address by buffer type
* @param size
* Describes the size of the image buffer
*
* @return rga_buffer_handle_t
*/
#ifdef __cplusplus
IM_API rga_buffer_handle_t importbuffer_fd(int fd, int size);
IM_API rga_buffer_handle_t importbuffer_virtualaddr(void *va, int size);
IM_API rga_buffer_handle_t importbuffer_physicaladdr(uint64_t pa, int size);
#endif
/**
* Import external buffers into RGA driver.
*
* @param fd/va/pa
* Select dma_fd/virtual_address/physical_address by buffer type
* @param width
* Describes the pixel width stride of the image buffer
* @param height
* Describes the pixel height stride of the image buffer
* @param format
* Describes the pixel format of the image buffer
*
* @return rga_buffer_handle_t
*/
#ifdef __cplusplus
IM_API rga_buffer_handle_t importbuffer_fd(int fd, int width, int height, int format);
IM_API rga_buffer_handle_t importbuffer_virtualaddr(void *va, int width, int height, int format);
IM_API rga_buffer_handle_t importbuffer_physicaladdr(uint64_t pa, int width, int height, int format);
#endif
/**
* Import external buffers into RGA driver.
*
* @param fd/va/pa
* Select dma_fd/virtual_address/physical_address by buffer type
* @param param
* Configure buffer parameters
*
* @return rga_buffer_handle_t
*/
IM_EXPORT_API rga_buffer_handle_t importbuffer_fd(int fd, im_handle_param_t *param);
IM_EXPORT_API rga_buffer_handle_t importbuffer_virtualaddr(void *va, im_handle_param_t *param);
IM_EXPORT_API rga_buffer_handle_t importbuffer_physicaladdr(uint64_t pa, im_handle_param_t *param);
/**
* Import external buffers into RGA driver.
*
* @param handle
* rga buffer handle
*
* @return success or else negative error code.
*/
IM_EXPORT_API IM_STATUS releasebuffer_handle(rga_buffer_handle_t handle);
/**
* Wrap image Parameters.
*
* @param handle/virtualaddr/physicaladdr/fd
* RGA buffer handle/virtualaddr/physicaladdr/fd.
* @param width
* Width of image manipulation area.
* @param height
* Height of image manipulation area.
* @param wstride
* Width pixel stride, default (width = wstride).
* @param hstride
* Height pixel stride, default (height = hstride).
* @param format
* Image format.
*
* @return rga_buffer_t
*/
#define wrapbuffer_handle(handle, width, height, format, ...) \
({ \
rga_buffer_t im2d_api_buffer; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
im2d_api_buffer = wrapbuffer_handle_t(handle, width, height, width, height, format); \
} else if (__argc == 2){ \
im2d_api_buffer = wrapbuffer_handle_t(handle, width, height, __args[0], __args[1], format); \
} else { \
memset(&im2d_api_buffer, 0x0, sizeof(im2d_api_buffer)); \
printf("invalid parameter\n"); \
} \
im2d_api_buffer; \
})
#define wrapbuffer_virtualaddr(vir_addr, width, height, format, ...) \
({ \
rga_buffer_t im2d_api_buffer; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
im2d_api_buffer = wrapbuffer_virtualaddr_t(vir_addr, width, height, width, height, format); \
} else if (__argc == 2){ \
im2d_api_buffer = wrapbuffer_virtualaddr_t(vir_addr, width, height, __args[0], __args[1], format); \
} else { \
memset(&im2d_api_buffer, 0x0, sizeof(im2d_api_buffer)); \
printf("invalid parameter\n"); \
} \
im2d_api_buffer; \
})
#define wrapbuffer_physicaladdr(phy_addr, width, height, format, ...) \
({ \
rga_buffer_t im2d_api_buffer; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
im2d_api_buffer = wrapbuffer_physicaladdr_t(phy_addr, width, height, width, height, format); \
} else if (__argc == 2){ \
im2d_api_buffer = wrapbuffer_physicaladdr_t(phy_addr, width, height, __args[0], __args[1], format); \
} else { \
memset(&im2d_api_buffer, 0x0, sizeof(im2d_api_buffer)); \
printf("invalid parameter\n"); \
} \
im2d_api_buffer; \
})
#define wrapbuffer_fd(fd, width, height, format, ...) \
({ \
rga_buffer_t im2d_api_buffer; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
im2d_api_buffer = wrapbuffer_fd_t(fd, width, height, width, height, format); \
} else if (__argc == 2){ \
im2d_api_buffer = wrapbuffer_fd_t(fd, width, height, __args[0], __args[1], format); \
} else { \
memset(&im2d_api_buffer, 0x0, sizeof(im2d_api_buffer)); \
printf("invalid parameter\n"); \
} \
im2d_api_buffer; \
})
/* Symbols for define *_t functions */
IM_C_API rga_buffer_t wrapbuffer_handle_t(rga_buffer_handle_t handle, int width, int height, int wstride, int hstride, int format);
IM_C_API rga_buffer_t wrapbuffer_virtualaddr_t(void* vir_addr, int width, int height, int wstride, int hstride, int format);
IM_C_API rga_buffer_t wrapbuffer_physicaladdr_t(void* phy_addr, int width, int height, int wstride, int hstride, int format);
IM_C_API rga_buffer_t wrapbuffer_fd_t(int fd, int width, int height, int wstride, int hstride, int format);
#ifdef __cplusplus
#undef wrapbuffer_handle
IM_API rga_buffer_t wrapbuffer_handle(rga_buffer_handle_t handle,
int width, int height, int format);
IM_API rga_buffer_t wrapbuffer_handle(rga_buffer_handle_t handle,
int width, int height, int format,
int wstride, int hstride);
#endif
void imsetAlphaBit(rga_buffer_t *buf, uint8_t alpha0, uint8_t alpha1);
void imsetOpacity(rga_buffer_t *buf, uint8_t alpha);
void imsetColorSpace(rga_buffer_t *buf, IM_COLOR_SPACE_MODE mode);
#endif /* #ifndef _im2d_buffer_h_ */

View File

@ -0,0 +1,151 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_common_h_
#define _im2d_common_h_
#include "im2d_type.h"
/**
* Query RGA basic information, supported resolution, supported format, etc.
*
* @param name
* RGA_VENDOR
* RGA_VERSION
* RGA_MAX_INPUT
* RGA_MAX_OUTPUT
* RGA_INPUT_FORMAT
* RGA_OUTPUT_FORMAT
* RGA_EXPECTED
* RGA_ALL
*
* @returns a string describing properties of RGA.
*/
IM_EXPORT_API const char* querystring(int name);
/**
* String to output the error message
*
* @param status
* process result value.
*
* @returns error message.
*/
#define imStrError(...) \
({ \
const char* im2d_api_err; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
im2d_api_err = imStrError_t(IM_STATUS_INVALID_PARAM); \
} else if (__argc == 1){ \
im2d_api_err = imStrError_t((IM_STATUS)__args[0]); \
} else { \
im2d_api_err = ("Fatal error, imStrError() too many parameters\n"); \
printf("Fatal error, imStrError() too many parameters\n"); \
} \
im2d_api_err; \
})
IM_C_API const char* imStrError_t(IM_STATUS status);
/**
* check im2d api header file
*
* @param header_version
* Default is RGA_CURRENT_API_HEADER_VERSION, no need to change if there are no special cases.
*
* @returns no error or else negative error code.
*/
#ifdef __cplusplus
IM_API IM_STATUS imcheckHeader(im_api_version_t header_version = RGA_CURRENT_API_HEADER_VERSION);
#endif
/**
* check RGA basic information, supported resolution, supported format, etc.
*
* @param src
* @param dst
* @param pat
* @param src_rect
* @param dst_rect
* @param pat_rect
* @param mode_usage
*
* @returns no error or else negative error code.
*/
#define imcheck(src, dst, src_rect, dst_rect, ...) \
({ \
IM_STATUS __ret = IM_STATUS_NOERROR; \
rga_buffer_t __pat; \
im_rect __pat_rect; \
memset(&__pat, 0, sizeof(rga_buffer_t)); \
memset(&__pat_rect, 0, sizeof(im_rect)); \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imcheck_t(src, dst, __pat, src_rect, dst_rect, __pat_rect, 0); \
} else if (__argc == 1){ \
__ret = imcheck_t(src, dst, __pat, src_rect, dst_rect, __pat_rect, __args[0]); \
} else { \
__ret = IM_STATUS_FAILED; \
printf("check failed\n"); \
} \
__ret; \
})
#define imcheck_composite(src, dst, pat, src_rect, dst_rect, pat_rect, ...) \
({ \
IM_STATUS __ret = IM_STATUS_NOERROR; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imcheck_t(src, dst, pat, src_rect, dst_rect, pat_rect, 0); \
} else if (__argc == 1){ \
__ret = imcheck_t(src, dst, pat, src_rect, dst_rect, pat_rect, __args[0]); \
} else { \
__ret = IM_STATUS_FAILED; \
printf("check failed\n"); \
} \
__ret; \
})
IM_C_API IM_STATUS imcheck_t(const rga_buffer_t src, const rga_buffer_t dst, const rga_buffer_t pat,
const im_rect src_rect, const im_rect dst_rect, const im_rect pat_rect, const int mode_usage);
/* Compatible with the legacy symbol */
IM_C_API void rga_check_perpare(rga_buffer_t *src, rga_buffer_t *dst, rga_buffer_t *pat,
im_rect *src_rect, im_rect *dst_rect, im_rect *pat_rect, int mode_usage);
/**
* block until all execution is complete
*
* @param release_fence_fd
* RGA job release fence fd
*
* @returns success or else negative error code.
*/
IM_EXPORT_API IM_STATUS imsync(int release_fence_fd);
/**
* config
*
* @param name
* enum IM_CONFIG_NAME
* @param value
*
* @returns success or else negative error code.
*/
IM_EXPORT_API IM_STATUS imconfig(IM_CONFIG_NAME name, uint64_t value);
#endif /* #ifndef _im2d_common_h_ */

View File

@ -0,0 +1,47 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_expand_h_
#define _im2d_expand_h_
#ifdef __cplusplus
#include "im2d_type.h"
#if ANDROID
#include <ui/GraphicBuffer.h>
using namespace android;
IM_API rga_buffer_handle_t importbuffer_GraphicBuffer_handle(buffer_handle_t hnd);
IM_API rga_buffer_handle_t importbuffer_GraphicBuffer(sp<GraphicBuffer> buf);
IM_API rga_buffer_t wrapbuffer_handle(buffer_handle_t hnd);
IM_API rga_buffer_t wrapbuffer_GraphicBuffer(sp<GraphicBuffer> buf);
#if USE_AHARDWAREBUFFER
#include <android/hardware_buffer.h>
IM_API rga_buffer_handle_t importbuffer_AHardwareBuffer(AHardwareBuffer *buf);
IM_API rga_buffer_t wrapbuffer_AHardwareBuffer(AHardwareBuffer *buf);
#endif /* #if USE_AHARDWAREBUFFER */
#endif /* #if ANDROID */
#endif /* #ifdef __cplusplus */
#endif

View File

@ -0,0 +1,80 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_mpi_hpp_
#define _im2d_mpi_hpp_
#include "im2d_type.h"
/**
* Create and config an rga ctx for rockit-ko
*
* @param flags
* Some configuration flags for this job
*
* @returns job id.
*/
IM_EXPORT_API im_ctx_id_t imbegin(uint32_t flags);
/**
* Cancel and delete an rga ctx for rockit-ko
*
* @param flags
* Some configuration flags for this job
*
* @returns success or else negative error code.
*/
IM_EXPORT_API IM_STATUS imcancel(im_ctx_id_t id);
/**
* process for rockit-ko
*
* @param src
* The input source image and is also the foreground image in blend.
* @param dst
* The output destination image and is also the foreground image in blend.
* @param pat
* The foreground image, or a LUT table.
* @param srect
* The rectangle on the src channel image that needs to be processed.
* @param drect
* The rectangle on the dst channel image that needs to be processed.
* @param prect
* The rectangle on the pat channel image that needs to be processed.
* @param acquire_fence_fd
* @param release_fence_fd
* @param opt
* The image processing options configuration.
* @param usage
* The image processing usage.
* @param ctx_id
* ctx id
*
* @returns success or else negative error code.
*/
#ifdef __cplusplus
IM_API IM_STATUS improcess(rga_buffer_t src, rga_buffer_t dst, rga_buffer_t pat,
im_rect srect, im_rect drect, im_rect prect,
int acquire_fence_fd, int *release_fence_fd,
im_opt_t *opt, int usage, im_ctx_id_t ctx_id);
#endif
IM_EXPORT_API IM_STATUS improcess_ctx(rga_buffer_t src, rga_buffer_t dst, rga_buffer_t pat,
im_rect srect, im_rect drect, im_rect prect,
int acquire_fence_fd, int *release_fence_fd,
im_opt_t *opt, int usage, im_ctx_id_t ctx_id);
#endif /* #ifndef _im2d_mpi_hpp_ */

View File

@ -0,0 +1,940 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_single_h_
#define _im2d_single_h_
#include "im2d_type.h"
#ifdef __cplusplus
/**
* copy
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcopy(const rga_buffer_t src, rga_buffer_t dst, int sync = 1, int *release_fence_fd = NULL);
/**
* Resize
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param fx
* X-direction resize factor.
* @param fy
* X-direction resize factor.
* @param interpolation
* Interpolation formula(Only RGA1 support).
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imresize(const rga_buffer_t src, rga_buffer_t dst, double fx = 0, double fy = 0, int interpolation = 0, int sync = 1, int *release_fence_fd = NULL);
/**
* Crop
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be cropped.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcrop(const rga_buffer_t src, rga_buffer_t dst, im_rect rect, int sync = 1, int *release_fence_fd = NULL);
/**
* translate
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param x
* Output the coordinates of the starting point in the X-direction of the destination image.
* @param y
* Output the coordinates of the starting point in the Y-direction of the destination image.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imtranslate(const rga_buffer_t src, rga_buffer_t dst, int x, int y, int sync = 1, int *release_fence_fd = NULL);
/**
* format convert
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param sfmt
* The source image format.
* @param dfmt
* The destination image format.
* @param mode
* color space mode:
* IM_YUV_TO_RGB_BT601_LIMIT
* IM_YUV_TO_RGB_BT601_FULL
* IM_YUV_TO_RGB_BT709_LIMIT
* IM_RGB_TO_YUV_BT601_FULL
* IM_RGB_TO_YUV_BT601_LIMIT
* IM_RGB_TO_YUV_BT709_LIMIT
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcvtcolor(rga_buffer_t src, rga_buffer_t dst, int sfmt, int dfmt, int mode = IM_COLOR_SPACE_DEFAULT, int sync = 1, int *release_fence_fd = NULL);
/**
* rotation
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param rotation
* IM_HAL_TRANSFORM_ROT_90
* IM_HAL_TRANSFORM_ROT_180
* IM_HAL_TRANSFORM_ROT_270
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imrotate(const rga_buffer_t src, rga_buffer_t dst, int rotation, int sync = 1, int *release_fence_fd = NULL);
/**
* flip
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param mode
* IM_HAL_TRANSFORM_FLIP_H
* IM_HAL_TRANSFORM_FLIP_V
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imflip(const rga_buffer_t src, rga_buffer_t dst, int mode, int sync = 1, int *release_fence_fd = NULL);
/**
* 2-channel blend (SRC + DST -> DST or SRCA + SRCB -> DST)
*
* @param fg_image
* The foreground image.
* @param bg_image
* The background image, which is also the output destination image.
* @param mode
* Port-Duff mode:
* IM_ALPHA_BLEND_SRC
* IM_ALPHA_BLEND_DST
* IM_ALPHA_BLEND_SRC_OVER
* IM_ALPHA_BLEND_DST_OVER
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imblend(const rga_buffer_t fd_image, rga_buffer_t bg_image, int mode = IM_ALPHA_BLEND_SRC_OVER, int sync = 1, int *release_fence_fd = NULL);
/**
* 3-channel blend (SRC + DST -> DST or SRCA + SRCB -> DST)
*
* @param fg_image
* The foreground image.
* @param bg_image
* The background image.
* @param output_image
* The output destination image.
* @param mode
* Port-Duff mode:
* IM_ALPHA_BLEND_SRC
* IM_ALPHA_BLEND_DST
* IM_ALPHA_BLEND_SRC_OVER
* IM_ALPHA_BLEND_DST_OVER
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
* @param release_fence_fd
* When 'sync == 0', the fence_fd used to identify the current job state
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcomposite(const rga_buffer_t srcA, const rga_buffer_t srcB, rga_buffer_t dst, int mode = IM_ALPHA_BLEND_SRC_OVER, int sync = 1, int *release_fence_fd = NULL);
/**
* color key
*
* @param fg_image
* The foreground image.
* @param bg_image
* The background image, which is also the output destination image.
* @param colorkey_range
* The range of color key.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcolorkey(const rga_buffer_t src, rga_buffer_t dst, im_colorkey_range range, int mode = IM_ALPHA_COLORKEY_NORMAL, int sync = 1, int *release_fence_fd = NULL);
/**
* OSD
*
* @param osd
* The osd text block.
* @param dst
* The background image.
* @param osd_rect
* The rectangle on the source image that needs to be OSD.
* @param osd_config
* osd mode configuration.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imosd(const rga_buffer_t osd,const rga_buffer_t dst,
const im_rect osd_rect, im_osd_t *osd_config,
int sync = 1, int *release_fence_fd = NULL);
/**
* nn quantize
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param nninfo
* nn configuration
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imquantize(const rga_buffer_t src, rga_buffer_t dst, im_nn_t nn_info, int sync = 1, int *release_fence_fd = NULL);
/**
* ROP
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param rop_code
* The ROP opcode.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imrop(const rga_buffer_t src, rga_buffer_t dst, int rop_code, int sync = 1, int *release_fence_fd = NULL);
/**
* fill/reset/draw
*
* @param dst
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be filled with color.
* @param color
* The fill color value.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imfill(rga_buffer_t dst, im_rect rect, int color, int sync = 1, int *release_fence_fd = NULL);
/**
* fill array
*
* @param dst
* The output destination image.
* @param rect_array
* The rectangle arrays on the source image that needs to be filled with color.
* @param array_size
* The size of rectangular area arrays.
* @param color
* The fill color value.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imfillArray(rga_buffer_t dst, im_rect *rect_array, int array_size, uint32_t color, int sync = 1, int *release_fence_fd = NULL);
/**
* fill rectangle
*
* @param dst
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be filled with color.
* @param color
* The fill color value.
* @param thickness
* Thickness of lines that make up the rectangle. Negative values, like -1,
* mean that the function has to draw a filled rectangle.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imrectangle(rga_buffer_t dst, im_rect rect,
uint32_t color, int thickness,
int sync = 1, int *release_fence_fd = NULL);
/**
* fill rectangle array
*
* @param dst
* The output destination image.
* @param rect_array
* The rectangle arrays on the source image that needs to be filled with color.
* @param array_size
* The size of rectangular area arrays.
* @param color
* The fill color value.
* @param thickness
* Thickness of lines that make up the rectangle. Negative values, like -1,
* mean that the function has to draw a filled rectangle.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imrectangleArray(rga_buffer_t dst, im_rect *rect_array, int array_size,
uint32_t color, int thickness,
int sync = 1, int *release_fence_fd = NULL);
/**
* MOSAIC
*
* @param image
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be mosaicked.
* @param mosaic_mode
* mosaic block width configuration:
* IM_MOSAIC_8
* IM_MOSAIC_16
* IM_MOSAIC_32
* IM_MOSAIC_64
* IM_MOSAIC_128
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS immosaic(const rga_buffer_t image, im_rect rect, int mosaic_mode, int sync = 1, int *release_fence_fd = NULL);
/**
* MOSAIC array
*
* @param image
* The output destination image.
* @param rect_array
* The rectangle arrays on the source image that needs to be filled with color.
* @param array_size
* The size of rectangular area arrays.
* @param mosaic_mode
* mosaic block width configuration:
* IM_MOSAIC_8
* IM_MOSAIC_16
* IM_MOSAIC_32
* IM_MOSAIC_64
* IM_MOSAIC_128
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS immosaicArray(const rga_buffer_t image, im_rect *rect_array, int array_size, int mosaic_mode, int sync = 1, int *release_fence_fd = NULL);
/**
* palette
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param lut
* The LUT table.
* @param sync
* When 'sync == 1', wait for the operation to complete and return, otherwise return directly.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS impalette(rga_buffer_t src, rga_buffer_t dst, rga_buffer_t lut, int sync = 1, int *release_fence_fd = NULL);
/**
* process for single task mode
*
* @param src
* The input source image and is also the foreground image in blend.
* @param dst
* The output destination image and is also the foreground image in blend.
* @param pat
* The foreground image, or a LUT table.
* @param srect
* The rectangle on the src channel image that needs to be processed.
* @param drect
* The rectangle on the dst channel image that needs to be processed.
* @param prect
* The rectangle on the pat channel image that needs to be processed.
* @param opt
* The image processing options configuration.
* @param usage
* The image processing usage.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS improcess(rga_buffer_t src, rga_buffer_t dst, rga_buffer_t pat,
im_rect srect, im_rect drect, im_rect prect,
int acquire_fence_fd, int *release_fence_fd,
im_opt_t *opt_ptr, int usage);
/**
* make border
*
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param top
* the top pixels
* @param bottom
* the bottom pixels
* @param left
* the left pixels
* @param right
* the right pixels
* @param border_type
* Border type.
* @param value
* The pixel value at which the border is filled.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS immakeBorder(rga_buffer_t src, rga_buffer_t dst,
int top, int bottom, int left, int right,
int border_type, int value = 0,
int sync = 1, int acquir_fence_fd = -1, int *release_fence_fd = NULL);
#endif /* #ifdef __cplusplus */
IM_C_API IM_STATUS immosaic(const rga_buffer_t image, im_rect rect, int mosaic_mode, int sync);
IM_C_API IM_STATUS imosd(const rga_buffer_t osd,const rga_buffer_t dst,
const im_rect osd_rect, im_osd_t *osd_config, int sync);
IM_C_API IM_STATUS improcess(rga_buffer_t src, rga_buffer_t dst, rga_buffer_t pat,
im_rect srect, im_rect drect, im_rect prect, int usage);
/* Start: Symbols reserved for compatibility with macro functions */
IM_C_API IM_STATUS imcopy_t(const rga_buffer_t src, rga_buffer_t dst, int sync);
IM_C_API IM_STATUS imresize_t(const rga_buffer_t src, rga_buffer_t dst, double fx, double fy, int interpolation, int sync);
IM_C_API IM_STATUS imcrop_t(const rga_buffer_t src, rga_buffer_t dst, im_rect rect, int sync);
IM_C_API IM_STATUS imtranslate_t(const rga_buffer_t src, rga_buffer_t dst, int x, int y, int sync);
IM_C_API IM_STATUS imcvtcolor_t(rga_buffer_t src, rga_buffer_t dst, int sfmt, int dfmt, int mode, int sync);
IM_C_API IM_STATUS imrotate_t(const rga_buffer_t src, rga_buffer_t dst, int rotation, int sync);
IM_C_API IM_STATUS imflip_t (const rga_buffer_t src, rga_buffer_t dst, int mode, int sync);
IM_C_API IM_STATUS imblend_t(const rga_buffer_t srcA, const rga_buffer_t srcB, rga_buffer_t dst, int mode, int sync);
IM_C_API IM_STATUS imcolorkey_t(const rga_buffer_t src, rga_buffer_t dst, im_colorkey_range range, int mode, int sync);
IM_C_API IM_STATUS imquantize_t(const rga_buffer_t src, rga_buffer_t dst, im_nn_t nn_info, int sync);
IM_C_API IM_STATUS imrop_t(const rga_buffer_t src, rga_buffer_t dst, int rop_code, int sync);
IM_C_API IM_STATUS imfill_t(rga_buffer_t dst, im_rect rect, int color, int sync);
IM_C_API IM_STATUS impalette_t(rga_buffer_t src, rga_buffer_t dst, rga_buffer_t lut, int sync);
/* End: Symbols reserved for compatibility with macro functions */
#ifndef __cplusplus
#define RGA_GET_MIN(n1, n2) ((n1) < (n2) ? (n1) : (n2))
/**
* copy
*
* @param src
* @param dst
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imcopy(src, dst, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imcopy_t(src, dst, 1); \
} else if (__argc == 1){ \
__ret = imcopy_t(src, dst, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* Resize
*
* @param src
* @param dst
* @param fx
* @param fy
* @param interpolation
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imresize(src, dst, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
double __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(double); \
if (__argc == 0) { \
__ret = imresize_t(src, dst, 0, 0, INTER_LINEAR, 1); \
} else if (__argc == 2){ \
__ret = imresize_t(src, dst, __args[RGA_GET_MIN(__argc, 0)], __args[RGA_GET_MIN(__argc, 1)], INTER_LINEAR, 1); \
} else if (__argc == 3){ \
__ret = imresize_t(src, dst, __args[RGA_GET_MIN(__argc, 0)], __args[RGA_GET_MIN(__argc, 1)], (int)__args[RGA_GET_MIN(__argc, 2)], 1); \
} else if (__argc == 4){ \
__ret = imresize_t(src, dst, __args[RGA_GET_MIN(__argc, 0)], __args[RGA_GET_MIN(__argc, 1)], (int)__args[RGA_GET_MIN(__argc, 2)], (int)__args[RGA_GET_MIN(__argc, 3)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
#define impyramid(src, dst, direction) \
imresize_t(src, \
dst, \
direction == IM_UP_SCALE ? 0.5 : 2, \
direction == IM_UP_SCALE ? 0.5 : 2, \
INTER_LINEAR, 1)
/**
* format convert
*
* @param src
* @param dst
* @param sfmt
* @param dfmt
* @param mode
* color space mode: IM_COLOR_SPACE_MODE
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imcvtcolor(src, dst, sfmt, dfmt, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imcvtcolor_t(src, dst, sfmt, dfmt, IM_COLOR_SPACE_DEFAULT, 1); \
} else if (__argc == 1){ \
__ret = imcvtcolor_t(src, dst, sfmt, dfmt, (int)__args[RGA_GET_MIN(__argc, 0)], 1); \
} else if (__argc == 2){ \
__ret = imcvtcolor_t(src, dst, sfmt, dfmt, (int)__args[RGA_GET_MIN(__argc, 0)], (int)__args[RGA_GET_MIN(__argc, 1)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* Crop
*
* @param src
* @param dst
* @param rect
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imcrop(src, dst, rect, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imcrop_t(src, dst, rect, 1); \
} else if (__argc == 1){ \
__ret = imcrop_t(src, dst, rect, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* translate
*
* @param src
* @param dst
* @param x
* @param y
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imtranslate(src, dst, x, y, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imtranslate_t(src, dst, x, y, 1); \
} else if (__argc == 1){ \
__ret = imtranslate_t(src, dst, x, y, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* rotation
*
* @param src
* @param dst
* @param rotation
* IM_HAL_TRANSFORM_ROT_90
* IM_HAL_TRANSFORM_ROT_180
* IM_HAL_TRANSFORM_ROT_270
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imrotate(src, dst, rotation, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imrotate_t(src, dst, rotation, 1); \
} else if (__argc == 1){ \
__ret = imrotate_t(src, dst, rotation, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* flip
*
* @param src
* @param dst
* @param mode
* IM_HAL_TRANSFORM_FLIP_H
* IM_HAL_TRANSFORM_FLIP_V
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imflip(src, dst, mode, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imflip_t(src, dst, mode, 1); \
} else if (__argc == 1){ \
__ret = imflip_t(src, dst, mode, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* blend (SRC + DST -> DST or SRCA + SRCB -> DST)
*
* @param srcA
* @param srcB can be NULL.
* @param dst
* @param mode
* IM_ALPHA_BLEND_MODE
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imblend(srcA, dst, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
rga_buffer_t srcB; \
memset(&srcB, 0x00, sizeof(rga_buffer_t)); \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imblend_t(srcA, srcB, dst, IM_ALPHA_BLEND_SRC_OVER, 1); \
} else if (__argc == 1){ \
__ret = imblend_t(srcA, srcB, dst, (int)__args[RGA_GET_MIN(__argc, 0)], 1); \
} else if (__argc == 2){ \
__ret = imblend_t(srcA, srcB, dst, (int)__args[RGA_GET_MIN(__argc, 0)], (int)__args[RGA_GET_MIN(__argc, 1)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
#define imcomposite(srcA, srcB, dst, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imblend_t(srcA, srcB, dst, IM_ALPHA_BLEND_SRC_OVER, 1); \
} else if (__argc == 1){ \
__ret = imblend_t(srcA, srcB, dst, (int)__args[RGA_GET_MIN(__argc, 0)], 1); \
} else if (__argc == 2){ \
__ret = imblend_t(srcA, srcB, dst, (int)__args[RGA_GET_MIN(__argc, 0)], (int)__args[RGA_GET_MIN(__argc, 1)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* color key
*
* @param src
* @param dst
* @param colorkey_range
* max color
* min color
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imcolorkey(src, dst, range, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imcolorkey_t(src, dst, range, IM_ALPHA_COLORKEY_NORMAL, 1); \
} else if (__argc == 1){ \
__ret = imcolorkey_t(src, dst, range, (int)__args[RGA_GET_MIN(__argc, 0)], 1); \
} else if (__argc == 2){ \
__ret = imcolorkey_t(src, dst, range, (int)__args[RGA_GET_MIN(__argc, 0)], (int)__args[RGA_GET_MIN(__argc, 1)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* nn quantize
*
* @param src
* @param dst
* @param nninfo
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imquantize(src, dst, nn_info, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imquantize_t(src, dst, nn_info, 1); \
} else if (__argc == 1){ \
__ret = imquantize_t(src, dst, nn_info, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* ROP
*
* @param src
* @param dst
* @param rop_code
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imrop(src, dst, rop_code, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imrop_t(src, dst, rop_code, 1); \
} else if (__argc == 1){ \
__ret = imrop_t(src, dst, rop_code, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* fill/reset/draw
*
* @param src
* @param dst
* @param rect
* @param color
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define imfill(buf, rect, color, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imfill_t(buf, rect, color, 1); \
} else if (__argc == 1){ \
__ret = imfill_t(buf, rect, color, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
#define imreset(buf, rect, color, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imfill_t(buf, rect, color, 1); \
} else if (__argc == 1){ \
__ret = imfill_t(buf, rect, color, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
#define imdraw(buf, rect, color, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = imfill_t(buf, rect, color, 1); \
} else if (__argc == 1){ \
__ret = imfill_t(buf, rect, color, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/**
* palette
*
* @param src
* @param dst
* @param lut
* @param sync
* wait until operation complete
*
* @returns success or else negative error code.
*/
#define impalette(src, dst, lut, ...) \
({ \
IM_STATUS __ret = IM_STATUS_SUCCESS; \
int __args[] = {__VA_ARGS__}; \
int __argc = sizeof(__args)/sizeof(int); \
if (__argc == 0) { \
__ret = impalette_t(src, dst, lut, 1); \
} else if (__argc == 1){ \
__ret = impalette_t(src, dst, lut, (int)__args[RGA_GET_MIN(__argc, 0)]); \
} else { \
__ret = IM_STATUS_INVALID_PARAM; \
printf("invalid parameter\n"); \
} \
__ret; \
})
/* End define IM2D macro API */
#endif
#endif /* #ifndef _im2d_single_h_ */

View File

@ -0,0 +1,497 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _im2d_task_h_
#define _im2d_task_h_
#include "im2d_type.h"
#ifdef __cplusplus
/**
* Create an rga job
*
* @param flags
* Some configuration flags for this job
*
* @returns job handle.
*/
IM_API im_job_handle_t imbeginJob(uint64_t flags = 0);
/**
* Submit and run an rga job
*
* @param job_handle
* This is the job handle that will be submitted.
* @param sync_mode
* run mode:
* IM_SYNC
* IM_ASYNC
* @param acquire_fence_fd
* @param release_fence_fd
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imendJob(im_job_handle_t job_handle,
int sync_mode = IM_SYNC,
int acquire_fence_fd = 0, int *release_fence_fd = NULL);
/**
* Cancel and delete an rga job
*
* @param job_handle
* This is the job handle that will be cancelled.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcancelJob(im_job_handle_t job_handle);
/**
* Add copy task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcopyTask(im_job_handle_t job_handle, const rga_buffer_t src, rga_buffer_t dst);
/**
* Add resize task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param fx
* X-direction resize factor.
* @param fy
* X-direction resize factor.
* @param interpolation
* Interpolation formula(Only RGA1 support).
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imresizeTask(im_job_handle_t job_handle,
const rga_buffer_t src, rga_buffer_t dst,
double fx = 0, double fy = 0,
int interpolation = 0);
/**
* Add crop task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be cropped.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcropTask(im_job_handle_t job_handle,
const rga_buffer_t src, rga_buffer_t dst, im_rect rect);
/**
* Add translate task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param x
* Output the coordinates of the starting point in the X-direction of the destination image.
* @param y
* Output the coordinates of the starting point in the Y-direction of the destination image.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imtranslateTask(im_job_handle_t job_handle,
const rga_buffer_t src, rga_buffer_t dst, int x, int y);
/**
* Add format convert task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param sfmt
* The source image format.
* @param dfmt
* The destination image format.
* @param mode
* color space mode:
* IM_YUV_TO_RGB_BT601_LIMIT
* IM_YUV_TO_RGB_BT601_FULL
* IM_YUV_TO_RGB_BT709_LIMIT
* IM_RGB_TO_YUV_BT601_FULL
* IM_RGB_TO_YUV_BT601_LIMIT
* IM_RGB_TO_YUV_BT709_LIMIT
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcvtcolorTask(im_job_handle_t job_handle,
rga_buffer_t src, rga_buffer_t dst,
int sfmt, int dfmt, int mode = IM_COLOR_SPACE_DEFAULT);
/**
* Add rotation task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param rotation
* IM_HAL_TRANSFORM_ROT_90
* IM_HAL_TRANSFORM_ROT_180
* IM_HAL_TRANSFORM_ROT_270
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imrotateTask(im_job_handle_t job_handle,
const rga_buffer_t src, rga_buffer_t dst, int rotation);
/**
* Add flip task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param mode
* IM_HAL_TRANSFORM_FLIP_H
* IM_HAL_TRANSFORM_FLIP_V
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imflipTask(im_job_handle_t job_handle,
const rga_buffer_t src, rga_buffer_t dst, int mode);
/**
* Add blend(SRC + DST -> DST) task
*
* @param job_handle
* Insert the task into the job handle.
* @param fg_image
* The foreground image.
* @param bg_image
* The background image, which is also the output destination image.
* @param mode
* Port-Duff mode:
* IM_ALPHA_BLEND_SRC
* IM_ALPHA_BLEND_DST
* IM_ALPHA_BLEND_SRC_OVER
* IM_ALPHA_BLEND_DST_OVER
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imblendTask(im_job_handle_t job_handle,
const rga_buffer_t fg_image, rga_buffer_t bg_image,
int mode = IM_ALPHA_BLEND_SRC_OVER);
/**
* Add composite(SRCA + SRCB -> DST) task
*
* @param job_handle
* Insert the task into the job handle.
* @param fg_image
* The foreground image.
* @param bg_image
* The background image.
* @param output_image
* The output destination image.
* @param mode
* Port-Duff mode:
* IM_ALPHA_BLEND_SRC
* IM_ALPHA_BLEND_DST
* IM_ALPHA_BLEND_SRC_OVER
* IM_ALPHA_BLEND_DST_OVER
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcompositeTask(im_job_handle_t job_handle,
const rga_buffer_t fg_image, const rga_buffer_t bg_image,
rga_buffer_t output_image,
int mode = IM_ALPHA_BLEND_SRC_OVER);
/**
* Add color key task
*
* @param job_handle
* Insert the task into the job handle.
* @param fg_image
* The foreground image.
* @param bg_image
* The background image, which is also the output destination image.
* @param colorkey_range
* The range of color key.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imcolorkeyTask(im_job_handle_t job_handle,
const rga_buffer_t fg_image, rga_buffer_t bg_image,
im_colorkey_range range, int mode = IM_ALPHA_COLORKEY_NORMAL);
/**
* Add OSD task
*
* @param job_handle
* Insert the task into the job handle.
* @param osd
* The osd text block.
* @param dst
* The background image.
* @param osd_rect
* The rectangle on the source image that needs to be OSD.
* @param osd_config
* osd mode configuration.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imosdTask(im_job_handle_t job_handle,
const rga_buffer_t osd,const rga_buffer_t bg_image,
const im_rect osd_rect, im_osd_t *osd_config);
/**
* Add nn quantize task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param nninfo
* nn configuration
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imquantizeTask(im_job_handle_t job_handle,
const rga_buffer_t src, rga_buffer_t dst, im_nn_t nn_info);
/**
* Add ROP task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param rop_code
* The ROP opcode.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imropTask(im_job_handle_t job_handle,
const rga_buffer_t src, rga_buffer_t dst, int rop_code);
/**
* Add color fill task
*
* @param job_handle
* Insert the task into the job handle.
* @param dst
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be filled with color.
* @param color
* The fill color value.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imfillTask(im_job_handle_t job_handle, rga_buffer_t dst, im_rect rect, uint32_t color);
/**
* Add color fill task array
*
* @param job_handle
* Insert the task into the job handle.
* @param dst
* The output destination image.
* @param rect_array
* The rectangle arrays on the source image that needs to be filled with color.
* @param array_size
* The size of rectangular area arrays.
* @param color
* The fill color value.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imfillTaskArray(im_job_handle_t job_handle,
rga_buffer_t dst,
im_rect *rect_array, int array_size, uint32_t color);
/**
* Add fill rectangle task
*
* @param job_handle
* Insert the task into the job handle.
* @param dst
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be filled with color.
* @param color
* The fill color value.
* @param thickness
* Thickness of lines that make up the rectangle. Negative values, like -1,
* mean that the function has to draw a filled rectangle.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imrectangleTask(im_job_handle_t job_handle,
rga_buffer_t dst,
im_rect rect,
uint32_t color, int thickness);
/**
* Add fill rectangle task array
*
* @param job_handle
* Insert the task into the job handle.
* @param dst
* The output destination image.
* @param rect_array
* The rectangle arrays on the source image that needs to be filled with color.
* @param array_size
* The size of rectangular area arrays.
* @param color
* The fill color value.
* @param thickness
* Thickness of lines that make up the rectangle. Negative values, like -1,
* mean that the function has to draw a filled rectangle.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS imrectangleTaskArray(im_job_handle_t job_handle,
rga_buffer_t dst,
im_rect *rect_array, int array_size,
uint32_t color, int thickness);
/**
* Add mosaic task
*
* @param job_handle
* Insert the task into the job handle.
* @param image
* The output destination image.
* @param rect
* The rectangle on the source image that needs to be mosaicked.
* @param mosaic_mode
* mosaic block width configuration:
* IM_MOSAIC_8
* IM_MOSAIC_16
* IM_MOSAIC_32
* IM_MOSAIC_64
* IM_MOSAIC_128
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS immosaicTask(im_job_handle_t job_handle,
const rga_buffer_t image, im_rect rect, int mosaic_mode);
/**
* Add mosaic task
*
* @param job_handle
* Insert the task into the job handle.
* @param image
* The output destination image.
* @param rect_array
* The rectangle arrays on the source image that needs to be filled with color.
* @param array_size
* The size of rectangular area arrays.
* @param mosaic_mode
* mosaic block width configuration:
* IM_MOSAIC_8
* IM_MOSAIC_16
* IM_MOSAIC_32
* IM_MOSAIC_64
* IM_MOSAIC_128
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS immosaicTaskArray(im_job_handle_t job_handle,
const rga_buffer_t image,
im_rect *rect_array, int array_size, int mosaic_mode);
/**
* Add palette task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image.
* @param dst
* The output destination image.
* @param lut
* The LUT table.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS impaletteTask(im_job_handle_t job_handle,
rga_buffer_t src, rga_buffer_t dst, rga_buffer_t lut);
/**
* Add process task
*
* @param job_handle
* Insert the task into the job handle.
* @param src
* The input source image and is also the foreground image in blend.
* @param dst
* The output destination image and is also the foreground image in blend.
* @param pat
* The foreground image, or a LUT table.
* @param srect
* The rectangle on the src channel image that needs to be processed.
* @param drect
* The rectangle on the dst channel image that needs to be processed.
* @param prect
* The rectangle on the pat channel image that needs to be processed.
* @param opt
* The image processing options configuration.
* @param usage
* The image processing usage.
*
* @returns success or else negative error code.
*/
IM_API IM_STATUS improcessTask(im_job_handle_t job_handle,
rga_buffer_t src, rga_buffer_t dst, rga_buffer_t pat,
im_rect srect, im_rect drect, im_rect prect,
im_opt_t *opt_ptr, int usage);
#endif /* #ifdef __cplusplus */
#endif /* #ifndef _im2d_task_h_ */

View File

@ -0,0 +1,470 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _RGA_IM2D_TYPE_H_
#define _RGA_IM2D_TYPE_H_
#include <stdint.h>
#include "rga.h"
#define IM_API /* define API export as needed */
#ifdef __cplusplus
#define IM_C_API extern "C"
#define IM_EXPORT_API extern "C"
#else
#define IM_C_API
#define IM_EXPORT_API
#endif
#ifdef __cplusplus
#define DEFAULT_INITIALIZER(x) = x
#else
#define DEFAULT_INITIALIZER(x)
#endif
typedef uint32_t im_api_version_t;
typedef uint32_t im_job_handle_t;
typedef uint32_t im_ctx_id_t;
typedef uint32_t rga_buffer_handle_t;
typedef enum {
/* Rotation */
IM_HAL_TRANSFORM_ROT_90 = 1 << 0,
IM_HAL_TRANSFORM_ROT_180 = 1 << 1,
IM_HAL_TRANSFORM_ROT_270 = 1 << 2,
IM_HAL_TRANSFORM_FLIP_H = 1 << 3,
IM_HAL_TRANSFORM_FLIP_V = 1 << 4,
IM_HAL_TRANSFORM_FLIP_H_V = 1 << 5,
IM_HAL_TRANSFORM_MASK = 0x3f,
/*
* Blend
* Additional blend usage, can be used with both source and target configs.
* If none of the below is set, the default "SRC over DST" is applied.
*/
IM_ALPHA_BLEND_SRC_OVER = 1 << 6, /* Default, Porter-Duff "SRC over DST" */
IM_ALPHA_BLEND_SRC = 1 << 7, /* Porter-Duff "SRC" */
IM_ALPHA_BLEND_DST = 1 << 8, /* Porter-Duff "DST" */
IM_ALPHA_BLEND_SRC_IN = 1 << 9, /* Porter-Duff "SRC in DST" */
IM_ALPHA_BLEND_DST_IN = 1 << 10, /* Porter-Duff "DST in SRC" */
IM_ALPHA_BLEND_SRC_OUT = 1 << 11, /* Porter-Duff "SRC out DST" */
IM_ALPHA_BLEND_DST_OUT = 1 << 12, /* Porter-Duff "DST out SRC" */
IM_ALPHA_BLEND_DST_OVER = 1 << 13, /* Porter-Duff "DST over SRC" */
IM_ALPHA_BLEND_SRC_ATOP = 1 << 14, /* Porter-Duff "SRC ATOP" */
IM_ALPHA_BLEND_DST_ATOP = 1 << 15, /* Porter-Duff "DST ATOP" */
IM_ALPHA_BLEND_XOR = 1 << 16, /* Xor */
IM_ALPHA_BLEND_MASK = 0x1ffc0,
IM_ALPHA_COLORKEY_NORMAL = 1 << 17,
IM_ALPHA_COLORKEY_INVERTED = 1 << 18,
IM_ALPHA_COLORKEY_MASK = 0x60000,
IM_SYNC = 1 << 19,
IM_CROP = 1 << 20, /* Unused */
IM_COLOR_FILL = 1 << 21,
IM_COLOR_PALETTE = 1 << 22,
IM_NN_QUANTIZE = 1 << 23,
IM_ROP = 1 << 24,
IM_ALPHA_BLEND_PRE_MUL = 1 << 25,
IM_ASYNC = 1 << 26,
IM_MOSAIC = 1 << 27,
IM_OSD = 1 << 28,
IM_PRE_INTR = 1 << 29,
IM_ALPHA_BIT_MAP = 1 << 30,
} IM_USAGE;
typedef enum {
IM_RASTER_MODE = 1 << 0,
IM_AFBC16x16_MODE = 1 << 1,
IM_TILE8x8_MODE = 1 << 2,
IM_TILE4x4_MODE = 1 << 3,
IM_RKFBC64x4_MODE = 1 << 4,
IM_AFBC32x8_MODE = 1 << 5,
/* legacy */
IM_FBC_MODE = IM_AFBC16x16_MODE,
IM_TILE_MODE = IM_TILE8x8_MODE,
} IM_RD_MODE;
typedef enum {
IM_SCHEDULER_RGA3_CORE0 = 1 << 0,
IM_SCHEDULER_RGA3_CORE1 = 1 << 1,
IM_SCHEDULER_RGA2_CORE0 = 1 << 2,
IM_SCHEDULER_RGA2_CORE1 = 1 << 3,
IM_SCHEDULER_RGA3_DEFAULT = IM_SCHEDULER_RGA3_CORE0,
IM_SCHEDULER_RGA2_DEFAULT = IM_SCHEDULER_RGA2_CORE0,
IM_SCHEDULER_MASK = 0xf,
IM_SCHEDULER_DEFAULT = 0,
} IM_SCHEDULER_CORE;
typedef enum {
IM_ROP_AND = 0x88,
IM_ROP_OR = 0xee,
IM_ROP_NOT_DST = 0x55,
IM_ROP_NOT_SRC = 0x33,
IM_ROP_XOR = 0xf6,
IM_ROP_NOT_XOR = 0xf9,
} IM_ROP_CODE;
typedef enum {
IM_MOSAIC_8 = 0x0,
IM_MOSAIC_16 = 0x1,
IM_MOSAIC_32 = 0x2,
IM_MOSAIC_64 = 0x3,
IM_MOSAIC_128 = 0x4,
} IM_MOSAIC_MODE;
typedef enum {
IM_BORDER_CONSTANT = 0, /* iiiiii|abcdefgh|iiiiiii with some specified value 'i' */
IM_BORDER_REFLECT = 2, /* fedcba|abcdefgh|hgfedcb */
IM_BORDER_WRAP = 3, /* cdefgh|abcdefgh|abcdefg */
} IM_BORDER_TYPE;
/* Status codes, returned by any blit function */
typedef enum {
IM_YUV_TO_RGB_BT601_LIMIT = 1 << 0,
IM_YUV_TO_RGB_BT601_FULL = 2 << 0,
IM_YUV_TO_RGB_BT709_LIMIT = 3 << 0,
IM_YUV_TO_RGB_MASK = 3 << 0,
IM_RGB_TO_YUV_BT601_FULL = 1 << 2,
IM_RGB_TO_YUV_BT601_LIMIT = 2 << 2,
IM_RGB_TO_YUV_BT709_LIMIT = 3 << 2,
IM_RGB_TO_YUV_MASK = 3 << 2,
IM_RGB_TO_Y4 = 1 << 4,
IM_RGB_TO_Y4_DITHER = 2 << 4,
IM_RGB_TO_Y1_DITHER = 3 << 4,
IM_Y4_MASK = 3 << 4,
IM_RGB_FULL = 1 << 8,
IM_RGB_CLIP = 2 << 8,
IM_YUV_BT601_LIMIT_RANGE = 3 << 8,
IM_YUV_BT601_FULL_RANGE = 4 << 8,
IM_YUV_BT709_LIMIT_RANGE = 5 << 8,
IM_YUV_BT709_FULL_RANGE = 6 << 8,
IM_FULL_CSC_MASK = 0xf << 8,
IM_COLOR_SPACE_DEFAULT = 0,
} IM_COLOR_SPACE_MODE;
typedef enum {
IM_UP_SCALE,
IM_DOWN_SCALE,
} IM_SCALE;
/* legacy */
typedef enum {
INTER_NEAREST,
INTER_LINEAR,
INTER_CUBIC,
} IM_SCALE_MODE;
typedef enum {
IM_INTERP_DEFAULT = 0,
IM_INTERP_LINEAR = 1,
IM_INTERP_CUBIC = 2,
IM_INTERP_AVERAGE = 3,
IM_INTERP_MASK = 0xf,
IM_INTERP_HORIZ_SHIFT = 0,
IM_INTERP_VERTI_SHIFT = 4,
IM_INTERP_HORIZ_FLAG = 0x1 << 8,
IM_INTERP_VERTI_FLAG = 0x1 << 9,
} IM_INTER_MODE;
typedef enum {
IM_CONFIG_SCHEDULER_CORE,
IM_CONFIG_PRIORITY,
IM_CONFIG_CHECK,
} IM_CONFIG_NAME;
typedef enum {
IM_OSD_MODE_STATISTICS = 0x1 << 0,
IM_OSD_MODE_AUTO_INVERT = 0x1 << 1,
} IM_OSD_MODE;
typedef enum {
IM_OSD_INVERT_CHANNEL_NONE = 0x0,
IM_OSD_INVERT_CHANNEL_Y_G = 0x1 << 0,
IM_OSD_INVERT_CHANNEL_C_RB = 0x1 << 1,
IM_OSD_INVERT_CHANNEL_ALPHA = 0x1 << 2,
IM_OSD_INVERT_CHANNEL_COLOR = IM_OSD_INVERT_CHANNEL_Y_G |
IM_OSD_INVERT_CHANNEL_C_RB,
IM_OSD_INVERT_CHANNEL_BOTH = IM_OSD_INVERT_CHANNEL_COLOR |
IM_OSD_INVERT_CHANNEL_ALPHA,
} IM_OSD_INVERT_CHANNEL;
typedef enum {
IM_OSD_FLAGS_INTERNAL = 0,
IM_OSD_FLAGS_EXTERNAL,
} IM_OSD_FLAGS_MODE;
typedef enum {
IM_OSD_INVERT_USE_FACTOR,
IM_OSD_INVERT_USE_SWAP,
} IM_OSD_INVERT_MODE;
typedef enum {
IM_OSD_BACKGROUND_DEFAULT_BRIGHT = 0,
IM_OSD_BACKGROUND_DEFAULT_DARK,
} IM_OSD_BACKGROUND_DEFAULT;
typedef enum {
IM_OSD_BLOCK_MODE_NORMAL = 0,
IM_OSD_BLOCK_MODE_DIFFERENT,
} IM_OSD_BLOCK_WIDTH_MODE;
typedef enum {
IM_OSD_MODE_HORIZONTAL,
IM_OSD_MODE_VERTICAL,
} IM_OSD_DIRECTION;
typedef enum {
IM_OSD_COLOR_PIXEL,
IM_OSD_COLOR_EXTERNAL,
} IM_OSD_COLOR_MODE;
typedef enum {
IM_INTR_READ_INTR = 1 << 0,
IM_INTR_READ_HOLD = 1 << 1,
IM_INTR_WRITE_INTR = 1 << 2,
} IM_PRE_INTR_FLAGS;
typedef enum {
IM_CONTEXT_NONE = 0x0,
IM_CONTEXT_SRC_FIX_ENABLE = 0x1 << 0, // Enable kernel to modify the image parameters of the channel.
IM_CONTEXT_SRC_CACHE_INFO = 0x1 << 1, // It will replace the parameters in ctx with the modified parameters.
IM_CONTEXT_SRC1_FIX_ENABLE = 0x1 << 2,
IM_CONTEXT_SRC1_CACHE_INFO = 0x1 << 3,
IM_CONTEXT_DST_FIX_ENABLE = 0x1 << 4,
IM_CONTEXT_DST_CACHE_INFO = 0x1 << 5,
} IM_CONTEXT_FLAGS;
/* Get RGA basic information index */
typedef enum {
RGA_VENDOR = 0,
RGA_VERSION,
RGA_MAX_INPUT,
RGA_MAX_OUTPUT,
RGA_BYTE_STRIDE,
RGA_SCALE_LIMIT,
RGA_INPUT_FORMAT,
RGA_OUTPUT_FORMAT,
RGA_FEATURE,
RGA_EXPECTED,
RGA_ALL,
} IM_INFORMATION;
/* Status codes, returned by any blit function */
typedef enum {
IM_STATUS_NOERROR = 2,
IM_STATUS_SUCCESS = 1,
IM_STATUS_NOT_SUPPORTED = -1,
IM_STATUS_OUT_OF_MEMORY = -2,
IM_STATUS_INVALID_PARAM = -3,
IM_STATUS_ILLEGAL_PARAM = -4,
IM_STATUS_ERROR_VERSION = -5,
IM_STATUS_FAILED = 0,
} IM_STATUS;
/* Rectangle definition */
typedef struct {
int x; /* upper-left x */
int y; /* upper-left y */
int width; /* width */
int height; /* height */
} im_rect;
typedef struct {
int max; /* The Maximum value of the color key */
int min; /* The minimum value of the color key */
} im_colorkey_range;
typedef struct im_nn {
int scale_r; /* scaling factor on R channal */
int scale_g; /* scaling factor on G channal */
int scale_b; /* scaling factor on B channal */
int offset_r; /* offset on R channal */
int offset_g; /* offset on G channal */
int offset_b; /* offset on B channal */
} im_nn_t;
/* im_info definition */
typedef struct {
void* vir_addr; /* virtual address */
void* phy_addr; /* physical address */
int fd; /* shared fd */
int width; /* width */
int height; /* height */
int wstride; /* wstride */
int hstride; /* hstride */
int format; /* format */
int color_space_mode; /* color_space_mode */
union {
int global_alpha; /* global_alpha, the default should be 0xff */
struct {
uint16_t alpha0;
uint16_t alpha1;
} alpha_bit; /* alpha bit(e.g. RGBA5551), 0: alpha0, 1: alpha1 */
};
int rd_mode;
/* legacy */
int color; /* color, used by color fill */
im_colorkey_range colorkey_range; /* range value of color key */
im_nn_t nn;
int rop_code;
rga_buffer_handle_t handle; /* buffer handle */
} rga_buffer_t;
typedef struct im_color {
union {
struct {
uint8_t red;
uint8_t green;
uint8_t blue;
uint8_t alpha;
};
uint32_t value;
};
} im_color_t;
typedef struct im_osd_invert_factor {
uint8_t alpha_max;
uint8_t alpha_min;
uint8_t yg_max;
uint8_t yg_min;
uint8_t crb_max;
uint8_t crb_min;
} im_osd_invert_factor_t;
typedef struct im_osd_bpp2 {
uint8_t ac_swap; // ac swap flag
// 0: CA
// 1: AC
uint8_t endian_swap; // rgba2bpp endian swap
// 0: Big endian
// 1: Little endian
im_color_t color0;
im_color_t color1;
} im_osd_bpp2_t;
typedef struct im_osd_block {
int width_mode; // normal or different
// IM_OSD_BLOCK_MODE_NORMAL
// IM_OSD_BLOCK_MODE_DIFFERENT
union {
int width; // normal_mode block width
int width_index; // different_mode block width index in RAM
};
int block_count; // block count
int background_config; // background config is bright or dark
// IM_OSD_BACKGROUND_DEFAULT_BRIGHT
// IM_OSD_BACKGROUND_DEFAULT_DARK
int direction; // osd block direction
// IM_OSD_MODE_HORIZONTAL
// IM_OSD_MODE_VERTICAL
int color_mode; // using src1 color or config color
// IM_OSD_COLOR_PIXEL
// IM_OSD_COLOR_EXTERNAL
im_color_t normal_color; // config color: normal
im_color_t invert_color; // config color: invert
} im_osd_block_t;
typedef struct im_osd_invert {
int invert_channel; // invert channel config:
// IM_OSD_INVERT_CHANNEL_NONE
// IM_OSD_INVERT_CHANNEL_Y_G
// IM_OSD_INVERT_CHANNEL_C_RB
// IM_OSD_INVERT_CHANNEL_ALPHA
// IM_OSD_INVERT_CHANNEL_COLOR
// IM_OSD_INVERT_CHANNEL_BOTH
int flags_mode; // use external or inertnal RAM invert flags
// IM_OSD_FLAGS_EXTERNAL
// IM_OSD_FLAGS_INTERNAL
int flags_index; // flags index when using internal RAM invert flags
uint64_t invert_flags; // external invert flags
uint64_t current_flags; // current flags
int invert_mode; // invert use swap or factor
// IM_OSD_INVERT_USE_FACTOR
// IM_OSD_INVERT_USE_SWAP
im_osd_invert_factor_t factor;
int threash;
} im_osd_invert_t;
typedef struct im_osd {
int osd_mode; // osd mode: statistics or auto_invert
// IM_OSD_MODE_STATISTICS
// IM_OSD_MODE_AUTO_INVERT
im_osd_block_t block_parm; // osd block info config
im_osd_invert_t invert_config;
im_osd_bpp2_t bpp2_info;
} im_osd_t;
typedef struct im_intr_config {
uint32_t flags;
int read_threshold;
int write_start;
int write_step;
} im_intr_config_t;
typedef struct im_opt {
im_api_version_t version DEFAULT_INITIALIZER(RGA_CURRENT_API_HEADER_VERSION);
int color; /* color, used by color fill */
im_colorkey_range colorkey_range; /* range value of color key */
im_nn_t nn;
int rop_code;
int priority;
int core;
int mosaic_mode;
im_osd_t osd_config;
im_intr_config_t intr_config;
int interp;
char reserve[124];
} im_opt_t;
typedef struct im_handle_param {
uint32_t width;
uint32_t height;
uint32_t format;
} im_handle_param_t;
#define IM_INTERP_HORIZ(x) ( ((x) & IM_INTERP_MASK) << IM_INTERP_HORIZ_SHIFT | IM_INTERP_HORIZ_FLAG )
#define IM_INTERP_VERTI(x) ( ((x) & IM_INTERP_MASK) << IM_INTERP_VERTI_SHIFT | IM_INTERP_VERTI_FLAG )
#define IM_INTERP(h,v) ( IM_INTERP_HORIZ(h) | IM_INTERP_VERTI(v) )
#endif /* _RGA_IM2D_TYPE_H_ */

View File

@ -0,0 +1,49 @@
/*
* Copyright (C) 2022 Rockchip Electronics Co., Ltd.
* Authors:
* Cerf Yu <cerf.yu@rock-chips.com>
*
* 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 _RGA_IM2D_VERSION_H_
#define _RGA_IM2D_VERSION_H_
#define RGA_VERSION_STR_HELPER(x) #x
#define RGA_VERSION_STR(x) RGA_VERSION_STR_HELPER(x)
/* RGA im2d api verison */
#define RGA_API_MAJOR_VERSION 1
#define RGA_API_MINOR_VERSION 10
#define RGA_API_REVISION_VERSION 1
#define RGA_API_BUILD_VERSION 0
#define RGA_API_SUFFIX
#define RGA_API_VERSION \
RGA_VERSION_STR(RGA_API_MAJOR_VERSION) "." \
RGA_VERSION_STR(RGA_API_MINOR_VERSION) "." \
RGA_VERSION_STR(RGA_API_REVISION_VERSION) "_[" \
RGA_VERSION_STR(RGA_API_BUILD_VERSION) "]"
#define RGA_API_FULL_VERSION "rga_api version " RGA_API_VERSION RGA_API_SUFFIX
/* For header file version verification */
#define RGA_CURRENT_API_VERSION (\
(RGA_API_MAJOR_VERSION & 0xff) << 24 | \
(RGA_API_MINOR_VERSION & 0xff) << 16 | \
(RGA_API_REVISION_VERSION & 0xff) << 8 | \
(RGA_API_BUILD_VERSION & 0xff)\
)
#define RGA_CURRENT_API_HEADER_VERSION RGA_CURRENT_API_VERSION
#endif /* _RGA_IM2D_VERSION_H_ */

View File

@ -0,0 +1,197 @@
/*
* Copyright (C) 2016 Rockchip Electronics Co., Ltd.
* Authors:
* Zhiqin Wei <wzq@rock-chips.com>
*
* 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 _RGA_DRIVER_H_
#define _RGA_DRIVER_H_
#ifndef ENABLE
#define ENABLE 1
#endif
#ifndef DISABLE
#define DISABLE 0
#endif
#ifdef __cplusplus
extern "C"
{
#endif
/* In order to be compatible with RK_FORMAT_XX and HAL_PIXEL_FORMAT_XX,
* RK_FORMAT_XX is shifted to the left by 8 bits to distinguish. */
typedef enum _Rga_SURF_FORMAT {
RK_FORMAT_RGBA_8888 = 0x0 << 8, /* [0:31] R:G:B:A 8:8:8:8 little endian */
RK_FORMAT_RGBX_8888 = 0x1 << 8, /* [0:31] R:G:B:X 8:8:8:8 little endian */
RK_FORMAT_RGB_888 = 0x2 << 8, /* [0:23] R:G:B 8:8:8 little endian */
RK_FORMAT_BGRA_8888 = 0x3 << 8, /* [0:31] B:G:R:A 8:8:8:8 little endian */
RK_FORMAT_RGB_565 = 0x4 << 8, /* [0:15] R:G:B 5:6:5 little endian */
RK_FORMAT_RGBA_5551 = 0x5 << 8, /* [0:15] R:G:B:A 5:5:5:1 little endian */
RK_FORMAT_RGBA_4444 = 0x6 << 8, /* [0:15] R:G:B:A 4:4:4:4 little endian */
RK_FORMAT_BGR_888 = 0x7 << 8, /* [0:23] B:G:R 8:8:8 little endian */
RK_FORMAT_YCbCr_422_SP = 0x8 << 8, /* 2 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x1 subsampled [0:15] Cb:Cr 8:8 */
RK_FORMAT_YCbCr_422_P = 0x9 << 8, /* 3 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x1 subsampled [0:7] Cb
* plane 2: 2x1 subsampled [0:7] Cr */
RK_FORMAT_YCbCr_420_SP = 0xa << 8, /* 2 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x2 subsampled [0:15] Cr:Cb 8:8 */
RK_FORMAT_YCbCr_420_P = 0xb << 8, /* 3 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x2 subsampled [0:7] Cb
* plane 2: 2x2 subsampled [0:7] Cr */
RK_FORMAT_YCrCb_422_SP = 0xc << 8, /* 2 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x1 subsampled [0:15] Cb:Cr 8:8 */
RK_FORMAT_YCrCb_422_P = 0xd << 8, /* 3 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x1 subsampled [0:7] Cr
* plane 2: 2x1 subsampled [0:7] Cb */
RK_FORMAT_YCrCb_420_SP = 0xe << 8, /* 2 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x2 subsampled [0:15] Cb:Cr 8:8 */
RK_FORMAT_YCrCb_420_P = 0xf << 8, /* 3 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: 2x2 subsampled [0:7] Cr
* plane 2: 2x2 subsampled [0:7] Cb */
RK_FORMAT_BPP1 = 0x10 << 8, /* [0] little endian */
RK_FORMAT_BPP2 = 0x11 << 8, /* [0:1] little endian */
RK_FORMAT_BPP4 = 0x12 << 8, /* [0:3] little endian */
RK_FORMAT_BPP8 = 0x13 << 8, /* [0:7] little endian */
RK_FORMAT_Y4 = 0x14 << 8, /* [0:3] Y little endian */
RK_FORMAT_YCbCr_400 = 0x15 << 8, /* [0:7] Y little endian */
RK_FORMAT_BGRX_8888 = 0x16 << 8, /* [0:31] B:G:R:X 8:8:8:8 little endian */
RK_FORMAT_YVYU_422 = 0x18 << 8, /* [0:31] Y0:Cr0:Y1:cb0 8:8:8:8 little endian */
RK_FORMAT_YVYU_420 = 0x19 << 8, /* ODD : [0:31] Y0:Cr0:Y1:cb0 8:8:8:8 little endian
* EVEN: [0:31] Y2:Y3:X:X 8:8:8:8 little endian */
RK_FORMAT_VYUY_422 = 0x1a << 8, /* [0:31] Cr0:Y0:Cb0:Y1 8:8:8:8 little endian */
RK_FORMAT_VYUY_420 = 0x1b << 8, /* ODD : [0:31] Cr0:Y0:Cb0:Y1 8:8:8:8 little endian
* EVEN: [0:31] Y2:Y3:X:X 8:8:8:8 little endian */
RK_FORMAT_YUYV_422 = 0x1c << 8, /* [0:31] Y0:Cb0:Y1:cr0 8:8:8:8 little endian */
RK_FORMAT_YUYV_420 = 0x1d << 8, /* ODD : [0:31] Y0:Cb0:Y1:cr0 8:8:8:8 little endian
* EVEN: [0:31] Y2:Y3:X:X 8:8:8:8 little endian */
RK_FORMAT_UYVY_422 = 0x1e << 8, /* [0:31] Cb0:Y0:Cr0:Y1 8:8:8:8 little endian */
RK_FORMAT_UYVY_420 = 0x1f << 8, /* ODD : [0:31] Cb0:Y0:Cr0:Y1 8:8:8:8 little endian
* EVEN: [0:31] Y2:Y3:X:X 8:8:8:8 little endian */
RK_FORMAT_YCbCr_420_SP_10B = 0x20 << 8, /* 2 plane YCbCr little endian
* plane 0: [0:9] Y
* plane 1: 2x2 subsampled [0:19] Cb:Cr 10: 10 (default)
* or
* plane 1: 2x2 subsampled [0:23] Cb:Cr 16: 16 */
RK_FORMAT_YCrCb_420_SP_10B = 0x21 << 8, /* 2 plane YCbCr little endian
* plane 0: [0:9] Y
* plane 1: 2x2 subsampled [0:19] Cr:Cb 10: 10 (default)
* or
* plane 1: 2x2 subsampled [0:23] Cr:Cb 16: 16 */
RK_FORMAT_YCbCr_422_SP_10B = 0x22 << 8, /* 2 plane YCbCr little endian
* plane 0: [0:9] Y
* plane 1: 2x1 subsampled [0:19] Cb:Cr 10:10 (default)
* or
* plane 1: 2x1 subsampled [0:23] Cb:Cr 16: 16 */
RK_FORMAT_YCrCb_422_SP_10B = 0x23 << 8, /* 2 plane YCbCr little endian
* plane 0: [0:9] Y
* plane 1: 2x1 subsampled [0:19] Cr:Cb 10:10 (default)
* or
* plane 1: 2x1 subsampled [0:23] Cr:Cb 16: 16 */
/* For compatibility with misspellings */
RK_FORMAT_YCbCr_422_10b_SP = RK_FORMAT_YCbCr_422_SP_10B << 8,
RK_FORMAT_YCrCb_422_10b_SP = RK_FORMAT_YCrCb_422_SP_10B << 8,
RK_FORMAT_BGR_565 = 0x24 << 8, /* [0:16] B:G:R 5:6:5 little endian */
RK_FORMAT_BGRA_5551 = 0x25 << 8, /* [0:16] B:G:R:A 5:5:5:1 little endian */
RK_FORMAT_BGRA_4444 = 0x26 << 8, /* [0:16] B:G:R:A 4:4:4:4 little endian */
RK_FORMAT_ARGB_8888 = 0x28 << 8, /* [0:31] A:R:G:B 8:8:8:8 little endian */
RK_FORMAT_XRGB_8888 = 0x29 << 8, /* [0:31] X:R:G:B 8:8:8:8 little endian */
RK_FORMAT_ARGB_5551 = 0x2a << 8, /* [0:16] A:R:G:B 5:5:5:1 little endian */
RK_FORMAT_ARGB_4444 = 0x2b << 8, /* [0:16] A:R:G:B 4:4:4:4 little endian */
RK_FORMAT_ABGR_8888 = 0x2c << 8, /* [0:31] A:B:G:R 8:8:8:8 little endian */
RK_FORMAT_XBGR_8888 = 0x2d << 8, /* [0:31] X:B:G:R 8:8:8:8 little endian */
RK_FORMAT_ABGR_5551 = 0x2e << 8, /* [0:16] A:B:G:R 5:5:5:1 little endian */
RK_FORMAT_ABGR_4444 = 0x2f << 8, /* [0:16] A:B:G:R 4:4:4:4 little endian */
RK_FORMAT_RGBA2BPP = 0x30 << 8, /* [0:1] Color:Alpha 1:1 little endian */
RK_FORMAT_A8 = 0x31 << 8, /* [0:7] Alpha */
RK_FORMAT_YCbCr_444_SP = 0x32 << 8, /* 2 plane YCbCr little endian
* plane 0: [0:7] Y
* plane 1: non-subsampled [0:15] Cb:Cr 8:8 */
RK_FORMAT_YCrCb_444_SP = 0x33 << 8, /* 2 plane YCrCb little endian
* plane 0: [0:7] Y
* plane 1: non-subsampled [0:15] Cr:Cb 8:8 */
RK_FORMAT_Y8 = 0x34 << 8, /* [0:7] zero:Y 4:4 little endian */
RK_FORMAT_UNKNOWN = 0x100 << 8,
} RgaSURF_FORMAT;
enum {
yuv2rgb_mode0 = 0x0, /* BT.601 MPEG */
yuv2rgb_mode1 = 0x1, /* BT.601 JPEG */
yuv2rgb_mode2 = 0x2, /* BT.709 */
rgb2yuv_601_full = 0x1 << 8,
rgb2yuv_709_full = 0x2 << 8,
yuv2yuv_601_limit_2_709_limit = 0x3 << 8,
yuv2yuv_601_limit_2_709_full = 0x4 << 8,
yuv2yuv_709_limit_2_601_limit = 0x5 << 8,
yuv2yuv_709_limit_2_601_full = 0x6 << 8, //not support
yuv2yuv_601_full_2_709_limit = 0x7 << 8,
yuv2yuv_601_full_2_709_full = 0x8 << 8, //not support
yuv2yuv_709_full_2_601_limit = 0x9 << 8, //not support
yuv2yuv_709_full_2_601_full = 0xa << 8, //not support
rgb2yuv_709_limit = 0xb << 8,
yuv2rgb_709_full = 0xc << 8, //not support
yuv2yuv_601_limit_2_601_full = 0xd << 8, //not support
yuv2yuv_601_full_2_601_limit = 0xe << 8, //not support
yuv2yuv_709_limit_2_709_full = 0xf << 8, //not support
yuv2yuv_709_full_2_709_limit = 0x10 << 8, //not support
full_csc_mask = 0xf00,
};
enum {
RGA3_SCHEDULER_CORE0 = 1 << 0,
RGA3_SCHEDULER_CORE1 = 1 << 1,
RGA2_SCHEDULER_CORE0 = 1 << 2,
RGA2_SCHEDULER_CORE1 = 1 << 3,
RGA_CORE_MASK = 0xf,
RGA_NONE_CORE = 0x0,
};
/* RGA3 rd_mode */
enum
{
raster_mode = 0x1 << 0,
fbc_mode = 0x1 << 1,
tile_mode = 0x1 << 2,
};
#ifdef __cplusplus
}
#endif
#endif /*_RK29_IPP_DRIVER_H_*/

View File

@ -0,0 +1,33 @@
#ifndef __RGA_FUNC_H__
#define __RGA_FUNC_H__
#include <dlfcn.h>
#include "RgaApi.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef int(* FUNC_RGA_INIT)();
typedef void(* FUNC_RGA_DEINIT)();
typedef int(* FUNC_RGA_BLIT)(rga_info_t *, rga_info_t *, rga_info_t *);
typedef struct _rga_context{
void *rga_handle;
FUNC_RGA_INIT init_func;
FUNC_RGA_DEINIT deinit_func;
FUNC_RGA_BLIT blit_func;
} rga_context;
int RGA_init(rga_context* rga_ctx);
void img_resize_fast(rga_context *rga_ctx, int src_fd, int src_w, int src_h, uint64_t dst_phys, int dst_w, int dst_h);
void img_resize_slow(rga_context *rga_ctx, void *src_virt, int src_w, int src_h, void *dst_virt, int dst_w, int dst_h);
int RGA_deinit(rga_context* rga_ctx);
#ifdef __cplusplus
}
#endif
#endif/*__RGA_FUNC_H__*/

View File

@ -0,0 +1,410 @@
#pragma once
#include <cv_bridge/cv_bridge.h>
#include <filesystem>
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/time_synchronizer.h>
#include <opencv2/core/eigen.hpp>
#include <opencv2/opencv.hpp>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/features/moment_of_inertia_estimation.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/segmentation/extract_clusters.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl_conversions/pcl_conversions.h>
#include "debugstream.hpp"
#include "yaml_config.h"
#include <omp.h>
#include <Eigen/Core>
#include <Eigen/Dense>
// 计算旋转矩阵
inline Eigen::Matrix4d TransforMatrix(const Eigen::Vector3d &translation,
double roll, double pitch, double yaw) {
Eigen::Quaterniond q = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
Eigen::Matrix4d transformation_matrix =
Eigen::Matrix4d::Identity(); // 初始化为单位矩阵
transformation_matrix.block<3, 3>(0, 0) =
q.toRotationMatrix(); // 设置旋转矩阵部分
transformation_matrix.block<3, 1>(0, 3) = translation; // 设置平移向量部分
// std::cout << "旋转矩阵:" << std::endl << transformation_matrix <<
// std::endl;
return transformation_matrix;
}
struct mybox {
mybox()
: lidar_points(new pcl::PointCloud<pcl::PointXYZ>),
lidar_cluster(new pcl::PointCloud<pcl::PointXYZ>) {}
std::string label;
cv::Rect rect;
cv::Rect small_rect;
pcl::PointCloud<pcl::PointXYZ>::Ptr lidar_points;
pcl::PointCloud<pcl::PointXYZ>::Ptr lidar_cluster;
Eigen::Vector3f obstacle_centroids;
Eigen::Vector3f obstacle_sizes;
Eigen::Quaternionf obstacle_orientations;
// 拷贝构造函数
mybox(const mybox &other)
: label(other.label), rect(other.rect), small_rect(other.small_rect),
lidar_points(new pcl::PointCloud<pcl::PointXYZ>(*other.lidar_points)),
lidar_cluster(new pcl::PointCloud<pcl::PointXYZ>(*other.lidar_cluster)),
obstacle_centroids(other.obstacle_centroids),
obstacle_sizes(other.obstacle_sizes),
obstacle_orientations(other.obstacle_orientations) {}
// 拷贝赋值运算符
mybox &operator=(const mybox &other) {
if (this != &other) {
label = other.label;
rect = other.rect;
small_rect = other.small_rect;
lidar_points.reset(
new pcl::PointCloud<pcl::PointXYZ>(*other.lidar_points));
lidar_cluster.reset(
new pcl::PointCloud<pcl::PointXYZ>(*other.lidar_cluster));
obstacle_centroids = other.obstacle_centroids;
obstacle_sizes = other.obstacle_sizes;
obstacle_orientations = other.obstacle_orientations;
}
return *this;
}
// 移动构造函数
mybox(mybox &&other) noexcept
: label(std::move(other.label)), rect(std::move(other.rect)),
small_rect(std::move(other.small_rect)),
lidar_points(std::move(other.lidar_points)),
lidar_cluster(std::move(other.lidar_cluster)),
obstacle_centroids(std::move(other.obstacle_centroids)),
obstacle_sizes(std::move(other.obstacle_sizes)),
obstacle_orientations(std::move(other.obstacle_orientations)) {}
// 移动赋值运算符
mybox &operator=(mybox &&other) noexcept {
if (this != &other) {
label = std::move(other.label);
rect = std::move(other.rect);
small_rect = std::move(other.small_rect);
lidar_points = std::move(other.lidar_points);
lidar_cluster = std::move(other.lidar_cluster);
obstacle_centroids = std::move(other.obstacle_centroids);
obstacle_sizes = std::move(other.obstacle_sizes);
obstacle_orientations = std::move(other.obstacle_orientations);
}
return *this;
}
};
// 把点云去除地面相关点
// 返回值第一个是非地面点,第二个是地面点
template <typename PointT>
inline std::pair<typename pcl::PointCloud<PointT>::Ptr,
typename pcl::PointCloud<PointT>::Ptr>
RansacSegmentPlane(typename pcl::PointCloud<PointT>::Ptr cloud,
int maxIterations, float distanceTol) {
// 使用pcl的分割分离出地面
// Count time
auto startTime = std::chrono::steady_clock::now();
// Create the segmentation object
pcl::SACSegmentation<PointT> seg;
// Optional
seg.setOptimizeCoefficients(true);
seg.setModelType(pcl::SACMODEL_PLANE);
seg.setMethodType(pcl::SAC_RANSAC);
seg.setMaxIterations(maxIterations);
seg.setDistanceThreshold(distanceTol);
// Segment the largest planar component
// PtCdtr<PointT> cloud_plane(new pcl::PointCloud<PointT>());
// PtCdtr<PointT> cloud_out(new pcl::PointCloud<PointT>());
pcl::ModelCoefficients::Ptr cloud_out(new pcl::ModelCoefficients);
pcl::PointIndices::Ptr cloud_plane(new pcl::PointIndices);
seg.setInputCloud(cloud);
seg.segment(*cloud_plane, *cloud_out);
typename pcl::PointCloud<PointT>::Ptr in_plane(new pcl::PointCloud<PointT>());
typename pcl::PointCloud<PointT>::Ptr out_plane(
new pcl::PointCloud<PointT>());
// Extract the inliers
pcl::ExtractIndices<PointT> extract;
extract.setInputCloud(cloud);
extract.setIndices(cloud_plane);
extract.setNegative(false);
extract.filter(*in_plane);
// Extract the outliers
extract.setNegative(true);
extract.filter(*out_plane);
auto endTime = std::chrono::steady_clock::now();
auto elapsedTime = std::chrono::duration_cast<std::chrono::milliseconds>(
endTime - startTime);
std::cout << "plane ransac-segment took " << elapsedTime.count()
<< " milliseconds" << std::endl;
return std::make_pair(out_plane, in_plane);
}
// reference
// https://pointclouds.org/documentation/tutorials/moment_of_inertia.html
/**
*
* @param obstacle_clouds
* @param obstacle_centroids
* @param obstacle_sizes
* @param obstacle_orientations
*/
inline void ExtractObstacles(
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> &obstacle_clouds,
std::vector<Eigen::Vector3f> &obstacle_centroids,
std::vector<Eigen::Vector3f> &obstacle_sizes,
std::vector<Eigen::Quaternionf> &obstacle_orientations,
bool enable_verbose = false) {
auto startTime = std::chrono::steady_clock::now();
obstacle_centroids.clear();
obstacle_sizes.clear();
obstacle_orientations.clear();
static int obb_omp_threads = yaml_config["obb_omp_threads"].as<int>();
omp_set_num_threads(obb_omp_threads);
#pragma omp parallel for
for (const auto &obstacle_cloud : obstacle_clouds) {
pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
feature_extractor.setInputCloud(obstacle_cloud);
feature_extractor.compute();
pcl::PointXYZ min_point_OBB;
pcl::PointXYZ max_point_OBB;
pcl::PointXYZ position_OBB;
Eigen::Matrix3f rotational_matrix_OBB;
feature_extractor.getOBB(min_point_OBB, max_point_OBB, position_OBB,
rotational_matrix_OBB);
Eigen::Vector3f position(position_OBB.x, position_OBB.y, position_OBB.z);
Eigen::Quaternionf quat(rotational_matrix_OBB);
Eigen::Vector3f size;
size << (max_point_OBB.x - min_point_OBB.x),
(max_point_OBB.y - min_point_OBB.y),
(max_point_OBB.z - min_point_OBB.z);
#pragma omp critical
{
obstacle_centroids.push_back(position);
obstacle_orientations.push_back(quat);
obstacle_sizes.push_back(size);
}
}
auto endTime = std::chrono::steady_clock::now();
auto elapsedTime = std::chrono::duration_cast<std::chrono::milliseconds>(
endTime - startTime);
std::cout << "extract obstacles took " << elapsedTime.count()
<< " milliseconds" << std::endl;
// debug
if (enable_verbose) {
std::cout << obstacle_centroids.size();
for (int i = 0; i < obstacle_centroids.size(); i++) {
std::cout << "======obstacle[" << i << "]======" << std::endl;
std::cout << obstacle_centroids[i] << std::endl;
std::cout << obstacle_sizes[i] << std::endl;
std::cout << obstacle_orientations[i].matrix() << std::endl;
std::cout << "========================" << std::endl;
}
}
}
/**
*
* @param obstacle_clouds
* @param obstacle_centroids
* @param obstacle_sizes
* @param obstacle_orientations
*/
inline void ExtractObstacles(
pcl::PointCloud<pcl::PointXYZ>::Ptr &obstacle_cloud,
Eigen::Vector3f &obstacle_centroids, Eigen::Vector3f &obstacle_sizes,
Eigen::Quaternionf &obstacle_orientations, bool enable_verbose = false) {
auto startTime = std::chrono::steady_clock::now();
pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
feature_extractor.setInputCloud(obstacle_cloud);
feature_extractor.compute();
pcl::PointXYZ min_point_OBB;
pcl::PointXYZ max_point_OBB;
pcl::PointXYZ position_OBB;
Eigen::Matrix3f rotational_matrix_OBB;
feature_extractor.getOBB(min_point_OBB, max_point_OBB, position_OBB,
rotational_matrix_OBB);
Eigen::Vector3f position(position_OBB.x, position_OBB.y, position_OBB.z);
Eigen::Quaternionf quat(rotational_matrix_OBB);
Eigen::Vector3f size;
size << (max_point_OBB.x - min_point_OBB.x),
(max_point_OBB.y - min_point_OBB.y), (max_point_OBB.z - min_point_OBB.z);
obstacle_centroids = std::move(position);
obstacle_orientations = std::move(quat);
obstacle_sizes = std::move(size);
auto endTime = std::chrono::steady_clock::now();
auto elapsedTime = std::chrono::duration_cast<std::chrono::milliseconds>(
endTime - startTime);
std::cout << "extract obstacles took " << elapsedTime.count()
<< " milliseconds" << std::endl;
// debug
if (enable_verbose) {
std::cout << "========obstacle========" << std::endl;
std::cout << obstacle_centroids << std::endl;
std::cout << obstacle_sizes << std::endl;
std::cout << obstacle_orientations.matrix() << std::endl;
std::cout << "========================" << std::endl;
}
}
class CoordinateHelp {
public:
CoordinateHelp() {
// 初始化相机内参矩阵
camera_inner_matrix_ =
(cv::Mat_<double>(3, 3)
<< yaml_config["camera_in_param"]["dx"].as<double>(),
0.0, yaml_config["camera_in_param"]["u0"].as<double>(), 0.0,
yaml_config["camera_in_param"]["dy"].as<double>(),
yaml_config["camera_in_param"]["v0"].as<double>(), 0.0, 0.0, 1.0);
gDebugCol5(camera_inner_matrix_);
// 初始化相机畸变矩阵
camera_distort_matrix_ =
(cv::Mat_<double>(1, 5)
<< yaml_config["camera_distort_params"]["p0"].as<double>(),
yaml_config["camera_distort_params"]["p1"].as<double>(),
yaml_config["camera_distort_params"]["p2"].as<double>(),
yaml_config["camera_distort_params"]["p3"].as<double>(),
yaml_config["camera_distort_params"]["p4"].as<double>());
gDebugCol5(camera_distort_matrix_);
// 初始化相机到雷达位姿
convert_camera2lidar_ = Camera2Lidar();
gDebugCol5(convert_camera2lidar_);
// 初始化雷达到车体位姿
convert_lidar2car_ = Lidar2Car();
gDebugCol5(convert_lidar2car_);
{
Eigen::Affine3d convert_point_cl = Eigen::Affine3d(
convert_camera2lidar_.inverse()); // 转换为Affine3d类型
Eigen::Matrix3d camera_inner_eigen;
cv::cv2eigen(camera_inner_matrix_, camera_inner_eigen);
Eigen::Matrix3d xyz2zyx;
xyz2zyx << 0, -1, 0, 0, 0, 1, 1, 0, 0;
all_in_one_matrix_ = camera_inner_eigen * xyz2zyx * convert_point_cl;
}
}
cv::Mat camera_inner_matrix_; // 相机内参矩阵
cv::Mat camera_distort_matrix_; // 相机畸变参数矩阵
Eigen::Matrix4d convert_camera2lidar_; // 相机到雷达的位姿转换
Eigen::Matrix4d convert_lidar2car_; // 雷达到车的位姿转换
Eigen::Affine3d all_in_one_matrix_; // 激光点到相机像素坐标系点
public:
void UndistortImage(cv::Mat &image) {
UndistortImageHelp(image, camera_inner_matrix_, camera_distort_matrix_);
}
// 点云点到相机像素像素平面
Eigen::Vector3d
ProjectLidarPointToCameraPixel(const Eigen::Vector3d &lidarPoint) {
return all_in_one_matrix_ * lidarPoint;
}
private:
inline void UndistortImageHelp(cv::Mat &inputImage,
const cv::Mat &cameraMatrix,
const cv::Mat &distCoeffs) {
static std::pair<cv::Mat, cv::Mat> undistort_map = [&]() {
// 创建用于存储映射矩阵的 Mat
cv::Mat map1, map2;
// 计算并缓存去畸变映射
cv::Size img_size(inputImage.cols, inputImage.rows); // 图像大小
cv::initUndistortRectifyMap(cameraMatrix, distCoeffs, cv::Mat(),
cameraMatrix, img_size, CV_16SC2, map1, map2);
return std::pair<cv::Mat, cv::Mat>{map1, map2};
}();
cv::remap(inputImage, inputImage, undistort_map.first, undistort_map.second,
cv::INTER_LINEAR);
}
Eigen::Matrix4d Camera2Lidar() {
// 初始化坐标系变换的旋转矩阵
Eigen::Vector3d trans;
trans[0] =
yaml_config["convert_carmera2lidar"]["transform"]["x"].as<double>();
trans[1] =
yaml_config["convert_carmera2lidar"]["transform"]["y"].as<double>();
trans[2] =
yaml_config["convert_carmera2lidar"]["transform"]["z"].as<double>();
std::cout << "trans x=" << trans[0] << std::endl;
std::cout << "trans y=" << trans[1] << std::endl;
std::cout << "trans z=" << trans[2] << std::endl;
// trans<<0.3643,0.2078,1.21;
double roll =
yaml_config["convert_carmera2lidar"]["rotation"]["roll"].as<double>();
double pitch =
yaml_config["convert_carmera2lidar"]["rotation"]["pitch"].as<double>();
double yaw =
yaml_config["convert_carmera2lidar"]["rotation"]["yaw"].as<double>();
std::cout << "roll=" << roll << std::endl;
std::cout << "pitch=" << pitch << std::endl;
std::cout << "yaw=" << yaw << std::endl;
Eigen::Matrix4d tran_matrix = TransforMatrix(
trans, roll * M_PI / 180.0, pitch * M_PI / 180.0, yaw * M_PI / 180.0);
// trans, roll , pitch , yaw );
gDebug() << VAR(tran_matrix);
// Eigen::Affine3d affine3d_transform(tran_matrix); // 转换为Affine3d类型
// affine3f_transform = affine3d_transform.cast<float>(); //
// 转换为Affine3f类型 affine3f_transform = affine3f_transform.inverse();
return tran_matrix;
}
inline Eigen::Matrix4d Lidar2Car() {
// 初始化坐标系变换的旋转矩阵
Eigen::Vector3d trans;
trans[0] = yaml_config["convert_lidar2car"]["transform"]["x"].as<double>();
trans[1] = yaml_config["convert_lidar2car"]["transform"]["y"].as<double>();
trans[2] = yaml_config["convert_lidar2car"]["transform"]["z"].as<double>();
std::cout << "trans x=" << trans[0] << std::endl;
std::cout << "trans y=" << trans[1] << std::endl;
std::cout << "trans z=" << trans[2] << std::endl;
// trans<<0.3643,0.2078,1.21;
double roll =
yaml_config["convert_lidar2car"]["rotation"]["roll"].as<double>();
double pitch =
yaml_config["convert_lidar2car"]["rotation"]["pitch"].as<double>();
double yaw =
yaml_config["convert_lidar2car"]["rotation"]["yaw"].as<double>();
std::cout << "roll=" << roll << std::endl;
std::cout << "pitch=" << pitch << std::endl;
std::cout << "yaw=" << yaw << std::endl;
Eigen::Matrix4d tran_matrix = TransforMatrix(
trans, roll * M_PI / 180.0, pitch * M_PI / 180.0, yaw * M_PI / 180.0);
gDebug() << VAR(tran_matrix);
// Eigen::Affine3d affine3d_transform(tran_matrix); // 转换为Affine3d类型
// affine3f_transform = affine3d_transform.cast<float>(); //
// 转换为Affine3f类型 affine3f_transform = affine3f_transform.inverse();
return tran_matrix;
}
};

View File

@ -0,0 +1,326 @@
#pragma once
/*-------------------------------------------
Includes
-------------------------------------------*/
#include <dlfcn.h>
#include <exception>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/time.h>
#define _BASETSD_H
#include "RgaUtils.h"
#include "postprocess.h"
#include "preprocess.h"
#include "rknn_api.h"
#include "debugstream.hpp"
#include "dianti.h"
#define PERF_WITH_POST 1
/*-------------------------------------------
Functions
-------------------------------------------*/
static void dump_tensor_attr(rknn_tensor_attr *attr) {
std::string shape_str = attr->n_dims < 1 ? "" : std::to_string(attr->dims[0]);
for (int i = 1; i < attr->n_dims; ++i) {
shape_str += ", " + std::to_string(attr->dims[i]);
}
printf(" index=%d, name=%s, n_dims=%d, dims=[%s], n_elems=%d, size=%d, "
"w_stride = %d, size_with_stride=%d, fmt=%s, "
"type=%s, qnt_type=%s, "
"zp=%d, scale=%f\n",
attr->index, attr->name, attr->n_dims, shape_str.c_str(),
attr->n_elems, attr->size, attr->w_stride, attr->size_with_stride,
get_format_string(attr->fmt), get_type_string(attr->type),
get_qnt_type_string(attr->qnt_type), attr->zp, attr->scale);
}
double __get_us(struct timeval t) { return (t.tv_sec * 1000000 + t.tv_usec); }
static unsigned char *load_data(FILE *fp, size_t ofst, size_t sz) {
unsigned char *data;
int ret;
data = NULL;
if (NULL == fp) {
return NULL;
}
ret = fseek(fp, ofst, SEEK_SET);
if (ret != 0) {
printf("blob seek failure.\n");
return NULL;
}
data = (unsigned char *)malloc(sz);
if (data == NULL) {
printf("buffer malloc failure.\n");
return NULL;
}
ret = fread(data, 1, sz, fp);
return data;
}
static unsigned char *load_model(const char *filename, int *model_size) {
FILE *fp;
unsigned char *data;
fp = fopen(filename, "rb");
if (NULL == fp) {
printf("Open file %s failed.\n", filename);
return NULL;
}
fseek(fp, 0, SEEK_END);
int size = ftell(fp);
data = load_data(fp, 0, size);
fclose(fp);
*model_size = size;
return data;
}
static int saveFloat(const char *file_name, float *output, int element_size) {
FILE *fp;
fp = fopen(file_name, "w");
for (int i = 0; i < element_size; i++) {
fprintf(fp, "%.6f\n", output[i]);
}
fclose(fp);
return 0;
}
class Yolov5 {
public:
rknn_context ctx;
rknn_input inputs[1];
int img_width = 0;
int img_height = 0;
int img_channel = 0;
int channel = 3;
int width = 0;
int height = 0;
rga_buffer_t src;
rga_buffer_t dst;
std::string option = "letterbox";
rknn_input_output_num io_num;
struct timeval start_time, stop_time;
rknn_tensor_attr *output_attrs;
const float nms_threshold = NMS_THRESH; // 默认的NMS阈值
const float box_conf_threshold = BOX_THRESH; // 默认的置信度阈值
unsigned char *model_data;
std::vector<std::string> labels;
Yolov5() {}
~Yolov5() {
// deinitPostProcess();
// release
rknn_destroy(ctx);
if (model_data) {
free(model_data);
}
}
void SetLabels(const std::vector<std::string> &labelss) { labels = labelss; }
void LoadModel(const std::string &model_name_str) {
int ret;
const char *model_name = model_name_str.c_str();
// std::string out_path = "./out.jpg";
// init rga context
memset(&src, 0, sizeof(src));
memset(&dst, 0, sizeof(dst));
printf("post process config: box_conf_threshold = %.2f, nms_threshold = "
"%.2f\n",
box_conf_threshold, nms_threshold);
/* Create the neural network */
printf("Loading mode...\n");
int model_data_size = 0;
model_data = load_model(model_name, &model_data_size);
ret = rknn_init(&ctx, model_data, model_data_size, 0, NULL);
if (ret < 0) {
printf("rknn_init error ret=%d\n", ret);
std::terminate();
}
rknn_sdk_version version;
ret = rknn_query(ctx, RKNN_QUERY_SDK_VERSION, &version,
sizeof(rknn_sdk_version));
if (ret < 0) {
printf("rknn_init error ret=%d\n", ret);
std::terminate();
}
printf("sdk version: %s driver version: %s\n", version.api_version,
version.drv_version);
ret = rknn_query(ctx, RKNN_QUERY_IN_OUT_NUM, &io_num, sizeof(io_num));
if (ret < 0) {
printf("rknn_init error ret=%d\n", ret);
std::terminate();
}
printf("model input num: %d, output num: %d\n", io_num.n_input,
io_num.n_output);
rknn_tensor_attr input_attrs[io_num.n_input];
memset(input_attrs, 0, sizeof(input_attrs));
for (int i = 0; i < io_num.n_input; i++) {
input_attrs[i].index = i;
ret = rknn_query(ctx, RKNN_QUERY_INPUT_ATTR, &(input_attrs[i]),
sizeof(rknn_tensor_attr));
if (ret < 0) {
printf("rknn_init error ret=%d\n", ret);
std::terminate();
}
dump_tensor_attr(&(input_attrs[i]));
}
// rknn_tensor_attr output_attrs[io_num.n_output];
output_attrs = new rknn_tensor_attr[io_num.n_output];
memset(output_attrs, 0, sizeof(*output_attrs));
for (int i = 0; i < io_num.n_output; i++) {
output_attrs[i].index = i;
ret = rknn_query(ctx, RKNN_QUERY_OUTPUT_ATTR, &(output_attrs[i]),
sizeof(rknn_tensor_attr));
dump_tensor_attr(&(output_attrs[i]));
}
if (input_attrs[0].fmt == RKNN_TENSOR_NCHW) {
printf("model is NCHW input fmt\n");
channel = input_attrs[0].dims[1];
height = input_attrs[0].dims[2];
width = input_attrs[0].dims[3];
} else {
printf("model is NHWC input fmt\n");
height = input_attrs[0].dims[1];
width = input_attrs[0].dims[2];
channel = input_attrs[0].dims[3];
}
printf("model input height=%d, width=%d, channel=%d\n", height, width,
channel);
memset(inputs, 0, sizeof(inputs));
inputs[0].index = 0;
inputs[0].type = RKNN_TENSOR_UINT8;
inputs[0].size = width * height * channel;
inputs[0].fmt = RKNN_TENSOR_NHWC;
inputs[0].pass_through = 0;
}
detect_result_group_t Infer(const cv::Mat &orig_img,
const std::string &out_path = "output.jpg",
bool debug = false) {
int ret;
cv::Mat img;
cv::cvtColor(orig_img, img, cv::COLOR_BGR2RGB);
img_width = img.cols;
img_height = img.rows;
printf("img width = %d, img height = %d\n", img_width, img_height);
// 指定目标大小和预处理方式,默认使用LetterBox的预处理
BOX_RECT pads;
memset(&pads, 0, sizeof(BOX_RECT));
cv::Size target_size(width, height);
cv::Mat resized_img(target_size.height, target_size.width, CV_8UC3);
// 计算缩放比例
float scale_w = (float)target_size.width / img.cols;
float scale_h = (float)target_size.height / img.rows;
if (img_width != width || img_height != height) {
// 直接缩放采用RGA加速
if (option == "resize") {
printf("resize image by rga\n");
ret = resize_rga(src, dst, img, resized_img, target_size);
if (ret != 0) {
fprintf(stderr, "resize with rga error\n");
std::terminate();
}
// 保存预处理图片
if (debug)
cv::imwrite("resize_input.jpg", resized_img);
} else if (option == "letterbox") {
printf("resize image with letterbox\n");
float min_scale = std::min(scale_w, scale_h);
scale_w = min_scale;
scale_h = min_scale;
letterbox(img, resized_img, pads, min_scale, target_size);
// 保存预处理图片
if (debug)
cv::imwrite("letterbox_input.jpg", resized_img);
} else {
fprintf(stderr,
"Invalid resize option. Use 'resize' or 'letterbox'.\n");
std::terminate();
}
inputs[0].buf = resized_img.data;
} else {
inputs[0].buf = img.data;
}
gettimeofday(&start_time, NULL);
rknn_inputs_set(ctx, io_num.n_input, inputs);
rknn_output outputs[io_num.n_output];
memset(outputs, 0, sizeof(outputs));
for (int i = 0; i < io_num.n_output; i++) {
outputs[i].index = i;
outputs[i].want_float = 0;
}
// 执行推理
ret = rknn_run(ctx, NULL);
ret = rknn_outputs_get(ctx, io_num.n_output, outputs, NULL);
// 后处理
detect_result_group_t detect_result_group;
std::vector<float> out_scales;
std::vector<int32_t> out_zps;
for (int i = 0; i < io_num.n_output; ++i) {
out_scales.push_back(output_attrs[i].scale);
out_zps.push_back(output_attrs[i].zp);
}
post_process((int8_t *)outputs[0].buf, (int8_t *)outputs[1].buf,
(int8_t *)outputs[2].buf, height, width, box_conf_threshold,
nms_threshold, pads, scale_w, scale_h, out_zps, out_scales,
&detect_result_group, labels);
gettimeofday(&stop_time, NULL);
printf("once run use %f ms\n",
(__get_us(stop_time) - __get_us(start_time)) / 1000);
// 画框和概率
char text[256];
for (int i = 0; i < detect_result_group.count; i++) {
detect_result_t *det_result = &(detect_result_group.results[i]);
sprintf(text, "%s %.1f%%", det_result->name, det_result->prop * 100);
printf("%s @ (%d %d %d %d) %f\n", det_result->name, det_result->box.left,
det_result->box.top, det_result->box.right, det_result->box.bottom,
det_result->prop);
int x1 = det_result->box.left;
int y1 = det_result->box.top;
int x2 = det_result->box.right;
int y2 = det_result->box.bottom;
rectangle(orig_img, cv::Point(x1, y1), cv::Point(x2, y2),
cv::Scalar(256, 0, 0, 256), 3);
putText(orig_img, text, cv::Point(x1, y1 + 12), cv::FONT_HERSHEY_SIMPLEX,
0.4, cv::Scalar(255, 255, 255));
}
if (!out_path.empty()) {
printf("save detect result to %s\n", out_path.c_str());
imwrite(out_path, orig_img);
}
rknn_outputs_release(ctx, io_num.n_output, outputs);
return detect_result_group;
}
};

View File

@ -0,0 +1,4 @@
<launch>
<!-- <node pkg="rviz" type="rviz" name="rviz" args="-d $(find guangpo_yolo_lidar)/rviz/guangpo.rviz"></node> -->
<node pkg="guangpo_yolo_lidar" type="guangpo_yolo_lidar_node" name="guangpo_yolo_lidar_node" output="screen" ></node>
</launch>

View File

@ -0,0 +1,4 @@
<launch>
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find guangpo_yolo_lidar)/rviz/guangpo.rviz"></node>
<!-- <node pkg="guangpo_yolo_lidar" type="guangpo_yolo_lidar_node" name="guangpo_yolo_lidar_node" output="screen" ></node> -->
</launch>

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 151 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 209 KiB

Binary file not shown.

View File

@ -0,0 +1,77 @@
<?xml version="1.0"?>
<package format="2">
<name>guangpo_yolo_lidar</name>
<version>0.0.0</version>
<description>The guangpo_yolo_lidar package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="firefly@todo.todo">firefly</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/guangpo_yolo_lidar</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>pcl_ros</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>cv_bridge</build_export_depend>
<build_export_depend>pcl_ros</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>cv_bridge</exec_depend>
<exec_depend>pcl_ros</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

View File

@ -0,0 +1,226 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 313
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Name: Time
SyncMode: 0
SyncSource: Image
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /usb_cam/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Alpha: 1
Class: rviz/Axes
Enabled: true
Length: 1
Name: Axes
Radius: 0.10000000149011612
Reference Frame: <Fixed Frame>
Show Trail: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /obstacles_topic
Name: MarkerArray
Namespaces:
{}
Queue Size: 100
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /cloud_ground
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 2.202476739883423
Min Value: 0.08952760696411133
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /cloud_noground
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /detect_img
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /box3d_markers
Name: MarkerArray
Namespaces:
"": true
Queue Size: 100
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 12.246346473693848
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 1.519796371459961
Target Frame: <Fixed Frame>
Yaw: 3.376760959625244
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1115
Hide Left Dock: false
Hide Right Dock: false
Image:
collapsed: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000003c1fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001c2000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650100000203000000cb0000001600fffffffb0000000a0049006d00610067006501000002d4000001280000001600ffffff000000010000010f000003c1fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003c1000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000030700fffffffb0000000800540069006d006501000000000000045000000000000000000000050f000003c100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1920
X: 0
Y: 24

View File

@ -0,0 +1,638 @@
#include <cv_bridge/cv_bridge.h>
#include <filesystem>
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/time_synchronizer.h>
#include <opencv2/opencv.hpp>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Int8.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include "dbscan.hpp"
#include "debugstream.hpp"
#include "yaml_config.h"
#include "yolo_lidar_help.hpp"
std::string model_dianti_name = []() -> std::string {
std::filesystem::path current_dir =
std::filesystem::path(__FILE__).parent_path();
std::filesystem::path model_path =
current_dir / "../model/RK3588/guangpo.rknn";
return model_path;
}();
std::string model_other_name = []() -> std::string {
std::filesystem::path current_dir =
std::filesystem::path(__FILE__).parent_path();
std::filesystem::path model_path =
current_dir / "../model/RK3588/yolov5s-640-640.rknn";
return model_path;
}();
std::string input_path = []() -> std::string {
std::filesystem::path current_dir =
std::filesystem::path(__FILE__).parent_path();
std::filesystem::path img_path = current_dir / "../model/RK3588/889.jpg";
return img_path;
}();
std::vector<std::string> labels_dianti = {"Dianti", "Ren"};
std::vector<std::string> labels_other = {
"person", "bicycle", "car",
"motorcycle", "airplane", "bus",
"train", "truck", "boat",
"traffic light", "fire hydrant", "stop sign",
"parking meter", "bench", "bird",
"cat", "dog", "horse",
"sheep", "cow", "elephant",
"bear", "zebra", "giraffe",
"backpack", "umbrella", "handbag",
"tie", "suitcase", "frisbee",
"skis", "snowboard", "sports ball",
"kite", "baseball bat", "baseball glove",
"skateboard", "surfboard", "tennis racket",
"bottle", "wine glass", "cup",
"fork", "knife", "spoon",
"bowl", "banana", "apple",
"sandwich", "orange", "broccoli",
"carrot", "hot dog", "pizza",
"donut", "cake", "chair",
"couch", "potted plant", "bed",
"dining table", "toilet", "tv",
"laptop", "mouse", "remote",
"keyboard", "cell phone", "microwave",
"oven", "toaster", "sink",
"refrigerator", "book", "clock",
"vase", "scissors", "teddy bear",
"hair drier", "toothbrush"};
#include "debugstream.hpp"
#include "dianti.h"
#include "yolov5.hpp"
class ImageReceiver {
public:
Yolov5 yolo_dianti;
Yolov5 yolo_other;
std::shared_ptr<DistanceEstimator> estimator;
ImageReceiver(ros::NodeHandle &nh) {
img_width = yaml_config["image"]["width"].as<int>();
img_height = yaml_config["image"]["height"].as<int>();
img_distort_enable = yaml_config["img_distort_enable"].as<bool>();
leaf_size = yaml_config["leaf_size"].as<double>();
// 初始化yolo
Init();
yolo_dianti.SetLabels(labels_dianti);
yolo_dianti.LoadModel(model_dianti_name);
yolo_other.SetLabels(labels_other);
yolo_other.LoadModel(model_other_name);
person_density_pub_ = nh.advertise<std_msgs::Int8>(
yaml_config["person_density_topic"].as<std::string>(), 10);
sub_detect_congest_enable_ = nh.subscribe(
yaml_config["detect_congest_enable_topic"].as<std::string>(), 10,
&ImageReceiver::detectCongestCallback, this);
// 初始化订阅话题和回调等
std::string sub_image_topic =
yaml_config["sub_image_topic"].as<std::string>();
std::string sub_pointcloud_topic =
yaml_config["sub_pointcloud_topic"].as<std::string>();
std::string pub_cloud_noground_topic =
yaml_config["pub_cloud_noground_topic"].as<std::string>();
pub_cloud_noground_ =
nh.advertise<sensor_msgs::PointCloud2>(pub_cloud_noground_topic, 10);
std::string pub_box3d_markers_topic =
yaml_config["pub_box3d_markers_topic"].as<std::string>();
pub_3dbox_ = nh.advertise<visualization_msgs::MarkerArray>(
pub_box3d_markers_topic, 10);
std::string send_image_topic =
yaml_config["pub_image_topic"].as<std::string>();
image_pub_ = nh.advertise<sensor_msgs::Image>(send_image_topic, 1);
std::string send_lidar_topic =
yaml_config["pub_lidar_topic"].as<std::string>();
lidar_pub1_ = nh.advertise<sensor_msgs::PointCloud2>(send_lidar_topic, 1);
lidar_pub2_ =
nh.advertise<sensor_msgs::PointCloud2>(send_lidar_topic + "2", 1);
gDebugCol3() << VAR(sub_image_topic, sub_pointcloud_topic);
bool use_bag = yaml_config["use_bag"].as<bool>();
gDebugCol3() << VAR(use_bag);
if (use_bag) {
image_sub_.subscribe(nh, sub_image_topic, 10);
point_cloud_sub_.subscribe(nh, sub_pointcloud_topic, 10);
sync_ = std::make_shared<Sync>(MySyncPolicy(500), image_sub_,
point_cloud_sub_);
double max_time_interval = yaml_config["max_time_interval"].as<double>();
ros::Duration max_interval(max_time_interval);
sync_->setMaxIntervalDuration(max_interval);
sync_->registerCallback(
boost::bind(&ImageReceiver::callback, this, _1, _2));
} else {
// my_image_sub_ =
// nh.subscribe(sub_image_topic, 10, &ImageReceiver::imageCallback,
// this);
// 准备读取图像数据
std::string camera_image_dev =
yaml_config["camera_image_dev"].as<std::string>();
// 打开视频设备
cap = std::make_shared<cv::VideoCapture>(camera_image_dev);
// 检查设备是否打开成功
if (!cap->isOpened()) {
std::cerr << "Failed to open video device!" << std::endl;
std::terminate();
}
// 设置视频帧大小为 1280x720
cap->set(cv::CAP_PROP_FRAME_WIDTH, img_width);
cap->set(cv::CAP_PROP_FRAME_HEIGHT, img_height);
my_pointcloud_sub_ = nh.subscribe(sub_pointcloud_topic, 10,
&ImageReceiver::lidarCallback, this);
}
}
~ImageReceiver() {
if (cap) {
cap->release();
}
}
void detectCongestCallback(const std_msgs::Bool::ConstPtr &msg) {
ROS_INFO("Received /detect_congest_enable: %s",
msg->data ? "true" : "false");
enable_detect_congest = msg->data;
}
void SendImage(const cv::Mat &image) {
// 将cv::Mat图像转换为sensor_msgs::Image消息
sensor_msgs::ImagePtr msg =
cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
msg->header.stamp = ros::Time::now();
// 发布图像消息
image_pub_.publish(msg);
ROS_INFO("Image published!");
}
void SendLidar(ros::Publisher &pub,
const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
// 发送点云数组
sensor_msgs::PointCloud2 msg;
pcl::toROSMsg(*cloud, msg);
msg.header.frame_id = "map"; // 设置坐标系
msg.header.stamp = ros::Time::now();
pub.publish(msg);
}
void lidarCallback(const sensor_msgs::PointCloud2ConstPtr &point_cloud_msg) {
ROS_INFO("Received lidar!");
// 接收雷达后,需要从驱动读取图像 1280x720
// 创建用于存储图像的 Mat 对象
cv::Mat image;
// 读取一帧图像
if (!cap->read(image)) {
std::cerr << "Failed to read frame from video device!" << std::endl;
std::terminate();
}
// 将点云转换为PCL点云
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*point_cloud_msg, *cloud);
// 调用统计接口
CallBackImageAndLidar(image, cloud);
}
void imageCallback(const sensor_msgs::ImageConstPtr &msg) {
ROS_INFO("Received image!");
// 在此处添加你的图像处理代码
try {
// 使用cv_bridge将sensor_msgs::Image转换为cv::Mat
// cv_bridge::CvImagePtr cv_ptr =
// cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
// cv::Mat image_ = cv_ptr->image;
// DetectImage(image_);
} catch (cv_bridge::Exception &e) {
ROS_ERROR("cv_bridge exception: %s", e.what());
}
}
void PublishObstacles(
const std::vector<Eigen::Vector3f> &obstacle_centroids,
const std::vector<Eigen::Vector3f> &obstacle_sizes,
const std::vector<Eigen::Quaternionf> &obstacle_orientations) {
visualization_msgs::MarkerArray marker_array;
// 首先发布一个DELETEALL命令,删除上次发布的所有障碍物标记
visualization_msgs::Marker delete_marker;
delete_marker.header.frame_id = "map";
delete_marker.action = visualization_msgs::Marker::DELETEALL;
marker_array.markers.push_back(delete_marker);
pub_3dbox_.publish(marker_array);
marker_array.markers.clear(); // 清空marker_array
for (size_t i = 0; i < obstacle_centroids.size(); ++i) {
visualization_msgs::Marker marker;
marker.header.frame_id = "map";
marker.type = visualization_msgs::Marker::CUBE;
marker.action = visualization_msgs::Marker::ADD;
marker.id = i;
marker.pose.position.x = obstacle_centroids[i].x();
marker.pose.position.y = obstacle_centroids[i].y();
marker.pose.position.z = obstacle_centroids[i].z();
marker.pose.orientation.x = obstacle_orientations[i].x();
marker.pose.orientation.y = obstacle_orientations[i].y();
marker.pose.orientation.z = obstacle_orientations[i].z();
marker.pose.orientation.w = obstacle_orientations[i].w();
marker.scale.x = obstacle_sizes[i].x();
marker.scale.y = obstacle_sizes[i].y();
marker.scale.z = obstacle_sizes[i].z();
marker.color.r = 1.0f;
marker.color.g = 0.0f;
marker.color.b = 0.0f;
marker.color.a = 0.3;
marker_array.markers.push_back(marker);
}
pub_3dbox_.publish(marker_array);
}
void callback(const sensor_msgs::ImageConstPtr &image_msg,
const sensor_msgs::PointCloud2ConstPtr &point_cloud_msg) {
// 在这里处理接收到的图像和点云数据
// 打印时间戳单位ms
ROS_INFO("Image timestamp: %f ms", image_msg->header.stamp.toSec() * 1000);
ROS_INFO("Point cloud timestamp: %f ms",
point_cloud_msg->header.stamp.toSec() * 1000);
// 将图像转换为cv::Mat
cv_bridge::CvImagePtr cv_ptr;
cv::Mat image;
try {
cv_ptr =
cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::BGR8);
image = cv_ptr->image;
// 在这里可以对图像进行处理或者显示
} catch (cv_bridge::Exception &e) {
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
// 将点云转换为PCL点云
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*point_cloud_msg, *cloud);
// 调用统计接口
CallBackImageAndLidar(image, cloud);
}
// 返回计算出来的相关联的人数
int GetPersonNumber(const detect_result_group_t &detect_result_group) {
int res{0};
static double person_distance = yaml_config["person_distance"].as<double>();
double x, y, w, h;
std::string class_name;
for (int i = 0; i < detect_result_group.count; i++) {
const detect_result_t *det_result = &(detect_result_group.results[i]);
x = (double)(det_result->box.left + det_result->box.right) / 2.0 /
img_width;
y = (double)(det_result->box.top + det_result->box.bottom) / 2.0 /
img_height;
w = (double)std::abs(det_result->box.right - det_result->box.left) /
img_width;
h = (double)std::abs(det_result->box.bottom - det_result->box.top) /
img_height;
class_name = det_result->name;
if (class_name == "person") {
const auto position_3d =
estimator->Get3DPosition(x, y, w, h, class_name);
double distance = position_3d.norm();
if (distance <= person_distance) {
res++;
}
}
}
return res;
}
// 统一接口
void CallBackImageAndLidar(cv::Mat &image,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
TIME_BEGIN(CallBackImageAndLidar);
TIME_BEGIN(preprecess);
// 先对图像去畸变
if (img_distort_enable) {
help.UndistortImage(image);
}
// 对点云进行降采样
if (leaf_size > 0) {
// 创建 VoxelGrid 滤波器
pcl::VoxelGrid<pcl::PointXYZ> vg;
vg.setInputCloud(cloud);
vg.setLeafSize(leaf_size, leaf_size, leaf_size);
vg.filter(*cloud);
}
TIME_END(preprecess);
// yolo_dianti.Infer(image, "");
detect_result_group_t detect_result_group;
TIME_BEGIN(infer);
detect_result_group = yolo_other.Infer(image, "");
TIME_END(infer);
TIME_BEGIN(send_image);
SendImage(image);
TIME_END(send_image);
// 开启电梯拥挤度检测
if (enable_detect_congest) {
int person_density = GetPersonNumber(detect_result_group);
gDebugCol4(person_density);
// 发布person_density话题
std_msgs::Int8 density_msg;
density_msg.data = person_density;
person_density_pub_.publish(density_msg);
}
// 开始计算3d障碍物
TIME_BEGIN_MS(deal_lidar);
// 如果需要去除地面的点云
static bool remove_ground_points_enable =
yaml_config["remove_ground_points_enable"].as<bool>();
if (remove_ground_points_enable) {
static int max_iterations = yaml_config["max_iterations"].as<double>();
static double remove_ground_height =
yaml_config["remove_ground_height"].as<double>();
// gDebug() << VAR(max_iterations, remove_ground_height);
auto [noground, ground] = RansacSegmentPlane<pcl::PointXYZ>(
cloud, max_iterations, remove_ground_height);
SendLidar(pub_cloud_noground_, noground);
// 把cloud赋值成noground,后面全部基于非地面点云做
*cloud = *noground;
}
gDebugWarn() << G_FILE_LINE;
std::vector<mybox> box3ds;
gDebugWarn() << G_FILE_LINE;
for (int i = 0; i < detect_result_group.count; i++) {
const detect_result_t *det_result = &(detect_result_group.results[i]);
// box.x = (double)(det_result->box.left + det_result->box.right) / 2.0 /
// img_width;
// box.y = (double)(det_result->box.top + det_result->box.bottom) / 2.0 /
// img_height;
// box.w = (double)std::abs(det_result->box.right - det_result->box.left)
// /
// img_width;
// box.h = (double)std::abs(det_result->box.bottom - det_result->box.top)
// /
// img_height;
mybox box;
box.rect = cv::Rect(det_result->box.left, det_result->box.top,
det_result->box.right - det_result->box.left,
det_result->box.bottom - det_result->box.top);
static const double shrink_factor = 0.1;
box.small_rect.x = box.rect.x + shrink_factor * box.rect.width / 2.0;
box.small_rect.y = box.rect.y + shrink_factor * box.rect.height / 2.0;
box.small_rect.width = box.rect.width * (1 - shrink_factor);
box.small_rect.height = box.rect.height * (1 - shrink_factor);
std::string class_name = det_result->name;
if (class_name == "person" || class_name == "bicycle" ||
class_name == "car" || class_name == "motorcycle" ||
class_name == "cat" || class_name == "dog") {
box.label = class_name;
box3ds.push_back(box);
}
}
gDebugWarn() << G_FILE_LINE;
Eigen::Vector3d X;
for (pcl::PointCloud<pcl::PointXYZ>::const_iterator it =
cloud->points.begin();
it != cloud->points.end(); it++) {
// if (it->x > 20 || it->x < 0.0 || std::abs(it->y) > 20) {
// continue;
// }
// 筛选掉一些不符合逻辑的点
static double min_x = yaml_config["lidar2camera"]["min_x"].as<double>();
static double max_x = yaml_config["lidar2camera"]["max_x"].as<double>();
static double min_y = yaml_config["lidar2camera"]["min_y"].as<double>();
static double max_y = yaml_config["lidar2camera"]["max_y"].as<double>();
static double min_z = yaml_config["lidar2camera"]["min_z"].as<double>();
static double max_z = yaml_config["lidar2camera"]["max_z"].as<double>();
if (it->x < min_x || it->x > max_x || it->x < min_y || it->x > max_y ||
it->x < min_z || it->x > max_z) {
continue;
}
X[0] = it->x;
X[1] = it->y;
X[2] = it->z;
auto Y = help.ProjectLidarPointToCameraPixel(X);
// 计算出的点云在像素平面上的点
cv::Point pt;
pt.x = Y[0] / Y[2];
pt.y = Y[1] / Y[2];
int only_one_box_contain = 0;
int box_id = 0;
for (int i = 0; i < box3ds.size(); i++) {
if (box3ds[i].small_rect.contains(pt)) {
box_id = i;
++only_one_box_contain;
if (only_one_box_contain > 1) {
break;
}
}
}
if (only_one_box_contain == 1) {
box3ds.at(box_id).lidar_points->push_back(*it);
}
// float val = it->x;
// float maxVal = 3;
// if (val < maxVal) {
// cv::circle(image, pt, 1, cv::Scalar(0, 255, 0), -1);
// } else {
// cv::circle(image, pt, 1, cv::Scalar(0, 0, 255), -1);
// }
// int red = std::min(255, (int)(255 * abs((val - maxVal) / maxVal)));
// int green =
// std::min(255, (int)(255 * (1 - abs((val - maxVal) / maxVal))));
// cv::circle(image, pt, 1, cv::Scalar(0, green, red), -1);
}
gDebugWarn() << G_FILE_LINE;
pcl::PointCloud<pcl::PointXYZ>::Ptr combined_lidar_points(
new pcl::PointCloud<pcl::PointXYZ>);
for (int i = 0; i < box3ds.size(); i++) {
const auto &box = box3ds[i];
*combined_lidar_points += *box.lidar_points;
}
SendLidar(lidar_pub1_, combined_lidar_points);
gDebugWarn() << G_FILE_LINE;
pcl::PointCloud<pcl::PointXYZ>::Ptr combined_lidar_points2(
new pcl::PointCloud<pcl::PointXYZ>);
// 点云聚类
for (int i = 0; i < box3ds.size(); i++) {
auto &box = box3ds[i];
box.lidar_cluster = EuclideanCluster(box.lidar_points);
*combined_lidar_points2 += *box.lidar_cluster;
}
SendLidar(lidar_pub2_, combined_lidar_points2);
gDebugWarn() << G_FILE_LINE;
// 把点云提取出3dbox
static int obb_omp_threads = yaml_config["obb_omp_threads"].as<int>();
// omp_set_num_threads(obb_omp_threads);
// #pragma omp parallel for
for (int i = 0; i < box3ds.size(); i++) {
auto &box = box3ds[i];
ExtractObstacles(box.lidar_cluster, box.obstacle_centroids,
box.obstacle_sizes, box.obstacle_orientations, true);
}
gDebugWarn() << G_FILE_LINE;
std::vector<Eigen::Vector3f> obstacle_centroids;
std::vector<Eigen::Vector3f> obstacle_sizes;
std::vector<Eigen::Quaternionf> obstacle_orientations;
for (int i = 0; i < box3ds.size(); i++) {
auto &box = box3ds[i];
// 如果聚类失败了(点太少或者不满足要求)
if (box.lidar_cluster->points.empty()) {
continue;
}
obstacle_centroids.push_back(box.obstacle_centroids);
obstacle_sizes.push_back(box.obstacle_sizes);
obstacle_orientations.push_back(box.obstacle_orientations);
}
gDebugWarn() << G_FILE_LINE;
PublishObstacles(obstacle_centroids, obstacle_sizes, obstacle_orientations);
}
void Init() {
Eigen::Matrix3d camera_matrix;
camera_matrix << yaml_config["camera_in_param"]["dx"].as<double>(), 0.0,
yaml_config["camera_in_param"]["u0"].as<double>(), 0.0,
yaml_config["camera_in_param"]["dy"].as<double>(),
yaml_config["camera_in_param"]["v0"].as<double>(), 0.0, 0.0, 1.0;
gDebug(camera_matrix);
estimator = std::make_shared<DistanceEstimator>(camera_matrix, img_width,
img_height);
}
void DetectImage(cv::Mat &img) {
TIME_BEGIN_MS(DetectImage);
detect_result_group_t detect_result_group;
detect_result_group = yolo_dianti.Infer(img, "");
TIME_END(DetectImage);
int img_width = img.cols;
int img_height = img.rows;
// gxt: add my process here ==============begin
// 相机内参
std::vector<Box> rens;
std::vector<Box> diantis;
gDebug(detect_result_group.count);
for (int i = 0; i < detect_result_group.count; i++) {
detect_result_t *det_result = &(detect_result_group.results[i]);
Box box;
box.x = (double)(det_result->box.left + det_result->box.right) / 2.0 /
img_width;
box.y = (double)(det_result->box.top + det_result->box.bottom) / 2.0 /
img_height;
box.w = (double)std::abs(det_result->box.right - det_result->box.left) /
img_width;
box.h = (double)std::abs(det_result->box.bottom - det_result->box.top) /
img_height;
std::string class_name = det_result->name;
if (class_name == "Dianti") {
diantis.push_back(box);
} else if (class_name == "Ren") {
rens.push_back(box);
}
}
TIME_END(DetectImage);
DealImage(*estimator, img, rens, diantis);
TIME_END(DetectImage);
// gxt: add my process here ==============end
SendImage(img);
#if DEBUG
printf("save detect result to %s\n", out_path.c_str());
imwrite(out_path, img);
#endif
}
public:
CoordinateHelp help;
private:
int img_width;
int img_height;
double leaf_size;
bool img_distort_enable = true;
ros::Subscriber my_image_sub_;
ros::Subscriber my_pointcloud_sub_;
// 订阅话题/detect_congest_enable
ros::Subscriber sub_detect_congest_enable_;
bool enable_detect_congest = true;
ros::Publisher person_density_pub_;
ros::Publisher image_pub_;
ros::Publisher lidar_pub1_;
ros::Publisher lidar_pub2_;
ros::Publisher pub_cloud_noground_;
ros::Publisher pub_3dbox_;
message_filters::Subscriber<sensor_msgs::Image> image_sub_;
message_filters::Subscriber<sensor_msgs::PointCloud2> point_cloud_sub_;
// 订阅图像和点云话题
typedef message_filters::sync_policies::ApproximateTime<
sensor_msgs::Image, sensor_msgs::PointCloud2>
MySyncPolicy;
typedef message_filters::Synchronizer<MySyncPolicy> Sync;
std::shared_ptr<Sync> sync_;
std::shared_ptr<cv::VideoCapture> cap;
};
/*-------------------------------------------
Main Functions
-------------------------------------------*/
int main(int argc, char **argv) {
ros::init(argc, argv, "image_receiver");
ros::NodeHandle nh;
ImageReceiver image_receiver(nh);
// 把它当作warmup了
if (yaml_config["warmup"].as<bool>()) {
cv::Mat image = cv::imread(input_path);
for (int n = 10; n >= 0; n--) {
image_receiver.DetectImage(image);
}
}
ros::spin();
return 0;
}

View File

@ -0,0 +1,420 @@
// Copyright (c) 2021 by Rockchip Electronics Co., Ltd. All Rights Reserved.
//
// 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.
/*-------------------------------------------
Includes
-------------------------------------------*/
#include <dlfcn.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/time.h>
#define _BASETSD_H
#include "RgaUtils.h"
#include "postprocess.h"
#include "rknn_api.h"
#include "preprocess.h"
#include "dianti.h"
#include "debugstream.hpp"
#define PERF_WITH_POST 1
/*-------------------------------------------
Functions
-------------------------------------------*/
static void dump_tensor_attr(rknn_tensor_attr *attr)
{
std::string shape_str = attr->n_dims < 1 ? "" : std::to_string(attr->dims[0]);
for (int i = 1; i < attr->n_dims; ++i)
{
shape_str += ", " + std::to_string(attr->dims[i]);
}
printf(" index=%d, name=%s, n_dims=%d, dims=[%s], n_elems=%d, size=%d, w_stride = %d, size_with_stride=%d, fmt=%s, "
"type=%s, qnt_type=%s, "
"zp=%d, scale=%f\n",
attr->index, attr->name, attr->n_dims, shape_str.c_str(), attr->n_elems, attr->size, attr->w_stride,
attr->size_with_stride, get_format_string(attr->fmt), get_type_string(attr->type),
get_qnt_type_string(attr->qnt_type), attr->zp, attr->scale);
}
double __get_us(struct timeval t) { return (t.tv_sec * 1000000 + t.tv_usec); }
static unsigned char *load_data(FILE *fp, size_t ofst, size_t sz)
{
unsigned char *data;
int ret;
data = NULL;
if (NULL == fp)
{
return NULL;
}
ret = fseek(fp, ofst, SEEK_SET);
if (ret != 0)
{
printf("blob seek failure.\n");
return NULL;
}
data = (unsigned char *)malloc(sz);
if (data == NULL)
{
printf("buffer malloc failure.\n");
return NULL;
}
ret = fread(data, 1, sz, fp);
return data;
}
static unsigned char *load_model(const char *filename, int *model_size)
{
FILE *fp;
unsigned char *data;
fp = fopen(filename, "rb");
if (NULL == fp)
{
printf("Open file %s failed.\n", filename);
return NULL;
}
fseek(fp, 0, SEEK_END);
int size = ftell(fp);
data = load_data(fp, 0, size);
fclose(fp);
*model_size = size;
return data;
}
static int saveFloat(const char *file_name, float *output, int element_size)
{
FILE *fp;
fp = fopen(file_name, "w");
for (int i = 0; i < element_size; i++)
{
fprintf(fp, "%.6f\n", output[i]);
}
fclose(fp);
return 0;
}
/*-------------------------------------------
Main Functions
-------------------------------------------*/
int main(int argc, char **argv)
{
if (argc < 3)
{
printf("Usage: %s <rknn model> <input_image_path> <resize/letterbox> <output_image_path>\n", argv[0]);
return -1;
}
int ret;
rknn_context ctx;
size_t actual_size = 0;
int img_width = 0;
int img_height = 0;
int img_channel = 0;
const float nms_threshold = NMS_THRESH; // 默认的NMS阈值
const float box_conf_threshold = BOX_THRESH; // 默认的置信度阈值
struct timeval start_time, stop_time;
char *model_name = (char *)argv[1];
char *input_path = argv[2];
std::string option = "letterbox";
std::string out_path = "./out.jpg";
if (argc >= 4)
{
option = argv[3];
}
if (argc >= 5)
{
out_path = argv[4];
}
// init rga context
rga_buffer_t src;
rga_buffer_t dst;
memset(&src, 0, sizeof(src));
memset(&dst, 0, sizeof(dst));
printf("post process config: box_conf_threshold = %.2f, nms_threshold = %.2f\n", box_conf_threshold, nms_threshold);
/* Create the neural network */
printf("Loading mode...\n");
int model_data_size = 0;
unsigned char *model_data = load_model(model_name, &model_data_size);
ret = rknn_init(&ctx, model_data, model_data_size, 0, NULL);
if (ret < 0)
{
printf("rknn_init error ret=%d\n", ret);
return -1;
}
rknn_sdk_version version;
ret = rknn_query(ctx, RKNN_QUERY_SDK_VERSION, &version, sizeof(rknn_sdk_version));
if (ret < 0)
{
printf("rknn_init error ret=%d\n", ret);
return -1;
}
printf("sdk version: %s driver version: %s\n", version.api_version, version.drv_version);
rknn_input_output_num io_num;
ret = rknn_query(ctx, RKNN_QUERY_IN_OUT_NUM, &io_num, sizeof(io_num));
if (ret < 0)
{
printf("rknn_init error ret=%d\n", ret);
return -1;
}
printf("model input num: %d, output num: %d\n", io_num.n_input, io_num.n_output);
rknn_tensor_attr input_attrs[io_num.n_input];
memset(input_attrs, 0, sizeof(input_attrs));
for (int i = 0; i < io_num.n_input; i++)
{
input_attrs[i].index = i;
ret = rknn_query(ctx, RKNN_QUERY_INPUT_ATTR, &(input_attrs[i]), sizeof(rknn_tensor_attr));
if (ret < 0)
{
printf("rknn_init error ret=%d\n", ret);
return -1;
}
dump_tensor_attr(&(input_attrs[i]));
}
rknn_tensor_attr output_attrs[io_num.n_output];
memset(output_attrs, 0, sizeof(output_attrs));
for (int i = 0; i < io_num.n_output; i++)
{
output_attrs[i].index = i;
ret = rknn_query(ctx, RKNN_QUERY_OUTPUT_ATTR, &(output_attrs[i]), sizeof(rknn_tensor_attr));
dump_tensor_attr(&(output_attrs[i]));
}
int channel = 3;
int width = 0;
int height = 0;
if (input_attrs[0].fmt == RKNN_TENSOR_NCHW)
{
printf("model is NCHW input fmt\n");
channel = input_attrs[0].dims[1];
height = input_attrs[0].dims[2];
width = input_attrs[0].dims[3];
}
else
{
printf("model is NHWC input fmt\n");
height = input_attrs[0].dims[1];
width = input_attrs[0].dims[2];
channel = input_attrs[0].dims[3];
}
printf("model input height=%d, width=%d, channel=%d\n", height, width, channel);
rknn_input inputs[1];
memset(inputs, 0, sizeof(inputs));
inputs[0].index = 0;
inputs[0].type = RKNN_TENSOR_UINT8;
inputs[0].size = width * height * channel;
inputs[0].fmt = RKNN_TENSOR_NHWC;
inputs[0].pass_through = 0;
// 读取图片
printf("Read %s ...\n", input_path);
cv::Mat orig_img = cv::imread(input_path, 1);
if (!orig_img.data)
{
printf("cv::imread %s fail!\n", input_path);
return -1;
}
cv::Mat img;
cv::cvtColor(orig_img, img, cv::COLOR_BGR2RGB);
img_width = img.cols;
img_height = img.rows;
printf("img width = %d, img height = %d\n", img_width, img_height);
// 指定目标大小和预处理方式,默认使用LetterBox的预处理
BOX_RECT pads;
memset(&pads, 0, sizeof(BOX_RECT));
cv::Size target_size(width, height);
cv::Mat resized_img(target_size.height, target_size.width, CV_8UC3);
// 计算缩放比例
float scale_w = (float)target_size.width / img.cols;
float scale_h = (float)target_size.height / img.rows;
if (img_width != width || img_height != height)
{
// 直接缩放采用RGA加速
if (option == "resize")
{
printf("resize image by rga\n");
ret = resize_rga(src, dst, img, resized_img, target_size);
if (ret != 0)
{
fprintf(stderr, "resize with rga error\n");
return -1;
}
// 保存预处理图片
cv::imwrite("resize_input.jpg", resized_img);
}
else if (option == "letterbox")
{
printf("resize image with letterbox\n");
float min_scale = std::min(scale_w, scale_h);
scale_w = min_scale;
scale_h = min_scale;
letterbox(img, resized_img, pads, min_scale, target_size);
// 保存预处理图片
cv::imwrite("letterbox_input.jpg", resized_img);
}
else
{
fprintf(stderr, "Invalid resize option. Use 'resize' or 'letterbox'.\n");
return -1;
}
inputs[0].buf = resized_img.data;
}
else
{
inputs[0].buf = img.data;
}
gettimeofday(&start_time, NULL);
rknn_inputs_set(ctx, io_num.n_input, inputs);
rknn_output outputs[io_num.n_output];
memset(outputs, 0, sizeof(outputs));
for (int i = 0; i < io_num.n_output; i++)
{
outputs[i].index = i;
outputs[i].want_float = 0;
}
// 执行推理
ret = rknn_run(ctx, NULL);
ret = rknn_outputs_get(ctx, io_num.n_output, outputs, NULL);
gettimeofday(&stop_time, NULL);
printf("once run use %f ms\n", (__get_us(stop_time) - __get_us(start_time)) / 1000);
// 后处理
detect_result_group_t detect_result_group;
std::vector<float> out_scales;
std::vector<int32_t> out_zps;
for (int i = 0; i < io_num.n_output; ++i)
{
out_scales.push_back(output_attrs[i].scale);
out_zps.push_back(output_attrs[i].zp);
}
post_process((int8_t *)outputs[0].buf, (int8_t *)outputs[1].buf, (int8_t *)outputs[2].buf, height, width,
box_conf_threshold, nms_threshold, pads, scale_w, scale_h, out_zps, out_scales, &detect_result_group);
// 画框和概率
char text[256];
for (int i = 0; i < detect_result_group.count; i++)
{
detect_result_t *det_result = &(detect_result_group.results[i]);
sprintf(text, "%s %.1f%%", det_result->name, det_result->prop * 100);
printf("%s @ (%d %d %d %d) %f\n", det_result->name, det_result->box.left, det_result->box.top,
det_result->box.right, det_result->box.bottom, det_result->prop);
int x1 = det_result->box.left;
int y1 = det_result->box.top;
int x2 = det_result->box.right;
int y2 = det_result->box.bottom;
rectangle(orig_img, cv::Point(x1, y1), cv::Point(x2, y2), cv::Scalar(256, 0, 0, 256), 3);
putText(orig_img, text, cv::Point(x1, y1 + 12), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(255, 255, 255));
}
// gxt: add my process here ==============begin
// 相机内参
Eigen::Matrix3d camera_matrix;
camera_matrix << 787.22316869, 0.0, 628.91534144, 0.0, 793.45182,
313.46301416, 0.0, 0.0, 1.0;
// int my_width=orig_img.cols;
// int my_height=orig_img.rows;
DistanceEstimator estimator(camera_matrix, img_width, img_height);
std::vector<Box> rens;
std::vector<Box> diantis;
gDebug(detect_result_group.count);
for (int i = 0; i < detect_result_group.count; i++)
{
detect_result_t *det_result = &(detect_result_group.results[i]);
// sprintf(text, "%s %.1f%%", det_result->name, det_result->prop * 100);
// printf("%s @ (%d %d %d %d) %f\n", det_result->name, det_result->box.left, det_result->box.top,
// det_result->box.right, det_result->box.bottom, det_result->prop);
Box box;
box.x=(double)(det_result->box.left+det_result->box.right)/2.0/img_width;
box.y=(double)(det_result->box.top+det_result->box.bottom)/2.0/img_height;
box.w=(double)std::abs(det_result->box.right-det_result->box.left)/img_width;
box.h=(double)std::abs(det_result->box.bottom-det_result->box.top)/img_height;
std::string class_name=det_result->name;
if(class_name=="Dianti") {
diantis.push_back(box);
} else if(class_name=="Ren") {
rens.push_back(box);
}
// int x1 = det_result->box.left;
// int y1 = det_result->box.top;
// int x2 = det_result->box.right;
// int y2 = det_result->box.bottom;
// rectangle(orig_img, cv::Point(x1, y1), cv::Point(x2, y2), cv::Scalar(256, 0, 0, 256), 3);
// putText(orig_img, text, cv::Point(x1, y1 + 12), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(255, 255, 255));
}
DealImage(estimator, orig_img, rens, diantis);
// gxt: add my process here ==============end
printf("save detect result to %s\n", out_path.c_str());
imwrite(out_path, orig_img);
ret = rknn_outputs_release(ctx, io_num.n_output, outputs);
// 耗时统计
int test_count = 10;
gettimeofday(&start_time, NULL);
for (int i = 0; i < test_count; ++i)
{
rknn_inputs_set(ctx, io_num.n_input, inputs);
ret = rknn_run(ctx, NULL);
ret = rknn_outputs_get(ctx, io_num.n_output, outputs, NULL);
#if PERF_WITH_POST
post_process((int8_t *)outputs[0].buf, (int8_t *)outputs[1].buf, (int8_t *)outputs[2].buf, height, width,
box_conf_threshold, nms_threshold, pads, scale_w, scale_h, out_zps, out_scales, &detect_result_group);
#endif
ret = rknn_outputs_release(ctx, io_num.n_output, outputs);
}
gettimeofday(&stop_time, NULL);
printf("loop count = %d , average run %f ms\n", test_count,
(__get_us(stop_time) - __get_us(start_time)) / 1000.0 / test_count);
deinitPostProcess();
// release
ret = rknn_destroy(ctx);
if (model_data)
{
free(model_data);
}
return 0;
}

View File

@ -0,0 +1,37 @@
#include "yolov5.hpp"
#include <cv_bridge/cv_bridge.h>
#include <filesystem>
#include <opencv2/opencv.hpp>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
std::string model_name = []() -> std::string {
std::filesystem::path current_dir =
std::filesystem::path(__FILE__).parent_path();
std::filesystem::path model_path =
current_dir / "../model/RK3588/guangpo.rknn";
return model_path;
}();
std::string input_path = []() -> std::string {
std::filesystem::path current_dir =
std::filesystem::path(__FILE__).parent_path();
std::filesystem::path img_path = current_dir / "../model/RK3588/889.jpg";
return img_path;
}();
int main(int argc, char **argv) {
ros::init(argc, argv, "main_test");
ros::NodeHandle nh;
Yolov5 yolo;
std::cout << "yolo begin" << std::endl;
yolo.SetLabels({"Dianti", "Ren"});
yolo.LoadModel(model_name);
cv::Mat image = cv::imread(input_path, 1);
yolo.Infer(image, "output.jpg");
ros::spin();
return 0;
}

View File

@ -0,0 +1,385 @@
// Copyright (c) 2021 by Rockchip Electronics Co., Ltd. All Rights Reserved.
//
// 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.
#include "postprocess.h"
#include <math.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/time.h>
#include <set>
#include <vector>
#include <string>
#include <cstring>
// not use
// #define LABEL_NALE_TXT_PATH ""
// std::vector<std::string> mylabels ={"Dianti","Ren"};
// static char *labels[OBJ_CLASS_NUM];
const int anchor0[6] = {10, 13, 16, 30, 33, 23};
const int anchor1[6] = {30, 61, 62, 45, 59, 119};
const int anchor2[6] = {116, 90, 156, 198, 373, 326};
inline static int clamp(float val, int min, int max) { return val > min ? (val < max ? val : max) : min; }
char *readLine(FILE *fp, char *buffer, int *len)
{
int ch;
int i = 0;
size_t buff_len = 0;
buffer = (char *)malloc(buff_len + 1);
if (!buffer)
return NULL; // Out of memory
while ((ch = fgetc(fp)) != '\n' && ch != EOF)
{
buff_len++;
void *tmp = realloc(buffer, buff_len + 1);
if (tmp == NULL)
{
free(buffer);
return NULL; // Out of memory
}
buffer = (char *)tmp;
buffer[i] = (char)ch;
i++;
}
buffer[i] = '\0';
*len = buff_len;
// Detect end
if (ch == EOF && (i == 0 || ferror(fp)))
{
free(buffer);
return NULL;
}
return buffer;
}
int readLines(const char *fileName, char *lines[], int max_line)
{
FILE *file = fopen(fileName, "r");
char *s;
int i = 0;
int n = 0;
if (file == NULL)
{
printf("Open %s fail!\n", fileName);
return -1;
}
while ((s = readLine(file, s, &n)) != NULL)
{
lines[i++] = s;
if (i >= max_line)
break;
}
fclose(file);
return i;
}
int loadLabelName(const char *locationFilename, char *label[])
{
printf("loadLabelName %s\n", locationFilename);
readLines(locationFilename, label, OBJ_CLASS_NUM);
return 0;
}
static float CalculateOverlap(float xmin0, float ymin0, float xmax0, float ymax0, float xmin1, float ymin1, float xmax1,
float ymax1)
{
float w = fmax(0.f, fmin(xmax0, xmax1) - fmax(xmin0, xmin1) + 1.0);
float h = fmax(0.f, fmin(ymax0, ymax1) - fmax(ymin0, ymin1) + 1.0);
float i = w * h;
float u = (xmax0 - xmin0 + 1.0) * (ymax0 - ymin0 + 1.0) + (xmax1 - xmin1 + 1.0) * (ymax1 - ymin1 + 1.0) - i;
return u <= 0.f ? 0.f : (i / u);
}
static int nms(int validCount, std::vector<float> &outputLocations, std::vector<int> classIds, std::vector<int> &order,
int filterId, float threshold)
{
for (int i = 0; i < validCount; ++i)
{
if (order[i] == -1 || classIds[i] != filterId)
{
continue;
}
int n = order[i];
for (int j = i + 1; j < validCount; ++j)
{
int m = order[j];
if (m == -1 || classIds[i] != filterId)
{
continue;
}
float xmin0 = outputLocations[n * 4 + 0];
float ymin0 = outputLocations[n * 4 + 1];
float xmax0 = outputLocations[n * 4 + 0] + outputLocations[n * 4 + 2];
float ymax0 = outputLocations[n * 4 + 1] + outputLocations[n * 4 + 3];
float xmin1 = outputLocations[m * 4 + 0];
float ymin1 = outputLocations[m * 4 + 1];
float xmax1 = outputLocations[m * 4 + 0] + outputLocations[m * 4 + 2];
float ymax1 = outputLocations[m * 4 + 1] + outputLocations[m * 4 + 3];
float iou = CalculateOverlap(xmin0, ymin0, xmax0, ymax0, xmin1, ymin1, xmax1, ymax1);
if (iou > threshold)
{
order[j] = -1;
}
}
}
return 0;
}
static int quick_sort_indice_inverse(std::vector<float> &input, int left, int right, std::vector<int> &indices)
{
float key;
int key_index;
int low = left;
int high = right;
if (left < right)
{
key_index = indices[left];
key = input[left];
while (low < high)
{
while (low < high && input[high] <= key)
{
high--;
}
input[low] = input[high];
indices[low] = indices[high];
while (low < high && input[low] >= key)
{
low++;
}
input[high] = input[low];
indices[high] = indices[low];
}
input[low] = key;
indices[low] = key_index;
quick_sort_indice_inverse(input, left, low - 1, indices);
quick_sort_indice_inverse(input, low + 1, right, indices);
}
return low;
}
static float sigmoid(float x) { return 1.0 / (1.0 + expf(-x)); }
static float unsigmoid(float y) { return -1.0 * logf((1.0 / y) - 1.0); }
inline static int32_t __clip(float val, float min, float max)
{
float f = val <= min ? min : (val >= max ? max : val);
return f;
}
static int8_t qnt_f32_to_affine(float f32, int32_t zp, float scale)
{
float dst_val = (f32 / scale) + zp;
int8_t res = (int8_t)__clip(dst_val, -128, 127);
return res;
}
static float deqnt_affine_to_f32(int8_t qnt, int32_t zp, float scale) { return ((float)qnt - (float)zp) * scale; }
static int process(int8_t *input, int *anchor, int grid_h, int grid_w, int height, int width, int stride,
std::vector<float> &boxes, std::vector<float> &objProbs, std::vector<int> &classId, float threshold,
int32_t zp, float scale)
{
int validCount = 0;
int grid_len = grid_h * grid_w;
int8_t thres_i8 = qnt_f32_to_affine(threshold, zp, scale);
for (int a = 0; a < 3; a++)
{
for (int i = 0; i < grid_h; i++)
{
for (int j = 0; j < grid_w; j++)
{
int8_t box_confidence = input[(PROP_BOX_SIZE * a + 4) * grid_len + i * grid_w + j];
if (box_confidence >= thres_i8)
{
int offset = (PROP_BOX_SIZE * a) * grid_len + i * grid_w + j;
int8_t *in_ptr = input + offset;
float box_x = (deqnt_affine_to_f32(*in_ptr, zp, scale)) * 2.0 - 0.5;
float box_y = (deqnt_affine_to_f32(in_ptr[grid_len], zp, scale)) * 2.0 - 0.5;
float box_w = (deqnt_affine_to_f32(in_ptr[2 * grid_len], zp, scale)) * 2.0;
float box_h = (deqnt_affine_to_f32(in_ptr[3 * grid_len], zp, scale)) * 2.0;
box_x = (box_x + j) * (float)stride;
box_y = (box_y + i) * (float)stride;
box_w = box_w * box_w * (float)anchor[a * 2];
box_h = box_h * box_h * (float)anchor[a * 2 + 1];
box_x -= (box_w / 2.0);
box_y -= (box_h / 2.0);
int8_t maxClassProbs = in_ptr[5 * grid_len];
int maxClassId = 0;
for (int k = 1; k < OBJ_CLASS_NUM; ++k)
{
int8_t prob = in_ptr[(5 + k) * grid_len];
if (prob > maxClassProbs)
{
maxClassId = k;
maxClassProbs = prob;
}
}
if (maxClassProbs > thres_i8)
{
objProbs.push_back((deqnt_affine_to_f32(maxClassProbs, zp, scale)) * (deqnt_affine_to_f32(box_confidence, zp, scale)));
classId.push_back(maxClassId);
validCount++;
boxes.push_back(box_x);
boxes.push_back(box_y);
boxes.push_back(box_w);
boxes.push_back(box_h);
}
}
}
}
}
return validCount;
}
int post_process(int8_t *input0, int8_t *input1, int8_t *input2, int model_in_h, int model_in_w, float conf_threshold,
float nms_threshold, BOX_RECT pads, float scale_w, float scale_h, std::vector<int32_t> &qnt_zps,
std::vector<float> &qnt_scales, detect_result_group_t *group, const std::vector<std::string>& labels)
{
// static int init = -1;
// if (init == -1)
// {
// int ret = 0;
// // ret = loadLabelName(LABEL_NALE_TXT_PATH, labels);
// for(int i=0;i<mylabels.size();i++) {
// labels[i] = new char[mylabels[i].size() + 1];
// std::strcpy((labels[i]),mylabels[i].c_str());
// // gDebug(mylabels);
// }
// ret = 0;
// if (ret < 0)
// {
// return -1;
// }
// init = 0;
// }
memset(group, 0, sizeof(detect_result_group_t));
std::vector<float> filterBoxes;
std::vector<float> objProbs;
std::vector<int> classId;
// stride 8
int stride0 = 8;
int grid_h0 = model_in_h / stride0;
int grid_w0 = model_in_w / stride0;
int validCount0 = 0;
validCount0 = process(input0, (int *)anchor0, grid_h0, grid_w0, model_in_h, model_in_w, stride0, filterBoxes, objProbs,
classId, conf_threshold, qnt_zps[0], qnt_scales[0]);
// stride 16
int stride1 = 16;
int grid_h1 = model_in_h / stride1;
int grid_w1 = model_in_w / stride1;
int validCount1 = 0;
validCount1 = process(input1, (int *)anchor1, grid_h1, grid_w1, model_in_h, model_in_w, stride1, filterBoxes, objProbs,
classId, conf_threshold, qnt_zps[1], qnt_scales[1]);
// stride 32
int stride2 = 32;
int grid_h2 = model_in_h / stride2;
int grid_w2 = model_in_w / stride2;
int validCount2 = 0;
validCount2 = process(input2, (int *)anchor2, grid_h2, grid_w2, model_in_h, model_in_w, stride2, filterBoxes, objProbs,
classId, conf_threshold, qnt_zps[2], qnt_scales[2]);
int validCount = validCount0 + validCount1 + validCount2;
// no object detect
if (validCount <= 0)
{
return 0;
}
std::vector<int> indexArray;
for (int i = 0; i < validCount; ++i)
{
indexArray.push_back(i);
}
quick_sort_indice_inverse(objProbs, 0, validCount - 1, indexArray);
std::set<int> class_set(std::begin(classId), std::end(classId));
for (auto c : class_set)
{
nms(validCount, filterBoxes, classId, indexArray, c, nms_threshold);
}
int last_count = 0;
group->count = 0;
/* box valid detect target */
for (int i = 0; i < validCount; ++i)
{
if (indexArray[i] == -1 || last_count >= OBJ_NUMB_MAX_SIZE)
{
continue;
}
int n = indexArray[i];
float x1 = filterBoxes[n * 4 + 0] - pads.left;
float y1 = filterBoxes[n * 4 + 1] - pads.top;
float x2 = x1 + filterBoxes[n * 4 + 2];
float y2 = y1 + filterBoxes[n * 4 + 3];
int id = classId[n];
float obj_conf = objProbs[i];
group->results[last_count].box.left = (int)(clamp(x1, 0, model_in_w) / scale_w);
group->results[last_count].box.top = (int)(clamp(y1, 0, model_in_h) / scale_h);
group->results[last_count].box.right = (int)(clamp(x2, 0, model_in_w) / scale_w);
group->results[last_count].box.bottom = (int)(clamp(y2, 0, model_in_h) / scale_h);
group->results[last_count].prop = obj_conf;
const char *label = labels.at(id).c_str();
strncpy(group->results[last_count].name, label, OBJ_NAME_MAX_SIZE);
// printf("result %2d: (%4d, %4d, %4d, %4d), %s\n", i, group->results[last_count].box.left,
// group->results[last_count].box.top,
// group->results[last_count].box.right, group->results[last_count].box.bottom, label);
last_count++;
}
group->count = last_count;
return 0;
}
// void deinitPostProcess()
// {
// for (int i = 0; i < OBJ_CLASS_NUM; i++)
// {
// if (labels[i] != nullptr)
// {
// free(labels[i]);
// labels[i] = nullptr;
// }
// }
// }

View File

@ -0,0 +1,61 @@
// Copyright (c) 2023 by Rockchip Electronics Co., Ltd. All Rights Reserved.
//
// 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.
#include "preprocess.h"
void letterbox(const cv::Mat &image, cv::Mat &padded_image, BOX_RECT &pads, const float scale, const cv::Size &target_size, const cv::Scalar &pad_color)
{
// 调整图像大小
cv::Mat resized_image;
cv::resize(image, resized_image, cv::Size(), scale, scale);
// 计算填充大小
int pad_width = target_size.width - resized_image.cols;
int pad_height = target_size.height - resized_image.rows;
pads.left = pad_width / 2;
pads.right = pad_width - pads.left;
pads.top = pad_height / 2;
pads.bottom = pad_height - pads.top;
// 在图像周围添加填充
cv::copyMakeBorder(resized_image, padded_image, pads.top, pads.bottom, pads.left, pads.right, cv::BORDER_CONSTANT, pad_color);
}
int resize_rga(rga_buffer_t &src, rga_buffer_t &dst, const cv::Mat &image, cv::Mat &resized_image, const cv::Size &target_size)
{
im_rect src_rect;
im_rect dst_rect;
memset(&src_rect, 0, sizeof(src_rect));
memset(&dst_rect, 0, sizeof(dst_rect));
size_t img_width = image.cols;
size_t img_height = image.rows;
if (image.type() != CV_8UC3)
{
printf("source image type is %d!\n", image.type());
return -1;
}
size_t target_width = target_size.width;
size_t target_height = target_size.height;
src = wrapbuffer_virtualaddr((void *)image.data, img_width, img_height, RK_FORMAT_RGB_888);
dst = wrapbuffer_virtualaddr((void *)resized_image.data, target_width, target_height, RK_FORMAT_RGB_888);
int ret = imcheck(src, dst, src_rect, dst_rect);
if (IM_STATUS_NOERROR != ret)
{
fprintf(stderr, "rga check error! %s", imStrError((IM_STATUS)ret));
return -1;
}
IM_STATUS STATUS = imresize(src, dst);
return 0;
}

View File

@ -0,0 +1,100 @@
#include "yaml_config.h"
#include <iostream>
#include <filesystem>
YAML::Node ReadConfigYamlFile();
// static std::string yaml_config_path =
// "/media/Projects/guangpo_lidar/src/guangpo_lidar/yaml_config/yaml_config.yaml";
static std::string yaml_config_path = []()->std::string{
std::filesystem::path current_dir =
std::filesystem::path(__FILE__).parent_path();
std::filesystem::path yaml_path = current_dir / "yaml_config.yaml";
std::cout << "yaml file path: " << yaml_path << std::endl;
return yaml_path;
}();
YAML::Node yaml_config = ReadConfigYamlFile();
YAML::Node ReadConfigYamlFile() {
YAML::Node res;
std::cout << __PRETTY_FUNCTION__ << ": " << std::endl;
std::cout << "BEGIN READ FILE: " << yaml_config_path << std::endl;
bool read_successful_flag = false;
try {
// Load the YAML file
res = YAML::LoadFile(yaml_config_path);
read_successful_flag = true;
} catch (const YAML::Exception &e) {
std::cerr << "Error while reading the YAML file: " << yaml_config_path
<< e.what() << std::endl;
// gDebugError("[GXT] : Error while reading the YAML file:") << e.what();
}
if (!read_successful_flag) {
// std::cerr << "backtrace:" << __PRETTY_FUNCTION__ << std::endl;
// std::cerr << "backtrace:" << __PRETTY_FUNCTION__ << std::endl;
// std::cerr << "backtrace:" << __PRETTY_FUNCTION__ << std::endl;
std::cerr << "Error while reading the YAML file!" << yaml_config_path
<< std::endl;
std::cerr << "Error while reading the YAML file!" << yaml_config_path
<< std::endl;
std::cerr << "Error while reading the YAML file!" << yaml_config_path
<< std::endl;
std::terminate();
}
std::cout << "Read yaml config file successfully! " << yaml_config_path
<< std::endl;
return res;
}
// __attribute((constructor)) inline bool
// GxtReadConfigYamlFile(const std::string &yaml_config_path) {
// bool read_successful_flag = false;
// try {
// // Load the YAML file
// YAML::Node config = YAML::LoadFile(yaml_config_path);
//
// read_successful_flag = true;
// // gDebugCol1("READ CONFIG FILE SUCCESSFULLY!");
//
// auto quantize = config["quantize"];
// ADDCONFIG(quantize, quantize_pose_quaternion_bit_width);
// ADDCONFIG(quantize, quantize_pose_quaternion_il);
// ADDCONFIG(quantize, quantize_pose_quaternion_bit_width);
// ADDCONFIG(quantize, quantize_pose_quaternion_il);
//
// ADDCONFIG(quantize, quantize_imu_speed_bit_width);
// ADDCONFIG(quantize, quantize_imu_speed_il);
// ADDCONFIG(quantize, quantize_imu_accbias_bit_width);
// ADDCONFIG(quantize, quantize_imu_accbias_il);
// ADDCONFIG(quantize, quantize_imu_gyrobias_bit_width);
// ADDCONFIG(quantize, quantize_imu_gyrobias_il);
//
// ADDCONFIG(quantize, quantize_inverse_depth_bit_width);
// ADDCONFIG(quantize, quantize_inverse_depth_il);
//
// ADDCONFIG(quantize, quantize_hessian_bit_width);
// ADDCONFIG(quantize, quantize_hessian_il);
// ADDCONFIG(quantize, quantize_b_bit_width);
// ADDCONFIG(quantize, quantize_b_il);
//
// auto flag = config["flag"];
// ADDCONFIG(flag, use_gxt_backend);
// ADDCONFIG(flag, enable_quantize);
// } catch (const YAML::Exception &e) {
// // std::cerr << "Error while reading the YAML file: " << e.what() <<
// // std::endl;
// gDebugError("[GXT] : Error while reading the YAML file:") << e.what();
// }
//
// if (!read_successful_flag) {
// gDebugCol3("\n\n\n==========================================");
// gDebugCol3("[GXT] : Error while reading the YAML file!");
// gDebugCol3("[GXT] : Error while reading the YAML file!");
// gDebugError("[GXT] : Error while reading the YAML file!");
// std::terminate();
// }
//
// return 0;
// }

View File

@ -0,0 +1,8 @@
#pragma once
#include <yaml-cpp/yaml.h>
#include <string>
extern YAML::Node yaml_config;

View File

@ -0,0 +1,107 @@
# 基础ros设置
sub_image_topic : "/usb_cam/image_raw"
sub_pointcloud_topic : "/livox/lidar_192_168_20_105"
pub_image_topic : "detect_img"
pub_lidar_topic : "detect_lidar"
pub_cloud_noground_topic : "cloud_noground"
pub_box3d_markers_topic : "box3d_markers"
# 使用仿真还是激光雷达
# 使用仿真就是图像数据从功能包接收
# 不使用仿真就是图像数据从/dev驱动中读取
use_bag : true
camera_image_dev : "/dev/video11"
# 大于一定距离就不计算到电梯拥挤度里面 ,单位 m
person_distance : 5
# 订阅的开启/关闭电梯拥挤度的话题
detect_congest_enable_topic : "/detect_congest_enable"
# 发布的电梯拥挤度话题
person_density_topic : "/person_density"
# 设置传感器时间同步最大时间间隔 单位s
max_time_interval : 0.2
# 点云是否去除地面(去除地面最好开启点云降采样)
remove_ground_points_enable : true
# 去除地面点云高度
remove_ground_height : 0.1
# 最大迭代次数
max_iterations : 250
# 图像是否去畸变,会增加约12ms耗时
img_distort_enable : true
# 点云降采样大小,单位 m,小于等于0就是不降采样
leaf_size : 0.02
# 点云dbscan聚类
cluster :
octreeResolution : 1
minPtsAux : 20
epsilon : 0.2
minPts : 10
# 欧式聚类
cluster_tolerance : 0.08
min_cluster_size : 10
max_cluster_size : 9999
# obb multiple threads
obb_omp_threads : 4
# 点云在多大范围投影到相机平面上(数值单位m,坐标系是激光坐标系)
lidar2camera:
min_x : 0.1
max_x : 20
min_y : -20
max_y : 20
min_z : -5
max_z : 5
# 激光雷达到车体坐标系变换
convert_lidar2car:
transform:
x: 0.3643
y: 0.2078
z: 1.21
# 角度,代码里会转成弧度
rotation :
roll: -179.5
pitch: 0.5
yaw: 360
# 相机到激光雷达坐标系变换
convert_carmera2lidar:
transform:
x: -0.01276627371659704
y: 1.040611755008172
z: 0.2783443893841093
# 角度,代码里会转成弧度
rotation :
yaw: 4.491111184694372
pitch: -1.475459526983985
roll: 0.2987467915697319
# 相机畸变参数
camera_distort_params:
p0: 0.05828191
p1: -0.11750722
p2: -0.014249
p3: 0.00087086
p4: -0.01850911
# 输入图片尺寸
image:
width: 1280
height: 720
# 相机内参矩阵
camera_in_param:
dx: 787.22316869
dy: 793.45182
u0: 628.91534144
v0: 313.46301416
# 启动时warmup并生成测试
warmup: false
# 生成debug图片
# write_img: false