Merge remote-tracking branch 'origin/develop'
commit
b5bc322135
|
@ -0,0 +1,24 @@
|
||||||
|
{
|
||||||
|
"configurations": [
|
||||||
|
{
|
||||||
|
"name": "Linux",
|
||||||
|
"includePath": [
|
||||||
|
"${workspaceFolder}/include/**",
|
||||||
|
],
|
||||||
|
"defines": ["__CUDACC__", "HAS_PYTHON"],
|
||||||
|
"compilerPath": "/usr/bin/gcc",
|
||||||
|
"cStandard": "gnu11",
|
||||||
|
"cppStandard": "gnu++11",
|
||||||
|
"intelliSenseMode": "linux-gcc-x64",
|
||||||
|
"configurationProvider": "ms-vscode.makefile-tools",
|
||||||
|
"browse": {
|
||||||
|
"path": [
|
||||||
|
"${workspaceFolder}/src/**",
|
||||||
|
],
|
||||||
|
"limitSymbolsToIncludedHeaders": false,
|
||||||
|
"databaseFilename": ""
|
||||||
|
}
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"version": 4
|
||||||
|
}
|
|
@ -0,0 +1,28 @@
|
||||||
|
{
|
||||||
|
// 使用 IntelliSense 了解相关属性。
|
||||||
|
// 悬停以查看现有属性的描述。
|
||||||
|
// 欲了解更多信息,请访问: https://go.microsoft.com/fwlink/?linkid=830387
|
||||||
|
"version": "0.2.0",
|
||||||
|
"configurations": [
|
||||||
|
{
|
||||||
|
"name": "(gdb) 启动",
|
||||||
|
"type": "cppdbg",
|
||||||
|
"request": "launch",
|
||||||
|
"program": "${workspaceFolder}/workspace/pro",
|
||||||
|
"args": ["yolo"],
|
||||||
|
"stopAtEntry": false,
|
||||||
|
"cwd": "${workspaceFolder}/workspace",
|
||||||
|
"environment": [],
|
||||||
|
"externalConsole": false,
|
||||||
|
"MIMode": "gdb",
|
||||||
|
"setupCommands": [
|
||||||
|
{
|
||||||
|
"description": "为 gdb 启用整齐打印",
|
||||||
|
"text": "-enable-pretty-printing",
|
||||||
|
"ignoreFailures": true
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"preLaunchTask": "build"
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
|
@ -0,0 +1,105 @@
|
||||||
|
{
|
||||||
|
"editor.snippetSuggestions": "bottom",
|
||||||
|
"editor.suggest.snippetsPreventQuickSuggestions": false,
|
||||||
|
"python.languageServer": "Jedi",
|
||||||
|
"files.associations": {
|
||||||
|
"*.cpp": "cpp",
|
||||||
|
"*.cu": "cpp",
|
||||||
|
"*.cuh": "cpp",
|
||||||
|
"unordered_map": "cpp",
|
||||||
|
"chrono": "cpp",
|
||||||
|
"thread": "cpp",
|
||||||
|
"future": "cpp",
|
||||||
|
"type_traits": "cpp",
|
||||||
|
"tuple": "cpp",
|
||||||
|
"__functional_03": "cpp",
|
||||||
|
"functional": "cpp",
|
||||||
|
"__nullptr": "cpp",
|
||||||
|
"cstddef": "cpp",
|
||||||
|
"exception": "cpp",
|
||||||
|
"initializer_list": "cpp",
|
||||||
|
"new": "cpp",
|
||||||
|
"optional": "cpp",
|
||||||
|
"typeinfo": "cpp",
|
||||||
|
"array": "cpp",
|
||||||
|
"atomic": "cpp",
|
||||||
|
"*.tcc": "cpp",
|
||||||
|
"bitset": "cpp",
|
||||||
|
"cctype": "cpp",
|
||||||
|
"clocale": "cpp",
|
||||||
|
"cmath": "cpp",
|
||||||
|
"codecvt": "cpp",
|
||||||
|
"complex": "cpp",
|
||||||
|
"condition_variable": "cpp",
|
||||||
|
"cstdarg": "cpp",
|
||||||
|
"cstdint": "cpp",
|
||||||
|
"cstdio": "cpp",
|
||||||
|
"cstdlib": "cpp",
|
||||||
|
"cstring": "cpp",
|
||||||
|
"ctime": "cpp",
|
||||||
|
"cwchar": "cpp",
|
||||||
|
"cwctype": "cpp",
|
||||||
|
"deque": "cpp",
|
||||||
|
"list": "cpp",
|
||||||
|
"unordered_set": "cpp",
|
||||||
|
"vector": "cpp",
|
||||||
|
"algorithm": "cpp",
|
||||||
|
"filesystem": "cpp",
|
||||||
|
"ratio": "cpp",
|
||||||
|
"string_view": "cpp",
|
||||||
|
"system_error": "cpp",
|
||||||
|
"fstream": "cpp",
|
||||||
|
"iomanip": "cpp",
|
||||||
|
"iosfwd": "cpp",
|
||||||
|
"iostream": "cpp",
|
||||||
|
"istream": "cpp",
|
||||||
|
"limits": "cpp",
|
||||||
|
"memory": "cpp",
|
||||||
|
"mutex": "cpp",
|
||||||
|
"ostream": "cpp",
|
||||||
|
"numeric": "cpp",
|
||||||
|
"sstream": "cpp",
|
||||||
|
"stdexcept": "cpp",
|
||||||
|
"streambuf": "cpp",
|
||||||
|
"cinttypes": "cpp",
|
||||||
|
"utility": "cpp",
|
||||||
|
"__config": "cpp",
|
||||||
|
"variant": "cpp",
|
||||||
|
"forward_list": "cpp",
|
||||||
|
"typeindex": "cpp",
|
||||||
|
"valarray": "cpp",
|
||||||
|
"__bit_reference": "cpp",
|
||||||
|
"__hash_table": "cpp",
|
||||||
|
"__split_buffer": "cpp",
|
||||||
|
"__tree": "cpp",
|
||||||
|
"iterator": "cpp",
|
||||||
|
"locale": "cpp",
|
||||||
|
"map": "cpp",
|
||||||
|
"set": "cpp",
|
||||||
|
"string": "cpp",
|
||||||
|
"__locale": "cpp",
|
||||||
|
"ios": "cpp",
|
||||||
|
"queue": "cpp",
|
||||||
|
"random": "cpp",
|
||||||
|
"stack": "cpp",
|
||||||
|
"__atomic": "cpp",
|
||||||
|
"__debug": "cpp",
|
||||||
|
"__node_handle": "cpp",
|
||||||
|
"__mutex_base": "cpp",
|
||||||
|
"__functional_base": "cpp",
|
||||||
|
"__memory": "cpp",
|
||||||
|
"__atomic_generated": "cpp",
|
||||||
|
"__functional_base_03": "cpp",
|
||||||
|
"__tuple": "cpp",
|
||||||
|
"*.inc": "cpp",
|
||||||
|
"memory_resource": "cpp",
|
||||||
|
"csignal": "cpp",
|
||||||
|
"strstream": "cpp",
|
||||||
|
"cfenv": "cpp",
|
||||||
|
"imuprocessor,h": "cpp",
|
||||||
|
"core": "cpp",
|
||||||
|
"numericaldiff": "cpp",
|
||||||
|
"bit": "cpp",
|
||||||
|
"*.ipp": "cpp"
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,15 @@
|
||||||
|
{
|
||||||
|
// See https://go.microsoft.com/fwlink/?LinkId=733558
|
||||||
|
// for the documentation about the tasks.json format
|
||||||
|
"version": "2.0.0",
|
||||||
|
"tasks": [
|
||||||
|
{
|
||||||
|
"label": "build",
|
||||||
|
"type": "shell",
|
||||||
|
"command": "make pro -j64"
|
||||||
|
|
||||||
|
// for cmake
|
||||||
|
//"command": "cd build && make pro -j25"
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
|
@ -0,0 +1,103 @@
|
||||||
|
cc := g++
|
||||||
|
nvcc = /usr/local/cuda-10.2/bin/nvcc
|
||||||
|
CXXFLAGS += -std=c++14
|
||||||
|
LDFLAGS = -lm
|
||||||
|
|
||||||
|
cpp_srcs := $(shell find src -name "*.cpp")
|
||||||
|
cpp_objs := $(cpp_srcs:.cpp=.cpp.o)
|
||||||
|
cpp_objs := $(cpp_objs:src/%=objs/%)
|
||||||
|
cpp_mk := $(cpp_objs:.cpp.o=.cpp.mk)
|
||||||
|
|
||||||
|
cu_srcs := $(shell find src -name "*.cu")
|
||||||
|
cu_objs := $(cu_srcs:.cu=.cu.o)
|
||||||
|
cu_objs := $(cu_objs:src/%=objs/%)
|
||||||
|
cu_mk := $(cu_objs:.cu.o=.cu.mk)
|
||||||
|
|
||||||
|
include_paths := include \
|
||||||
|
third-party \
|
||||||
|
/usr/include/opencv4 \
|
||||||
|
/usr/include/aarch64-linux-gnu \
|
||||||
|
/usr/local/cuda-10.2/include \
|
||||||
|
/usr/include/pcl-1.8 \
|
||||||
|
/usr/include/eigen3 \
|
||||||
|
/usr/include/vtk-6.3 \
|
||||||
|
#/home/user/Downloads/TensorRT-8.0.1.6/include \
|
||||||
|
|
||||||
|
library_paths := /usr/lib/aarch64-linux-gnu \
|
||||||
|
/usr/local/cuda-10.2/lib64 \
|
||||||
|
/usr/local/lib \
|
||||||
|
/home/jetson/tmp/obstacle-detection/lib \
|
||||||
|
#/home/jetson/Downloads/TensorRT-8.0.1.6/lib \
|
||||||
|
|
||||||
|
link_librarys := opencv_core opencv_highgui opencv_imgproc opencv_videoio opencv_imgcodecs \
|
||||||
|
nvinfer nvinfer_plugin nvonnxparser \
|
||||||
|
cuda cublas cudart cudnn realsense2 glfw GL GLU\
|
||||||
|
pcl_common pcl_segmentation pcl_io pcl_kdtree pcl_filters\
|
||||||
|
pcl_features pcl_apps pcl_io_ply pcl_keypoints pcl_ml pcl_octree pcl_outofcore pcl_people pcl_recognition pcl_registration pcl_sample_consensus pcl_search pcl_stereo pcl_surface pcl_tracking pcl_visualization \
|
||||||
|
boost_system vtkCommonCore-6.3 vtkCommonMath-6.3 vtkRenderingCore-6.3 vtkCommonDataModel-6.3\
|
||||||
|
stdc++ dl\
|
||||||
|
JetsonGPIO
|
||||||
|
|
||||||
|
empty :=
|
||||||
|
export_path := $(subst $(empty) $(empty),:,$(library_paths))
|
||||||
|
|
||||||
|
run_paths := $(foreach item,$(library_paths),-Wl,-rpath=$(item))
|
||||||
|
include_paths := $(foreach item,$(include_paths),-I$(item))
|
||||||
|
library_paths := $(foreach item,$(library_paths),-L$(item))
|
||||||
|
link_librarys := $(foreach item,$(link_librarys),-l$(item))
|
||||||
|
|
||||||
|
cpp_compile_flags := -std=c++14 -fPIC -w -g -pthread -fopenmp -O0
|
||||||
|
cu_compile_flags := -std=c++14 -g -w -O0 -Xcompiler "$(cpp_compile_flags)"
|
||||||
|
link_flags := -pthread -fopenmp -Wl,-rpath='$$ORIGIN'
|
||||||
|
|
||||||
|
cpp_compile_flags += $(include_paths)
|
||||||
|
cu_compile_flags += $(include_paths)
|
||||||
|
link_flags += $(library_paths) $(link_librarys) $(run_paths)
|
||||||
|
|
||||||
|
ifneq ($(MAKECMDGOALS), clean)
|
||||||
|
-include $(cpp_mk) $(cu_mk)
|
||||||
|
endif
|
||||||
|
|
||||||
|
pro := workspace/pro
|
||||||
|
expath := library_path.txt
|
||||||
|
|
||||||
|
library_path.txt :
|
||||||
|
@echo LD_LIBRARY_PATH=$(export_path):"$$"LD_LIBRARY_PATH > $@
|
||||||
|
|
||||||
|
workspace/pro : $(cpp_objs) $(cu_objs)
|
||||||
|
@echo Link $@
|
||||||
|
@mkdir -p $(dir $@)
|
||||||
|
@$(cc) $^ -o $@ $(link_flags)
|
||||||
|
|
||||||
|
objs/%.cpp.o : src/%.cpp
|
||||||
|
@echo Compile CXX $<
|
||||||
|
@mkdir -p $(dir $@)
|
||||||
|
@$(cc) -c $< -o $@ $(cpp_compile_flags)
|
||||||
|
|
||||||
|
objs/%.cu.o : src/%.cu
|
||||||
|
@echo Compile CUDA $<
|
||||||
|
@mkdir -p $(dir $@)
|
||||||
|
@$(nvcc) -c $< -o $@ $(cu_compile_flags)
|
||||||
|
|
||||||
|
objs/%.cpp.mk : src/%.cpp
|
||||||
|
@echo Compile depends CXX $<
|
||||||
|
@mkdir -p $(dir $@)
|
||||||
|
@$(cc) -M $< -MF $@ -MT $(@:.cpp.mk=.cpp.o) $(cpp_compile_flags)
|
||||||
|
|
||||||
|
objs/%.cu.mk : src/%.cu
|
||||||
|
@echo Compile depends CUDA $<
|
||||||
|
@mkdir -p $(dir $@)
|
||||||
|
@$(nvcc) -M $< -MF $@ -MT $(@:.cu.mk=.cu.o) $(cu_compile_flags)
|
||||||
|
|
||||||
|
run : workspace/pro
|
||||||
|
@cd workspace && ./pro
|
||||||
|
|
||||||
|
clean :
|
||||||
|
@rm -rf objs workspace/pro
|
||||||
|
@rm -rf library_path.txt
|
||||||
|
@rm -rf workspace/Result.jpg
|
||||||
|
|
||||||
|
# 导出符号,使得运行时能够链接上
|
||||||
|
export LD_LIBRARY_PATH:=$(export_path):$(LD_LIBRARY_PATH)
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,4 @@
|
||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
find ./src -regex '.*\.\(cpp\|hpp\|cc\|cxx\|cu\|cuh\|h\)' | xargs clang-format -i \
|
||||||
|
-style="{BasedOnStyle: google, IndentWidth: 2, ColumnLimit: 100}"
|
|
@ -0,0 +1,141 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "opencv2/core/core.hpp"
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
// opencv 用于图像数据读取与处理
|
||||||
|
#include <opencv2/core/core.hpp>
|
||||||
|
#include <opencv2/imgproc/imgproc.hpp>
|
||||||
|
#include <opencv2/highgui/highgui.hpp>
|
||||||
|
|
||||||
|
// 使用Eigen的Geometry模块处理3d运动
|
||||||
|
#include <Eigen/Core>
|
||||||
|
#include <Eigen/Geometry>
|
||||||
|
|
||||||
|
// pcl
|
||||||
|
#include <pcl/common/transforms.h>
|
||||||
|
#include <pcl/point_types.h>
|
||||||
|
#include <pcl/io/pcd_io.h>
|
||||||
|
#include <pcl/PointIndices.h>
|
||||||
|
#include <pcl/point_cloud.h>
|
||||||
|
#include <pcl/visualization/pcl_visualizer.h>
|
||||||
|
#include <pcl/segmentation/sac_segmentation.h>
|
||||||
|
#include <pcl/filters/extract_indices.h>
|
||||||
|
|
||||||
|
// boost.format 字符串处理
|
||||||
|
#include <boost/format.hpp>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace pcl;
|
||||||
|
|
||||||
|
// 定义点云类型
|
||||||
|
typedef PointCloud<PointXYZ> PointCloudXYZ;
|
||||||
|
|
||||||
|
class DepthProcessor{
|
||||||
|
private:
|
||||||
|
cv::Mat imgRGB;
|
||||||
|
cv::Mat imgDepth; // or pointCloud detect by lidar
|
||||||
|
|
||||||
|
cv::Mat obstacle; // [dis, cls, maby size]
|
||||||
|
|
||||||
|
|
||||||
|
public:
|
||||||
|
//点云显示对象
|
||||||
|
visualization::PCLVisualizer::Ptr pcdViewer;
|
||||||
|
visualization::PCLVisualizer::Ptr tmpViewer;
|
||||||
|
cv::Mat mK; // camera intrinsic or external parameters between camera and lidar
|
||||||
|
//最近物体信息
|
||||||
|
double dist, max_x, max_y, min_x, min_y;
|
||||||
|
std::string label;
|
||||||
|
// 创建点云对象
|
||||||
|
PointCloudXYZ::Ptr cloud;
|
||||||
|
//相机参数
|
||||||
|
double fx, fy, cx, cy;
|
||||||
|
//深度阈值,单位米
|
||||||
|
double minDepth, maxDepth;
|
||||||
|
//过滤孤立点的阈值/
|
||||||
|
int thre_count;
|
||||||
|
double radius;
|
||||||
|
//过滤通行区域的阈值
|
||||||
|
double thre_low_x, thre_high_x, thre_low_y, thre_high_y;
|
||||||
|
|
||||||
|
//地面高度阈值
|
||||||
|
double thre_ground;
|
||||||
|
|
||||||
|
//相机初始化高度
|
||||||
|
float camHigh;
|
||||||
|
|
||||||
|
//判断物体的点云个数阈值、半径阈值
|
||||||
|
int thre_ponit_count, thre_point_radius;
|
||||||
|
float ground_height;
|
||||||
|
|
||||||
|
DepthProcessor(const std::string file_path, const cv::Mat tmp_mk);
|
||||||
|
bool obstacleDetect(const cv::Mat depthMat, const Eigen::Affine3f& transform);
|
||||||
|
PointCloudXYZ::Ptr depth2Cloud(PointCloudXYZ::Ptr oriCloud, const cv::Mat depthMat, int startRow, int endRow);
|
||||||
|
bool camHighInit(const cv::Mat depthMat, const Eigen::Affine3f& transform);
|
||||||
|
|
||||||
|
static PointCloudXYZ::Ptr downsampling(const PointCloudXYZ::Ptr& pointCloud, float leaf);
|
||||||
|
static PointCloudXYZ::Ptr axisFilter(const PointCloudXYZ::Ptr& pointCloud, const double&thre_low, const double& thre_high, const string& field, const bool& flag_in);
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr delGround(const PointCloudXYZ::Ptr& pointCloud);
|
||||||
|
static void calHistogram(const PointCloudXYZ::Ptr& pointCloud, float& maxY, std::vector<std::vector<int>>& histogram);
|
||||||
|
static void radiusSearch(const PointCloudXYZ::Ptr& pointCloud, const PointXYZ& queryPoint, const float& radius, std::vector<int>& indResults);
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr delGround_else(const PointCloudXYZ::Ptr& pointCloud, std::vector<int> index);
|
||||||
|
|
||||||
|
void RadiusOutlierFilter(const PointCloudXYZ::Ptr &pcd_cloud0);
|
||||||
|
|
||||||
|
void load_config(const string filepath);
|
||||||
|
|
||||||
|
void ConditionFilter(const double &ground);
|
||||||
|
double IOU(double max_x1,double min_x1,double max_y1,double min_y1,double max_x2,double min_x2,double max_y2,double min_y2);
|
||||||
|
|
||||||
|
void calHistogramZ(const PointCloudXYZ::Ptr &pointCloud, std::vector<std::vector<int>>& histogram);
|
||||||
|
|
||||||
|
bool obstacleRecognize(cv::Mat boxes);
|
||||||
|
cv::Mat getObstacle();
|
||||||
|
};
|
||||||
|
|
||||||
|
//用作深度转点云的 多线程并行操作
|
||||||
|
class Depth2cloud : public cv::ParallelLoopBody{
|
||||||
|
public:
|
||||||
|
cv::Mat depthMat;
|
||||||
|
PointCloudXYZ::Ptr _cloud;
|
||||||
|
Depth2cloud(cv::Mat mat, PointCloudXYZ::Ptr cloud):depthMat(mat), _cloud(cloud){};
|
||||||
|
|
||||||
|
virtual void operator()(const cv::Range& range) const override{
|
||||||
|
PointCloudXYZ::Ptr tmpcloud(new PointCloudXYZ);
|
||||||
|
int col = depthMat.cols;
|
||||||
|
cv::Mat image = depthMat.clone();
|
||||||
|
image.convertTo(image, CV_32FC1);
|
||||||
|
|
||||||
|
for(int i=range.start;i<range.end;i++){
|
||||||
|
for(int j=0;j<col;j++){
|
||||||
|
// 获取深度值
|
||||||
|
float depth = image.at<float>(i, j);
|
||||||
|
// 忽略深度值小于320mm的点
|
||||||
|
if (depth <= 320)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
// 计算三维坐标
|
||||||
|
double X = (j - 322.771) * depth / 388.588 / 1000;
|
||||||
|
if(X > 0.5 || X < -0.5)
|
||||||
|
continue;
|
||||||
|
double Y = (i - 236.947) * depth / 388.588 / 1000;
|
||||||
|
double Z = depth / 1000;
|
||||||
|
|
||||||
|
// 创建点云点并设置坐标
|
||||||
|
PointXYZ point;
|
||||||
|
point.x = X;
|
||||||
|
point.y = Y;
|
||||||
|
point.z = Z;
|
||||||
|
|
||||||
|
// 将点添加到点云中
|
||||||
|
tmpcloud->push_back(point);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
*_cloud = *tmpcloud;
|
||||||
|
}
|
||||||
|
};
|
|
@ -0,0 +1,92 @@
|
||||||
|
# pragma once
|
||||||
|
|
||||||
|
|
||||||
|
#include <librealsense2/rs.hpp>
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef PI
|
||||||
|
#define PI 3.14159265358979323846
|
||||||
|
#define PI_FL 3.141592f
|
||||||
|
#endif
|
||||||
|
|
||||||
|
class IMUProcessor
|
||||||
|
{
|
||||||
|
// theta is the angle of camera rotation in x, y and z components
|
||||||
|
float3 theta;
|
||||||
|
std::mutex theta_mtx;
|
||||||
|
/* alpha indicates the part that gyro and accelerometer take in computation of theta; higher alpha gives more weight to gyro, but too high
|
||||||
|
values cause drift; lower alpha gives more weight to accelerometer, which is more sensitive to disturbances */
|
||||||
|
float alpha = 0.9f;
|
||||||
|
bool firstGyro = true;
|
||||||
|
bool firstAccel = true;
|
||||||
|
// Keeps the arrival time of previous gyro frame
|
||||||
|
double last_ts_gyro = 0;
|
||||||
|
public:
|
||||||
|
// Function to calculate the change in angle of motion based on data from gyro
|
||||||
|
void process_gyro(rs2_vector gyro_data, double ts)
|
||||||
|
{
|
||||||
|
if (firstGyro) // On the first iteration, use only data from accelerometer to set the camera's initial position
|
||||||
|
{
|
||||||
|
firstGyro = false;
|
||||||
|
last_ts_gyro = ts;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
// Holds the change in angle, as calculated from gyro
|
||||||
|
float3 gyro_angle;
|
||||||
|
|
||||||
|
// Initialize gyro_angle with data from gyro
|
||||||
|
gyro_angle.x = gyro_data.x; // Pitch
|
||||||
|
gyro_angle.y = gyro_data.y; // Yaw
|
||||||
|
gyro_angle.z = gyro_data.z; // Roll
|
||||||
|
|
||||||
|
// Compute the difference between arrival times of previous and current gyro frames
|
||||||
|
double dt_gyro = (ts - last_ts_gyro) / 1000.0;
|
||||||
|
last_ts_gyro = ts;
|
||||||
|
|
||||||
|
// Change in angle equals gyro measures * time passed since last measurement
|
||||||
|
gyro_angle = gyro_angle * static_cast<float>(dt_gyro);
|
||||||
|
|
||||||
|
// Apply the calculated change of angle to the current angle (theta)
|
||||||
|
std::lock_guard<std::mutex> lock(theta_mtx);
|
||||||
|
theta.add(-gyro_angle.z, -gyro_angle.y, gyro_angle.x);
|
||||||
|
}
|
||||||
|
|
||||||
|
void process_accel(rs2_vector accel_data)
|
||||||
|
{
|
||||||
|
// Holds the angle as calculated from accelerometer data
|
||||||
|
float3 accel_angle;
|
||||||
|
|
||||||
|
// Calculate rotation angle from accelerometer data
|
||||||
|
accel_angle.z = atan2(accel_data.y, accel_data.z);
|
||||||
|
accel_angle.x = atan2(accel_data.x, sqrt(accel_data.y * accel_data.y + accel_data.z * accel_data.z));
|
||||||
|
|
||||||
|
// If it is the first iteration, set initial pose of camera according to accelerometer data (note the different handling for Y axis)
|
||||||
|
std::lock_guard<std::mutex> lock(theta_mtx);
|
||||||
|
if (firstAccel)
|
||||||
|
{
|
||||||
|
firstAccel = false;
|
||||||
|
theta = accel_angle;
|
||||||
|
// Since we can't infer the angle around Y axis using accelerometer data, we'll use PI as a convetion for the initial pose
|
||||||
|
theta.y = PI_FL;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
/*
|
||||||
|
Apply Complementary Filter:
|
||||||
|
- high-pass filter = theta * alpha: allows short-duration signals to pass through while filtering out signals
|
||||||
|
that are steady over time, is used to cancel out drift.
|
||||||
|
- low-pass filter = accel * (1- alpha): lets through long term changes, filtering out short term fluctuations
|
||||||
|
*/
|
||||||
|
theta.x = theta.x * alpha + accel_angle.x * (1 - alpha);
|
||||||
|
theta.z = theta.z * alpha + accel_angle.z * (1 - alpha);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns the current rotation angle
|
||||||
|
float3 get_theta()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(theta_mtx);
|
||||||
|
return theta;
|
||||||
|
}
|
||||||
|
};
|
|
@ -0,0 +1,92 @@
|
||||||
|
#ifndef __YOLO_HPP__
|
||||||
|
#define __YOLO_HPP__
|
||||||
|
|
||||||
|
#include <future>
|
||||||
|
#include <memory>
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
#include <opencv2/opencv.hpp>
|
||||||
|
|
||||||
|
// yolov8 instance segmentation表示不同的模型类型
|
||||||
|
enum class Type : int {
|
||||||
|
V5 = 0,
|
||||||
|
X = 1,
|
||||||
|
V3 = 2,
|
||||||
|
V7 = 3,
|
||||||
|
V8 = 5,
|
||||||
|
V8Seg = 6
|
||||||
|
};
|
||||||
|
|
||||||
|
//用于存储实例分割的结果
|
||||||
|
struct InstanceSegmentMap {
|
||||||
|
int width = 0, height = 0; // width % 8 == 0
|
||||||
|
unsigned char *data = nullptr; // is width * height memory
|
||||||
|
|
||||||
|
InstanceSegmentMap(int width, int height);
|
||||||
|
virtual ~InstanceSegmentMap();
|
||||||
|
};
|
||||||
|
|
||||||
|
//表示检测到的物体边界框
|
||||||
|
struct Box {
|
||||||
|
float left, top, right, bottom, confidence;
|
||||||
|
int classLabel;
|
||||||
|
std::shared_ptr<InstanceSegmentMap> seg; // valid only in segment task
|
||||||
|
|
||||||
|
Box() = default;
|
||||||
|
Box(float left, float top, float right, float bottom, float confidence, int label)
|
||||||
|
: left(left),
|
||||||
|
top(top),
|
||||||
|
right(right),
|
||||||
|
bottom(bottom),
|
||||||
|
confidence(confidence),
|
||||||
|
classLabel(label) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
//表示输入图像。它包含图像数据指针、宽度和高度。
|
||||||
|
struct Image {
|
||||||
|
const void *bgrptr = nullptr;
|
||||||
|
int width = 0, height = 0;
|
||||||
|
|
||||||
|
Image() = default;
|
||||||
|
Image(const void *bgrptr, int width, int height) : bgrptr(bgrptr), width(width), height(height) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
//存储检测结果的 Box 结构体的容器类型
|
||||||
|
typedef std::vector<Box> BoxArray;
|
||||||
|
|
||||||
|
// [Preprocess]: 0.50736 ms
|
||||||
|
// [Forward]: 3.96410 ms
|
||||||
|
// [BoxDecode]: 0.12016 ms
|
||||||
|
// [SegmentDecode]: 0.15610 ms
|
||||||
|
//用于执行模型推理并返回检测结果
|
||||||
|
class Infer {
|
||||||
|
public:
|
||||||
|
virtual BoxArray forward(const Image &image, void *stream = nullptr) = 0;
|
||||||
|
virtual std::vector<BoxArray> forwards(const std::vector<Image> &images,
|
||||||
|
void *stream = nullptr) = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
//用于加载指定类型的模型,
|
||||||
|
std::shared_ptr<Infer> load(const std::string &engine_file, Type type,
|
||||||
|
float confidence_threshold = 0.25f, float nms_threshold = 0.5f);
|
||||||
|
|
||||||
|
//返回指定模型类型的字符串表示。
|
||||||
|
const char *type_name(Type type);
|
||||||
|
std::tuple<uint8_t, uint8_t, uint8_t> hsv2bgr(float h, float s, float v);
|
||||||
|
std::tuple<uint8_t, uint8_t, uint8_t> random_color(int id);
|
||||||
|
|
||||||
|
//定义了一个 Yolo 类,用于加载 YOLOv8 模型并执行物体检测和实例分割。
|
||||||
|
class Yolo{
|
||||||
|
public:
|
||||||
|
Yolo(const std::string enginePath) {detector = load(enginePath, Type::V8Seg);};
|
||||||
|
static const char *cocoLabels[];
|
||||||
|
BoxArray detect(cv::Mat colorMat);
|
||||||
|
std::shared_ptr<Infer> detector;
|
||||||
|
//yolo-video_demo函数直接返回BoxArray类型(vector<Box>)的objs,可以直接使用obj.left等形式返回物体识别框信息
|
||||||
|
//可返回left, top, right, bottom, confidence,box_width,box_height
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif // __YOLO_HPP__
|
|
@ -0,0 +1,153 @@
|
||||||
|
#ifndef __CPM_HPP__
|
||||||
|
#define __CPM_HPP__
|
||||||
|
|
||||||
|
// Comsumer Producer Model
|
||||||
|
|
||||||
|
#include <algorithm>
|
||||||
|
#include <condition_variable>
|
||||||
|
#include <future>
|
||||||
|
#include <memory>
|
||||||
|
#include <queue>
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
namespace cpm {
|
||||||
|
|
||||||
|
template <typename Result, typename Input, typename Model>
|
||||||
|
class Instance {
|
||||||
|
protected:
|
||||||
|
struct Item {
|
||||||
|
Input input;
|
||||||
|
std::shared_ptr<std::promise<Result>> pro;
|
||||||
|
};
|
||||||
|
|
||||||
|
std::condition_variable cond_;
|
||||||
|
std::queue<Item> input_queue_;
|
||||||
|
std::mutex queue_lock_;
|
||||||
|
std::shared_ptr<std::thread> worker_;
|
||||||
|
volatile bool run_ = false;
|
||||||
|
volatile int max_items_processed_ = 0;
|
||||||
|
void *stream_ = nullptr;
|
||||||
|
|
||||||
|
public:
|
||||||
|
virtual ~Instance() { stop(); }
|
||||||
|
|
||||||
|
void stop() {
|
||||||
|
run_ = false;
|
||||||
|
cond_.notify_one();
|
||||||
|
{
|
||||||
|
std::unique_lock<std::mutex> l(queue_lock_);
|
||||||
|
while (!input_queue_.empty()) {
|
||||||
|
auto &item = input_queue_.front();
|
||||||
|
if (item.pro) item.pro->set_value(Result());
|
||||||
|
input_queue_.pop();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
if (worker_) {
|
||||||
|
worker_->join();
|
||||||
|
worker_.reset();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual std::shared_future<Result> commit(const Input &input) {
|
||||||
|
Item item;
|
||||||
|
item.input = input;
|
||||||
|
item.pro.reset(new std::promise<Result>());
|
||||||
|
{
|
||||||
|
std::unique_lock<std::mutex> __lock_(queue_lock_);
|
||||||
|
input_queue_.push(item);
|
||||||
|
}
|
||||||
|
cond_.notify_one();
|
||||||
|
return item.pro->get_future();
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual std::vector<std::shared_future<Result>> commits(const std::vector<Input> &inputs) {
|
||||||
|
std::vector<std::shared_future<Result>> output;
|
||||||
|
{
|
||||||
|
std::unique_lock<std::mutex> __lock_(queue_lock_);
|
||||||
|
for (int i = 0; i < (int)inputs.size(); ++i) {
|
||||||
|
Item item;
|
||||||
|
item.input = inputs[i];
|
||||||
|
item.pro.reset(new std::promise<Result>());
|
||||||
|
output.emplace_back(item.pro->get_future());
|
||||||
|
input_queue_.push(item);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
cond_.notify_one();
|
||||||
|
return output;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename LoadMethod>
|
||||||
|
bool start(const LoadMethod &loadmethod, int max_items_processed = 1, void *stream = nullptr) {
|
||||||
|
stop();
|
||||||
|
|
||||||
|
this->stream_ = stream;
|
||||||
|
this->max_items_processed_ = max_items_processed;
|
||||||
|
std::promise<bool> status;
|
||||||
|
worker_ = std::make_shared<std::thread>(&Instance::worker<LoadMethod>, this,
|
||||||
|
std::ref(loadmethod), std::ref(status));
|
||||||
|
return status.get_future().get();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
template <typename LoadMethod>
|
||||||
|
void worker(const LoadMethod &loadmethod, std::promise<bool> &status) {
|
||||||
|
std::shared_ptr<Model> model = loadmethod();
|
||||||
|
if (model == nullptr) {
|
||||||
|
status.set_value(false);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
run_ = true;
|
||||||
|
status.set_value(true);
|
||||||
|
|
||||||
|
std::vector<Item> fetch_items;
|
||||||
|
std::vector<Input> inputs;
|
||||||
|
while (get_items_and_wait(fetch_items, max_items_processed_)) {
|
||||||
|
inputs.resize(fetch_items.size());
|
||||||
|
std::transform(fetch_items.begin(), fetch_items.end(), inputs.begin(),
|
||||||
|
[](Item &item) { return item.input; });
|
||||||
|
|
||||||
|
auto ret = model->forwards(inputs, stream_);
|
||||||
|
for (int i = 0; i < (int)fetch_items.size(); ++i) {
|
||||||
|
if (i < (int)ret.size()) {
|
||||||
|
fetch_items[i].pro->set_value(ret[i]);
|
||||||
|
} else {
|
||||||
|
fetch_items[i].pro->set_value(Result());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
inputs.clear();
|
||||||
|
fetch_items.clear();
|
||||||
|
}
|
||||||
|
model.reset();
|
||||||
|
run_ = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool get_items_and_wait(std::vector<Item> &fetch_items, int max_size) {
|
||||||
|
std::unique_lock<std::mutex> l(queue_lock_);
|
||||||
|
cond_.wait(l, [&]() { return !run_ || !input_queue_.empty(); });
|
||||||
|
|
||||||
|
if (!run_) return false;
|
||||||
|
|
||||||
|
fetch_items.clear();
|
||||||
|
for (int i = 0; i < max_size && !input_queue_.empty(); ++i) {
|
||||||
|
fetch_items.emplace_back(std::move(input_queue_.front()));
|
||||||
|
input_queue_.pop();
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool get_item_and_wait(Item &fetch_item) {
|
||||||
|
std::unique_lock<std::mutex> l(queue_lock_);
|
||||||
|
cond_.wait(l, [&]() { return !run_ || !input_queue_.empty(); });
|
||||||
|
|
||||||
|
if (!run_) return false;
|
||||||
|
|
||||||
|
fetch_item = std::move(input_queue_.front());
|
||||||
|
input_queue_.pop();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}; // namespace cpm
|
||||||
|
|
||||||
|
#endif // __CPM_HPP__
|
|
@ -0,0 +1,29 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* File Name : sonar.h
|
||||||
|
* Description : This file contains the common defines of the Extend
|
||||||
|
******************************************************************************
|
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
#ifndef __SONAR_DRIVER_H
|
||||||
|
#define __SONAR_DRIVER_H
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <strings.h>
|
||||||
|
// #include <ros/ros.h>
|
||||||
|
// #include <sensor_msgs/Range.h>
|
||||||
|
#include "uart-ctrl.h"
|
||||||
|
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
#define RX_BUFFER_MAX 10
|
||||||
|
#define TX_BUFFER_MAX 5
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
#endif // __SONAR_DRIVER_H
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
// unsigned int distance[4];
|
|
@ -0,0 +1,72 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* File Name : net-ctrl.h
|
||||||
|
* Description : This file contains the common defines of the Extend
|
||||||
|
******************************************************************************
|
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
|
||||||
|
#ifndef ___UART_CTRL_H__
|
||||||
|
#define ___UART_CTRL_H__
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
typedef struct{
|
||||||
|
int baudrate; //baudrate
|
||||||
|
int databit; //data bits, 5, 6, 7, 8
|
||||||
|
int fctl; //flow control, 0: none, 1: hardware, 2: software
|
||||||
|
int parity; //parity 0: none, 1: odd, 2: even
|
||||||
|
int stopbit; //stop bits, 1, 2
|
||||||
|
const int reserved; //reserved, must be zero
|
||||||
|
}PortInfo_t;
|
||||||
|
|
||||||
|
typedef PortInfo_t *pPortInfo_t;
|
||||||
|
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
/*
|
||||||
|
* 打开串口,返回文件描述符
|
||||||
|
* dev:设备文件名
|
||||||
|
*/
|
||||||
|
int uart_init(const char* dev);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 设置串口
|
||||||
|
* fdcom: 串口文件描述符, pportinfo: 待设置的串口信息
|
||||||
|
*/
|
||||||
|
int uart_set(int fdcom, const pPortInfo_t pportinfo);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 关闭串口
|
||||||
|
* fdcom:串口文件描述符
|
||||||
|
*/
|
||||||
|
void uart_deinit(int fdcom);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 发送数据
|
||||||
|
* fdcom:串口描述符, data:待发送数据, datalen:数据长度
|
||||||
|
* 返回实际发送长度
|
||||||
|
*/
|
||||||
|
int uart_txd(int fdcom, const unsigned char *data, int datalen);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 接收数据
|
||||||
|
* fdcom:串口描述符, data:接收缓冲区, datalen.:接收长度, baudrate:波特率
|
||||||
|
* 返回实际读入的长度
|
||||||
|
*/
|
||||||
|
int uart_rxd(int fdcom, unsigned char *data, int datalen, int baudrate);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // ___UART_CTRL_H__
|
||||||
|
|
|
@ -0,0 +1,74 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2021 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
#include <iostream>
|
||||||
|
#include <string>
|
||||||
|
#include <map>
|
||||||
|
#include <librealsense2/rs.hpp>
|
||||||
|
#include <algorithm>
|
||||||
|
|
||||||
|
//////////////////////////////
|
||||||
|
// Demos Helpers //
|
||||||
|
//////////////////////////////
|
||||||
|
|
||||||
|
// Find devices with specified streams
|
||||||
|
bool device_with_streams(std::vector <rs2_stream> stream_requests, std::string& out_serial)
|
||||||
|
{
|
||||||
|
rs2::context ctx;
|
||||||
|
auto devs = ctx.query_devices();
|
||||||
|
std::vector <rs2_stream> unavailable_streams = stream_requests;
|
||||||
|
for (auto dev : devs)
|
||||||
|
{
|
||||||
|
std::map<rs2_stream, bool> found_streams;
|
||||||
|
for (auto& type : stream_requests)
|
||||||
|
{
|
||||||
|
found_streams[type] = false;
|
||||||
|
for (auto& sensor : dev.query_sensors())
|
||||||
|
{
|
||||||
|
for (auto& profile : sensor.get_stream_profiles())
|
||||||
|
{
|
||||||
|
if (profile.stream_type() == type)
|
||||||
|
{
|
||||||
|
found_streams[type] = true;
|
||||||
|
unavailable_streams.erase(std::remove(unavailable_streams.begin(), unavailable_streams.end(), type), unavailable_streams.end());
|
||||||
|
if (dev.supports(RS2_CAMERA_INFO_SERIAL_NUMBER))
|
||||||
|
out_serial = dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Check if all streams are found in current device
|
||||||
|
bool found_all_streams = true;
|
||||||
|
for (auto& stream : found_streams)
|
||||||
|
{
|
||||||
|
if (!stream.second)
|
||||||
|
{
|
||||||
|
found_all_streams = false;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (found_all_streams)
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
// After scanning all devices, not all requested streams were found
|
||||||
|
for (auto& type : unavailable_streams)
|
||||||
|
{
|
||||||
|
switch (type)
|
||||||
|
{
|
||||||
|
case RS2_STREAM_POSE:
|
||||||
|
case RS2_STREAM_FISHEYE:
|
||||||
|
std::cerr << "Connect T26X and rerun the demo" << std::endl;
|
||||||
|
break;
|
||||||
|
case RS2_STREAM_DEPTH:
|
||||||
|
std::cerr << "The demo requires Realsense camera with DEPTH sensor" << std::endl;
|
||||||
|
break;
|
||||||
|
case RS2_STREAM_COLOR:
|
||||||
|
std::cerr << "The demo requires Realsense camera with RGB sensor" << std::endl;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
throw std::runtime_error("The requested stream: " + std::to_string(type) + ", for the demo is not supported by connected devices!"); // stream type
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,98 @@
|
||||||
|
#ifndef __INFER_HPP__
|
||||||
|
#define __INFER_HPP__
|
||||||
|
|
||||||
|
#include <initializer_list>
|
||||||
|
#include <memory>
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
namespace trt {
|
||||||
|
|
||||||
|
#define INFO(...) trt::__log_func(__FILE__, __LINE__, __VA_ARGS__)
|
||||||
|
void __log_func(const char *file, int line, const char *fmt, ...);
|
||||||
|
|
||||||
|
enum class DType : int { FLOAT = 0, HALF = 1, INT8 = 2, INT32 = 3, BOOL = 4, UINT8 = 5 };
|
||||||
|
|
||||||
|
class Timer {
|
||||||
|
public:
|
||||||
|
Timer();
|
||||||
|
virtual ~Timer();
|
||||||
|
void start(void *stream = nullptr);
|
||||||
|
float stop(const char *prefix = "Timer", bool print = true);
|
||||||
|
|
||||||
|
private:
|
||||||
|
void *start_, *stop_;
|
||||||
|
void *stream_;
|
||||||
|
};
|
||||||
|
|
||||||
|
class BaseMemory {
|
||||||
|
public:
|
||||||
|
BaseMemory() = default;
|
||||||
|
BaseMemory(void *cpu, size_t cpu_bytes, void *gpu, size_t gpu_bytes);
|
||||||
|
virtual ~BaseMemory();
|
||||||
|
virtual void *gpu_realloc(size_t bytes);
|
||||||
|
virtual void *cpu_realloc(size_t bytes);
|
||||||
|
void release_gpu();
|
||||||
|
void release_cpu();
|
||||||
|
void release();
|
||||||
|
inline bool owner_gpu() const { return owner_gpu_; }
|
||||||
|
inline bool owner_cpu() const { return owner_cpu_; }
|
||||||
|
inline size_t cpu_bytes() const { return cpu_bytes_; }
|
||||||
|
inline size_t gpu_bytes() const { return gpu_bytes_; }
|
||||||
|
virtual inline void *get_gpu() const { return gpu_; }
|
||||||
|
virtual inline void *get_cpu() const { return cpu_; }
|
||||||
|
void reference(void *cpu, size_t cpu_bytes, void *gpu, size_t gpu_bytes);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void *cpu_ = nullptr;
|
||||||
|
size_t cpu_bytes_ = 0, cpu_capacity_ = 0;
|
||||||
|
bool owner_cpu_ = true;
|
||||||
|
|
||||||
|
void *gpu_ = nullptr;
|
||||||
|
size_t gpu_bytes_ = 0, gpu_capacity_ = 0;
|
||||||
|
bool owner_gpu_ = true;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename _DT>
|
||||||
|
class Memory : public BaseMemory {
|
||||||
|
public:
|
||||||
|
Memory() = default;
|
||||||
|
Memory(const Memory &other) = delete;
|
||||||
|
Memory &operator=(const Memory &other) = delete;
|
||||||
|
virtual _DT *gpu(size_t size) { return (_DT *)BaseMemory::gpu_realloc(size * sizeof(_DT)); }
|
||||||
|
virtual _DT *cpu(size_t size) { return (_DT *)BaseMemory::cpu_realloc(size * sizeof(_DT)); }
|
||||||
|
|
||||||
|
inline size_t cpu_size() const { return cpu_bytes_ / sizeof(_DT); }
|
||||||
|
inline size_t gpu_size() const { return gpu_bytes_ / sizeof(_DT); }
|
||||||
|
|
||||||
|
virtual inline _DT *gpu() const { return (_DT *)gpu_; }
|
||||||
|
virtual inline _DT *cpu() const { return (_DT *)cpu_; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class Infer {
|
||||||
|
public:
|
||||||
|
virtual bool forward(const std::vector<void *> &bindings, void *stream = nullptr,
|
||||||
|
void *input_consum_event = nullptr) = 0;
|
||||||
|
virtual int index(const std::string &name) = 0;
|
||||||
|
virtual std::vector<int> run_dims(const std::string &name) = 0;
|
||||||
|
virtual std::vector<int> run_dims(int ibinding) = 0;
|
||||||
|
virtual std::vector<int> static_dims(const std::string &name) = 0;
|
||||||
|
virtual std::vector<int> static_dims(int ibinding) = 0;
|
||||||
|
virtual int numel(const std::string &name) = 0;
|
||||||
|
virtual int numel(int ibinding) = 0;
|
||||||
|
virtual int num_bindings() = 0;
|
||||||
|
virtual bool is_input(int ibinding) = 0;
|
||||||
|
virtual bool set_run_dims(const std::string &name, const std::vector<int> &dims) = 0;
|
||||||
|
virtual bool set_run_dims(int ibinding, const std::vector<int> &dims) = 0;
|
||||||
|
virtual DType dtype(const std::string &name) = 0;
|
||||||
|
virtual DType dtype(int ibinding) = 0;
|
||||||
|
virtual bool has_dynamic_dim() = 0;
|
||||||
|
virtual void print() = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
std::shared_ptr<Infer> load(const std::string &file);
|
||||||
|
std::string format_shape(const std::vector<int> &shape);
|
||||||
|
|
||||||
|
} // namespace trt
|
||||||
|
|
||||||
|
#endif // __INFER_HPP__
|
|
@ -0,0 +1,139 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file rs_advanced_mode_command.h
|
||||||
|
* @brief Advanced Mode Commands header file
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef RS2_ADVANCED_MODE_COMMAND_H
|
||||||
|
#define RS2_ADVANCED_MODE_COMMAND_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t plusIncrement;
|
||||||
|
uint32_t minusDecrement;
|
||||||
|
uint32_t deepSeaMedianThreshold;
|
||||||
|
uint32_t scoreThreshA;
|
||||||
|
uint32_t scoreThreshB;
|
||||||
|
uint32_t textureDifferenceThreshold;
|
||||||
|
uint32_t textureCountThreshold;
|
||||||
|
uint32_t deepSeaSecondPeakThreshold;
|
||||||
|
uint32_t deepSeaNeighborThreshold;
|
||||||
|
uint32_t lrAgreeThreshold;
|
||||||
|
}STDepthControlGroup;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t rsmBypass;
|
||||||
|
float diffThresh;
|
||||||
|
float sloRauDiffThresh;
|
||||||
|
uint32_t removeThresh;
|
||||||
|
}STRsm;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t minWest;
|
||||||
|
uint32_t minEast;
|
||||||
|
uint32_t minWEsum;
|
||||||
|
uint32_t minNorth;
|
||||||
|
uint32_t minSouth;
|
||||||
|
uint32_t minNSsum;
|
||||||
|
uint32_t uShrink;
|
||||||
|
uint32_t vShrink;
|
||||||
|
}STRauSupportVectorControl;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t disableSADColor;
|
||||||
|
uint32_t disableRAUColor;
|
||||||
|
uint32_t disableSLORightColor;
|
||||||
|
uint32_t disableSLOLeftColor;
|
||||||
|
uint32_t disableSADNormalize;
|
||||||
|
}STColorControl;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t rauDiffThresholdRed;
|
||||||
|
uint32_t rauDiffThresholdGreen;
|
||||||
|
uint32_t rauDiffThresholdBlue;
|
||||||
|
}STRauColorThresholdsControl;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t diffThresholdRed;
|
||||||
|
uint32_t diffThresholdGreen;
|
||||||
|
uint32_t diffThresholdBlue;
|
||||||
|
}STSloColorThresholdsControl;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t sloK1Penalty;
|
||||||
|
uint32_t sloK2Penalty;
|
||||||
|
uint32_t sloK1PenaltyMod1;
|
||||||
|
uint32_t sloK2PenaltyMod1;
|
||||||
|
uint32_t sloK1PenaltyMod2;
|
||||||
|
uint32_t sloK2PenaltyMod2;
|
||||||
|
}STSloPenaltyControl;
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
float lambdaCensus;
|
||||||
|
float lambdaAD;
|
||||||
|
uint32_t ignoreSAD;
|
||||||
|
}STHdad;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
float colorCorrection1;
|
||||||
|
float colorCorrection2;
|
||||||
|
float colorCorrection3;
|
||||||
|
float colorCorrection4;
|
||||||
|
float colorCorrection5;
|
||||||
|
float colorCorrection6;
|
||||||
|
float colorCorrection7;
|
||||||
|
float colorCorrection8;
|
||||||
|
float colorCorrection9;
|
||||||
|
float colorCorrection10;
|
||||||
|
float colorCorrection11;
|
||||||
|
float colorCorrection12;
|
||||||
|
}STColorCorrection;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t meanIntensitySetPoint;
|
||||||
|
}STAEControl;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t depthUnits;
|
||||||
|
int32_t depthClampMin;
|
||||||
|
int32_t depthClampMax;
|
||||||
|
uint32_t disparityMode;
|
||||||
|
int32_t disparityShift;
|
||||||
|
}STDepthTableControl;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t uDiameter;
|
||||||
|
uint32_t vDiameter;
|
||||||
|
}STCensusRadius;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
float amplitude;
|
||||||
|
}STAFactor;
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /*RS2_ADVANCED_MODE_COMMAND_H*/
|
|
@ -0,0 +1,200 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_pipeline.h
|
||||||
|
* \brief
|
||||||
|
* Exposes RealSense processing-block functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_CONFIG_H
|
||||||
|
#define LIBREALSENSE_RS2_CONFIG_H
|
||||||
|
|
||||||
|
#define RS2_DEFAULT_TIMEOUT 15000
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rs_types.h"
|
||||||
|
#include "rs_sensor.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create a config instance
|
||||||
|
* The config allows pipeline users to request filters for the pipeline streams and device selection and configuration.
|
||||||
|
* This is an optional step in pipeline creation, as the pipeline resolves its streaming device internally.
|
||||||
|
* Config provides its users a way to set the filters and test if there is no conflict with the pipeline requirements
|
||||||
|
* from the device. It also allows the user to find a matching device for the config filters and the pipeline, in order to
|
||||||
|
* select a device explicitly, and modify its controls before streaming starts.
|
||||||
|
*
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return rs2_config* A pointer to a new config instance
|
||||||
|
*/
|
||||||
|
rs2_config* rs2_create_config(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Deletes an instance of a config
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
*/
|
||||||
|
void rs2_delete_config(rs2_config* config);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable a device stream explicitly, with selected stream parameters.
|
||||||
|
* The method allows the application to request a stream with specific configuration. If no stream is explicitly enabled, the pipeline
|
||||||
|
* configures the device and its streams according to the attached computer vision modules and processing blocks requirements, or
|
||||||
|
* default configuration for the first available device.
|
||||||
|
* The application can configure any of the input stream parameters according to its requirement, or set to 0 for don't care value.
|
||||||
|
* The config accumulates the application calls for enable configuration methods, until the configuration is applied. Multiple enable
|
||||||
|
* stream calls for the same stream with conflicting parameters override each other, and the last call is maintained.
|
||||||
|
* Upon calling \c resolve(), the config checks for conflicts between the application configuration requests and the attached computer
|
||||||
|
* vision modules and processing blocks requirements, and fails if conflicts are found. Before \c resolve() is called, no conflict
|
||||||
|
* check is done.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] stream Stream type to be enabled
|
||||||
|
* \param[in] index Stream index, used for multiple streams of the same type. -1 indicates any.
|
||||||
|
* \param[in] width Stream image width - for images streams. 0 indicates any.
|
||||||
|
* \param[in] height Stream image height - for images streams. 0 indicates any.
|
||||||
|
* \param[in] format Stream data format - pixel format for images streams, of data type for other streams. RS2_FORMAT_ANY indicates any.
|
||||||
|
* \param[in] framerate Stream frames per second. 0 indicates any.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_enable_stream(rs2_config* config,
|
||||||
|
rs2_stream stream,
|
||||||
|
int index,
|
||||||
|
int width,
|
||||||
|
int height,
|
||||||
|
rs2_format format,
|
||||||
|
int framerate,
|
||||||
|
rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable all device streams explicitly.
|
||||||
|
* The conditions and behavior of this method are similar to those of \c enable_stream().
|
||||||
|
* This filter enables all raw streams of the selected device. The device is either selected explicitly by the application,
|
||||||
|
* or by the pipeline requirements or default. The list of streams is device dependent.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_enable_all_stream(rs2_config* config, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Select a specific device explicitly by its serial number, to be used by the pipeline.
|
||||||
|
* The conditions and behavior of this method are similar to those of \c enable_stream().
|
||||||
|
* This method is required if the application needs to set device or sensor settings prior to pipeline streaming, to enforce
|
||||||
|
* the pipeline to use the configured device.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] serial device serial number, as returned by RS2_CAMERA_INFO_SERIAL_NUMBER
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_enable_device(rs2_config* config, const char* serial, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Select a recorded device from a file, to be used by the pipeline through playback.
|
||||||
|
* The device available streams are as recorded to the file, and \c resolve() considers only this device and configuration
|
||||||
|
* as available.
|
||||||
|
* This request cannot be used if enable_record_to_file() is called for the current config, and vise versa
|
||||||
|
* By default, playback is repeated once the file ends. To control this, see 'rs2_config_enable_device_from_file_repeat_option'.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] file The playback file of the device
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_enable_device_from_file(rs2_config* config, const char* file, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Select a recorded device from a file, to be used by the pipeline through playback.
|
||||||
|
* The device available streams are as recorded to the file, and \c resolve() considers only this device and configuration
|
||||||
|
* as available.
|
||||||
|
* This request cannot be used if enable_record_to_file() is called for the current config, and vise versa
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] file The playback file of the device
|
||||||
|
* \param[in] repeat_playback if true, when file ends the playback starts again, in an infinite loop;
|
||||||
|
if false, when file ends playback does not start again, and should by stopped manually by the user.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_enable_device_from_file_repeat_option(rs2_config* config, const char* file, int repeat_playback, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Requires that the resolved device would be recorded to file
|
||||||
|
* This request cannot be used if enable_device_from_file() is called for the current config, and vise versa
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] file The desired file for the output record
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_enable_record_to_file(rs2_config* config, const char* file, rs2_error ** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Disable a device stream explicitly, to remove any requests on this stream type.
|
||||||
|
* The stream can still be enabled due to pipeline computer vision module request. This call removes any filter on the
|
||||||
|
* stream configuration.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] stream Stream type, for which the filters are cleared
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_disable_stream(rs2_config* config, rs2_stream stream, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Disable a device stream explicitly, to remove any requests on this stream profile.
|
||||||
|
* The stream can still be enabled due to pipeline computer vision module request. This call removes any filter on the
|
||||||
|
* stream configuration.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] stream Stream type, for which the filters are cleared
|
||||||
|
* \param[in] index Stream index, for which the filters are cleared
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_disable_indexed_stream(rs2_config* config, rs2_stream stream, int index, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Disable all device stream explicitly, to remove any requests on the streams profiles.
|
||||||
|
* The streams can still be enabled due to pipeline computer vision module request. This call removes any filter on the
|
||||||
|
* streams configuration.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_config_disable_all_streams(rs2_config* config, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Resolve the configuration filters, to find a matching device and streams profiles.
|
||||||
|
* The method resolves the user configuration filters for the device and streams, and combines them with the requirements of
|
||||||
|
* the computer vision modules and processing blocks attached to the pipeline. If there are no conflicts of requests, it looks
|
||||||
|
* for an available device, which can satisfy all requests, and selects the first matching streams configuration. In the absence
|
||||||
|
* of any request, the rs2::config selects the first available device and the first color and depth streams configuration.
|
||||||
|
* The pipeline profile selection during \c start() follows the same method. Thus, the selected profile is the same, if no
|
||||||
|
* change occurs to the available devices occurs.
|
||||||
|
* Resolving the pipeline configuration provides the application access to the pipeline selected device for advanced control.
|
||||||
|
* The returned configuration is not applied to the device, so the application doesn't own the device sensors. However, the
|
||||||
|
* application can call \c enable_device(), to enforce the device returned by this method is selected by pipeline \c start(),
|
||||||
|
* and configure the device and sensors options or extensions before streaming starts.
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] pipe The pipeline for which the selected filters are applied
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return A matching device and streams profile, which satisfies the filters and pipeline requests.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_config_resolve(rs2_config* config, rs2_pipeline* pipe, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if the config can resolve the configuration filters, to find a matching device and streams profiles.
|
||||||
|
* The resolution conditions are as described in \c resolve().
|
||||||
|
*
|
||||||
|
* \param[in] config A pointer to an instance of a config
|
||||||
|
* \param[in] pipe The pipeline for which the selected filters are applied
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return True if a valid profile selection exists, false if no selection can be found under the config filters and the available devices.
|
||||||
|
*/
|
||||||
|
int rs2_config_can_resolve(rs2_config* config, rs2_pipeline* pipe, rs2_error ** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,147 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_context.h
|
||||||
|
* \brief Exposes RealSense context functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_CONTEXT_H
|
||||||
|
#define LIBREALSENSE_RS2_CONTEXT_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
#include "rs_types.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Creates RealSense context that is required for the rest of the API.
|
||||||
|
* \param[in] api_version Users are expected to pass their version of \c RS2_API_VERSION to make sure they are running the correct librealsense version.
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return Context object
|
||||||
|
*/
|
||||||
|
rs2_context* rs2_create_context(int api_version, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Frees the relevant context object.
|
||||||
|
* \param[in] context Object that is no longer needed
|
||||||
|
*/
|
||||||
|
void rs2_delete_context(rs2_context* context);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* set callback to get devices changed events
|
||||||
|
* these events will be raised by the context whenever new RealSense device is connected or existing device gets disconnected
|
||||||
|
* \param context Object representing librealsense session
|
||||||
|
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the context
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_devices_changed_callback_cpp(rs2_context* context, rs2_devices_changed_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* set callback to get devices changed events
|
||||||
|
* these events will be raised by the context whenever new RealSense device is connected or existing device gets disconnected
|
||||||
|
* \param context Object representing librealsense session
|
||||||
|
* \param[in] callback function pointer to register as per-notifications callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_devices_changed_callback(const rs2_context* context, rs2_devices_changed_callback_ptr callback, void* user, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create a new device and add it to the context
|
||||||
|
* \param ctx The context to which the new device will be added
|
||||||
|
* \param file The file from which the device should be created
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* @return A pointer to a device that plays data from the file, or null in case of failure
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_context_add_device(rs2_context* ctx, const char* file, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add an instance of software device to the context
|
||||||
|
* \param ctx The context to which the new device will be added
|
||||||
|
* \param dev Instance of software device to register into the context
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_context_add_software_device(rs2_context* ctx, rs2_device* dev, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Removes a playback device from the context, if exists
|
||||||
|
* \param[in] ctx The context from which the device should be removed
|
||||||
|
* \param[in] file The file name that was used to add the device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_context_remove_device(rs2_context* ctx, const char* file, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Removes tracking module.
|
||||||
|
* function query_devices() locks the tracking module in the tm_context object.
|
||||||
|
* If the tracking module device is not used it should be removed using this function, so that other applications could find it.
|
||||||
|
* This function can be used both before the call to query_device() to prevent enabling tracking modules or afterwards to
|
||||||
|
* release them.
|
||||||
|
*/
|
||||||
|
void rs2_context_unload_tracking_module(rs2_context* ctx, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* create a static snapshot of all connected devices at the time of the call
|
||||||
|
* \param context Object representing librealsense session
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the list of devices, should be released by rs2_delete_device_list
|
||||||
|
*/
|
||||||
|
rs2_device_list* rs2_query_devices(const rs2_context* context, rs2_error** error);
|
||||||
|
|
||||||
|
#define RS2_PRODUCT_LINE_ANY 0xff
|
||||||
|
#define RS2_PRODUCT_LINE_ANY_INTEL 0xfe
|
||||||
|
#define RS2_PRODUCT_LINE_NON_INTEL 0x01
|
||||||
|
#define RS2_PRODUCT_LINE_D400 0x02
|
||||||
|
#define RS2_PRODUCT_LINE_SR300 0x04
|
||||||
|
#define RS2_PRODUCT_LINE_L500 0x08
|
||||||
|
#define RS2_PRODUCT_LINE_T200 0x10
|
||||||
|
#define RS2_PRODUCT_LINE_DEPTH (RS2_PRODUCT_LINE_L500 | RS2_PRODUCT_LINE_SR300 | RS2_PRODUCT_LINE_D400)
|
||||||
|
#define RS2_PRODUCT_LINE_TRACKING RS2_PRODUCT_LINE_T200
|
||||||
|
|
||||||
|
/**
|
||||||
|
* create a static snapshot of all connected devices at the time of the call
|
||||||
|
* \param context Object representing librealsense session
|
||||||
|
* \param product_mask Controls what kind of devices will be returned
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the list of devices, should be released by rs2_delete_device_list
|
||||||
|
*/
|
||||||
|
rs2_device_list* rs2_query_devices_ex(const rs2_context* context, int product_mask, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Creates RealSense device_hub .
|
||||||
|
* \param[in] context The context for the device hub
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return Device hub object
|
||||||
|
*/
|
||||||
|
rs2_device_hub* rs2_create_device_hub(const rs2_context* context, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Frees the relevant device hub object.
|
||||||
|
* \param[in] hub Object that is no longer needed
|
||||||
|
*/
|
||||||
|
void rs2_delete_device_hub(const rs2_device_hub* hub);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* If any device is connected return it, otherwise wait until next RealSense device connects.
|
||||||
|
* Calling this method multiple times will cycle through connected devices
|
||||||
|
* \param[in] ctx The context to creat the device
|
||||||
|
* \param[in] hub The device hub object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return device object
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_device_hub_wait_for_device(const rs2_device_hub* hub, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Checks if device is still connected
|
||||||
|
* \param[in] hub The device hub object
|
||||||
|
* \param[in] device The device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return 1 if the device is connected, 0 otherwise
|
||||||
|
*/
|
||||||
|
int rs2_device_hub_is_device_connected(const rs2_device_hub* hub, const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,551 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_device.h
|
||||||
|
* \brief Exposes RealSense device functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_DEVICE_H
|
||||||
|
#define LIBREALSENSE_RS2_DEVICE_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rs_types.h"
|
||||||
|
#include "rs_sensor.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Determines number of devices in a list.
|
||||||
|
* \param[in] info_list The list of connected devices captured using rs2_query_devices
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Device count
|
||||||
|
*/
|
||||||
|
int rs2_get_device_count(const rs2_device_list* info_list, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Deletes device list, any devices created using this list will remain unaffected.
|
||||||
|
* \param[in] info_list List to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_device_list(rs2_device_list* info_list);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Checks if a specific device is contained inside a device list.
|
||||||
|
* \param[in] info_list The list of devices to check in
|
||||||
|
* \param[in] device RealSense device to check for
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return True if the device is in the list and false otherwise
|
||||||
|
*/
|
||||||
|
int rs2_device_list_contains(const rs2_device_list* info_list, const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a device by index. The device object represents a physical camera and provides the means to manipulate it.
|
||||||
|
* \param[in] info_list the list containing the device to retrieve
|
||||||
|
* \param[in] index The zero based index of device to retrieve
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The requested device, should be released by rs2_delete_device
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_create_device(const rs2_device_list* info_list, int index, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delete RealSense device
|
||||||
|
* \param[in] device Realsense device to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_device(rs2_device* device);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve camera specific information, like versions of various internal components.
|
||||||
|
* \param[in] device The RealSense device
|
||||||
|
* \param[in] info Camera info type to retrieve
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The requested camera info string, in a format specific to the device model
|
||||||
|
*/
|
||||||
|
const char* rs2_get_device_info(const rs2_device* device, rs2_camera_info info, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if a camera supports a specific camera info type.
|
||||||
|
* \param[in] device The RealSense device to check
|
||||||
|
* \param[in] info The parameter to check for support
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return True if the parameter both exist and well-defined for the specific device
|
||||||
|
*/
|
||||||
|
int rs2_supports_device_info(const rs2_device* device, rs2_camera_info info, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Send hardware reset request to the device. The actual reset is asynchronous.
|
||||||
|
* Note: Invalidates all handles to this device.
|
||||||
|
* \param[in] device The RealSense device to reset
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_hardware_reset(const rs2_device * device, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Send raw data to device
|
||||||
|
* \param[in] device RealSense device to send data to
|
||||||
|
* \param[in] raw_data_to_send Raw data to be sent to device
|
||||||
|
* \param[in] size_of_raw_data_to_send Size of raw_data_to_send in bytes
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Device's response in a rs2_raw_data_buffer, which should be released by rs2_delete_raw_data
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_send_and_receive_raw_data(rs2_device* device, void* raw_data_to_send, unsigned size_of_raw_data_to_send, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Test if the given device can be extended to the requested extension.
|
||||||
|
* \param[in] device Realsense device
|
||||||
|
* \param[in] extension The extension to which the device should be tested if it is extendable
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Non-zero value iff the device can be extended to the given extension
|
||||||
|
*/
|
||||||
|
int rs2_is_device_extendable_to(const rs2_device* device, rs2_extension extension, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create a static snapshot of all connected sensors within a specific device.
|
||||||
|
* \param[in] device Specific RealSense device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The list of sensors, should be released by rs2_delete_sensor_list
|
||||||
|
*/
|
||||||
|
rs2_sensor_list* rs2_query_sensors(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enter the given device into loopback operation mode that uses the given file as input for raw data
|
||||||
|
* \param[in] device Device to enter into loopback operation mode
|
||||||
|
* \param[in] from_file Path to bag file with raw data for loopback
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_loopback_enable(const rs2_device* device, const char* from_file, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Restores the given device into normal operation mode
|
||||||
|
* \param[in] device Device to restore to normal operation mode
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_loopback_disable(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Checks if the device is in loopback mode or not
|
||||||
|
* \param[in] device Device to check for operation mode
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if the device is in loopback operation mode
|
||||||
|
*/
|
||||||
|
int rs2_loopback_is_enabled(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Connects to a given tm2 controller
|
||||||
|
* \param[in] device Device to connect to the controller
|
||||||
|
* \param[in] mac_addr The MAC address of the desired controller
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_connect_tm2_controller(const rs2_device* device, const unsigned char* mac_addr, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Disconnects a given tm2 controller
|
||||||
|
* \param[in] device Device to disconnect the controller from
|
||||||
|
* \param[in] id The ID of the desired controller
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_disconnect_tm2_controller(const rs2_device* device, int id, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Reset device to factory calibration
|
||||||
|
* \param[in] device The RealSense device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_reset_to_factory_calibration(const rs2_device* device, rs2_error** e);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Write calibration to device's EEPROM
|
||||||
|
* \param[in] device The RealSense device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_write_calibration(const rs2_device* device, rs2_error** e);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update device to the provided firmware, the device must be extendable to RS2_EXTENSION_UPDATABLE.
|
||||||
|
* This call is executed on the caller's thread and it supports progress notifications via the optional callback.
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[in] fw_image Firmware image buffer
|
||||||
|
* \param[in] fw_image_size Firmware image buffer size
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_update_firmware_cpp(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update device to the provided firmware, the device must be extendable to RS2_EXTENSION_UPDATABLE.
|
||||||
|
* This call is executed on the caller's thread and it supports progress notifications via the optional callback.
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[in] fw_image Firmware image buffer
|
||||||
|
* \param[in] fw_image_size Firmware image buffer size
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] client_data Optional client data for the callback
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_update_firmware(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create backup of camera flash memory. Such backup does not constitute valid firmware image, and cannot be
|
||||||
|
* loaded back to the device, but it does contain all calibration and device information.
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_create_flash_backup_cpp(const rs2_device* device, rs2_update_progress_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create backup of camera flash memory. Such backup does not constitute valid firmware image, and cannot be
|
||||||
|
* loaded back to the device, but it does contain all calibration and device information.
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] client_data Optional client data for the callback
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_create_flash_backup(const rs2_device* device, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);
|
||||||
|
|
||||||
|
#define RS2_UNSIGNED_UPDATE_MODE_UPDATE 0
|
||||||
|
#define RS2_UNSIGNED_UPDATE_MODE_READ_ONLY 1
|
||||||
|
#define RS2_UNSIGNED_UPDATE_MODE_FULL 2
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update device to the provided firmware by writing raw data directly to the flash, this command can be executed only on unlocked camera.
|
||||||
|
* The device must be extendable to RS2_EXTENSION_UPDATABLE.
|
||||||
|
* This call is executed on the caller's thread and it supports progress notifications via the optional callback.
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[in] fw_image Firmware image buffer
|
||||||
|
* \param[in] fw_image_size Firmware image buffer size
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] update_mode Select one of RS2_UNSIGNED_UPDATE_MODE, WARNING!!! setting to any option other than RS2_UNSIGNED_UPDATE_MODE_UPDATE will make this call unsafe and might damage the camera
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_update_firmware_unsigned_cpp(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback* callback, int update_mode, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Checks if the device and the provided firmware image are compatible
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[in] fw_image Firmware image buffer
|
||||||
|
* \param[in] fw_image_size Firmware image buffer size in bytes
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Non-zero if the firmware is compatible with the device and 0 otherwise
|
||||||
|
*/
|
||||||
|
int rs2_check_firmware_compatibility(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update device to the provided firmware by writing raw data directly to the flash, this command can be executed only on unlocked camera.
|
||||||
|
* The device must be extendable to RS2_EXTENSION_UPDATABLE.
|
||||||
|
* This call is executed on the caller's thread and it supports progress notifications via the optional callback.
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[in] fw_image Firmware image buffer
|
||||||
|
* \param[in] fw_image_size Firmware image buffer size
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] client_data Optional client data for the callback
|
||||||
|
* \param[in] update_mode Select one of RS2_UNSIGNED_UPDATE_MODE, WARNING!!! setting to any option other than RS2_UNSIGNED_UPDATE_MODE_UPDATE will make this call unsafe and might damage the camera
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_update_firmware_unsigned(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback_ptr callback, void* client_data, int update_mode, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enter the device to update state, this will cause the updatable device to disconnect and reconnect as update device.
|
||||||
|
* \param[in] device Device to update
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_enter_update_state(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This will improve the depth noise.
|
||||||
|
* \param[in] json_content Json string to configure regular speed on chip calibration parameters:
|
||||||
|
{
|
||||||
|
"calib type" : 0,
|
||||||
|
"speed": 3,
|
||||||
|
"scan parameter": 0,
|
||||||
|
"adjust both sides": 0,
|
||||||
|
"white wall mode": 0
|
||||||
|
}
|
||||||
|
calib_type - calibraton type: 0 = regular, 1 = focal length, 2 = both regular and focal length in order
|
||||||
|
speed - for regular calibration. value can be one of: Very fast = 0, Fast = 1, Medium = 2, Slow = 3, White wall = 4, default is Slow for type 0 and Fast for type 2
|
||||||
|
scan_parameter - for regular calibration. value can be one of: Py scan (default) = 0, Rx scan = 1
|
||||||
|
adjust_both_sides - for focal length calibration. value can be one of: 0 = adjust right only, 1 = adjust both sides
|
||||||
|
white_wall_mode - white wall mode: 0 for normal mode and 1 for white wall mode
|
||||||
|
if json is nullptr it will be ignored and calibration will use the default parameters
|
||||||
|
* \param[out] health The absolute value of regular calibration Health-Check captures how far camera calibration is from the optimal one
|
||||||
|
[0, 0.25) - Good
|
||||||
|
[0.25, 0.75) - Can be Improved
|
||||||
|
[0.75, ) - Requires Calibration
|
||||||
|
The absolute value of focal length calibration Health-Check captures how far camera calibration is from the optimal one
|
||||||
|
[0, 0.15) - Good
|
||||||
|
[0.15, 0.75) - Can be Improved
|
||||||
|
[0.75, ) - Requires Calibration
|
||||||
|
The two health numbers are encoded in one integer as follows for calib_type 2:
|
||||||
|
Regular health number times 1000 are bits 0 to 11
|
||||||
|
Regular health number is negative if bit 24 is 1
|
||||||
|
Focal length health number times 1000 are bits 12 to 23
|
||||||
|
Focal length health number is negative if bit 25 is 1
|
||||||
|
* \param[in] callback Optional callback to get progress notifications
|
||||||
|
* \param[in] timeout_ms Timeout in ms (use 5000 msec unless instructed otherwise)
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_on_chip_calibration_cpp(rs2_device* device, const void* json_content, int content_size, float* health, rs2_update_progress_callback* progress_callback, int timeout_ms, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This will improve the depth noise.
|
||||||
|
* \param[in] json_content Json string to configure regular speed on chip calibration parameters:
|
||||||
|
{
|
||||||
|
"calib type" : 0,
|
||||||
|
"speed": 3,
|
||||||
|
"scan parameter": 0,
|
||||||
|
"adjust both sides": 0,
|
||||||
|
"white wall mode": 0
|
||||||
|
}
|
||||||
|
calib_type - calibraton type: 0 = regular, 1 = focal length, 2 = both regular and focal length in order
|
||||||
|
speed - for regular calibration, value can be one of: Very fast = 0, Fast = 1, Medium = 2, Slow = 3, White wall = 4, default is Slow for type 0 and Fast for type 2
|
||||||
|
scan_parameter - for regular calibration. value can be one of: Py scan (default) = 0, Rx scan = 1
|
||||||
|
adjust_both_sides - for focal length calibration. value can be one of: 0 = adjust right only, 1 = adjust both sides
|
||||||
|
white_wall_mode - white wall mode: 0 for normal mode and 1 for white wall mode
|
||||||
|
if json is nullptr it will be ignored and calibration will use the default parameters
|
||||||
|
* \param[out] health The absolute value of regular calibration Health-Check captures how far camera calibration is from the optimal one
|
||||||
|
[0, 0.25) - Good
|
||||||
|
[0.25, 0.75) - Can be Improved
|
||||||
|
[0.75, ) - Requires Calibration
|
||||||
|
The absolute value of focal length calibration Health-Check captures how far camera calibration is from the optimal one
|
||||||
|
[0, 0.15) - Good
|
||||||
|
[0.15, 0.75) - Can be Improved
|
||||||
|
[0.75, ) - Requires Calibration
|
||||||
|
The two health numbers are encoded in one integer as follows for calib_type 2:
|
||||||
|
Regular health number times 1000 are bits 0 to 11
|
||||||
|
Regular health number is negative if bit 24 is 1
|
||||||
|
Focal length health number times 1000 are bits 12 to 23
|
||||||
|
Focal length health number is negative if bit 25 is 1
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] client_data Optional client data for the callback
|
||||||
|
* \param[in] timeout_ms Timeout in ms (use 5000 msec unless instructed otherwise)
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_on_chip_calibration(rs2_device* device, const void* json_content, int content_size, float* health, rs2_update_progress_callback_ptr callback, void* client_data, int timeout_ms, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This will adjust camera absolute distance to flat target. User needs to enter the known ground truth.
|
||||||
|
* \param[in] ground_truth_mm Ground truth in mm must be between 60 and 10000
|
||||||
|
* \param[in] json_content Json string to configure tare calibration parameters:
|
||||||
|
{
|
||||||
|
"average step count": 20,
|
||||||
|
"step count": 20,
|
||||||
|
"accuracy": 2,
|
||||||
|
"scan parameter": 0,
|
||||||
|
"data sampling": 0
|
||||||
|
}
|
||||||
|
average step count - number of frames to average, must be between 1 - 30, default = 20
|
||||||
|
step count - max iteration steps, must be between 5 - 30, default = 10
|
||||||
|
accuracy - Subpixel accuracy level, value can be one of: Very high = 0 (0.025%), High = 1 (0.05%), Medium = 2 (0.1%), Low = 3 (0.2%), Default = Very high (0.025%), default is Medium
|
||||||
|
scan_parameter - value can be one of: Py scan (default) = 0, Rx scan = 1
|
||||||
|
data_sampling - value can be one of:polling data sampling = 0, interrupt data sampling = 1
|
||||||
|
if json is nullptr it will be ignored and calibration will use the default parameters
|
||||||
|
* \param[in] content_size Json string size if its 0 the json will be ignored and calibration will use the default parameters
|
||||||
|
* \param[in] callback Optional callback to get progress notifications
|
||||||
|
* \param[in] timeout_ms Timeout in ms (use 5000 msec unless instructed otherwise)
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_tare_calibration_cpp(rs2_device* dev, float ground_truth_mm, const void* json_content, int content_size, rs2_update_progress_callback* progress_callback, int timeout_ms, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Used in device_calibration; enumerates the different calibration types
|
||||||
|
* available for that extension.
|
||||||
|
*/
|
||||||
|
typedef enum rs2_calibration_type
|
||||||
|
{
|
||||||
|
RS2_CALIBRATION_AUTO_DEPTH_TO_RGB,
|
||||||
|
RS2_CALIBRATION_MANUAL_DEPTH_TO_RGB,
|
||||||
|
RS2_CALIBRATION_THERMAL,
|
||||||
|
RS2_CALIBRATION_TYPE_COUNT
|
||||||
|
} rs2_calibration_type;
|
||||||
|
const char* rs2_calibration_type_to_string( rs2_calibration_type );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Used in device_calibration with rs2_calibration_change_callback
|
||||||
|
*/
|
||||||
|
typedef enum rs2_calibration_status
|
||||||
|
{
|
||||||
|
// Anything >= 0 is not an issue
|
||||||
|
RS2_CALIBRATION_TRIGGERED = 0, // AC triggered and is active; conditions are valid
|
||||||
|
RS2_CALIBRATION_SPECIAL_FRAME = 1, // Special frame received; expect a frame-drop!
|
||||||
|
RS2_CALIBRATION_STARTED = 2, // Have all frames in hand; starting processing
|
||||||
|
RS2_CALIBRATION_NOT_NEEDED = 3, // Finished; existing calibration within tolerances; nothing done!
|
||||||
|
RS2_CALIBRATION_SUCCESSFUL = 4, // Finished; have new calibration in-hand
|
||||||
|
|
||||||
|
RS2_CALIBRATION_RETRY = -1, // Initiating retry (asked for a new special frame)
|
||||||
|
RS2_CALIBRATION_FAILED = -2, // Unexpected: exception, device removed, stream stopped, etc.
|
||||||
|
RS2_CALIBRATION_SCENE_INVALID = -3, // Scene was not good enough for calibration; will retry
|
||||||
|
RS2_CALIBRATION_BAD_RESULT = -4, // Calibration finished, but results aren't good; will retry
|
||||||
|
RS2_CALIBRATION_BAD_CONDITIONS = -5, // Trigger was attempted but conditions (temp/APD) were invalid (still inactive)
|
||||||
|
|
||||||
|
RS2_CALIBRATION_STATUS_FIRST = -5,
|
||||||
|
RS2_CALIBRATION_STATUS_LAST = 4,
|
||||||
|
RS2_CALIBRATION_STATUS_COUNT = RS2_CALIBRATION_STATUS_LAST - RS2_CALIBRATION_STATUS_FIRST + 1,
|
||||||
|
} rs2_calibration_status;
|
||||||
|
const char* rs2_calibration_status_to_string( rs2_calibration_status );
|
||||||
|
|
||||||
|
typedef struct rs2_calibration_change_callback rs2_calibration_change_callback;
|
||||||
|
typedef void (*rs2_calibration_change_callback_ptr)(rs2_calibration_status, void* arg);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Adds a callback for a sensor that gets called when calibration (intrinsics) changes, e.g. due to auto-calibration
|
||||||
|
* \param[in] sensor the sensor
|
||||||
|
* \param[in] callback the C callback function that gets called
|
||||||
|
* \param[in] user user argument that gets passed to the callback function
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_register_calibration_change_callback( rs2_device* dev, rs2_calibration_change_callback_ptr callback, void* user, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Adds a callback for a sensor that gets called when calibration (intrinsics) changes, e.g. due to auto-calibration
|
||||||
|
* \param[in] sensor the sensor
|
||||||
|
* \param[in] callback the C++ callback interface that gets called
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_register_calibration_change_callback_cpp( rs2_device* dev, rs2_calibration_change_callback* callback, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Triggers calibration of the given type
|
||||||
|
* \param[in] dev the device
|
||||||
|
* \param[in] type the type of calibration requested
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_trigger_device_calibration( rs2_device* dev, rs2_calibration_type type, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This will adjust camera absolute distance to flat target. User needs to enter the known ground truth.
|
||||||
|
* \param[in] ground_truth_mm Ground truth in mm must be between 60 and 10000
|
||||||
|
* \param[in] json_content Json string to configure tare calibration parameters:
|
||||||
|
{
|
||||||
|
"average_step_count": 20,
|
||||||
|
"step count": 20,
|
||||||
|
"accuracy": 2,
|
||||||
|
"scan parameter": 0,
|
||||||
|
"data sampling": 0
|
||||||
|
}
|
||||||
|
average step count - number of frames to average, must be between 1 - 30, default = 20
|
||||||
|
step count - max iteration steps, must be between 5 - 30, default = 10
|
||||||
|
accuracy - Subpixel accuracy level, value can be one of: Very high = 0 (0.025%), High = 1 (0.05%), Medium = 2 (0.1%), Low = 3 (0.2%), Default = Very high (0.025%), default is Medium
|
||||||
|
scan_parameter - value can be one of: Py scan (default) = 0, Rx scan = 1
|
||||||
|
data_sampling - value can be one of:polling data sampling = 0, interrupt data sampling = 1
|
||||||
|
if json is nullptr it will be ignored and calibration will use the default parameters
|
||||||
|
* \param[in] content_size Json string size if its 0 the json will be ignored and calibration will use the default parameters
|
||||||
|
* \param[in] callback Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] client_data Optional client data for the callback
|
||||||
|
* \param[in] timeout_ms Timeout in ms (use 5000 msec unless instructed otherwise)
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_tare_calibration(rs2_device* dev, float ground_truth_mm, const void* json_content, int content_size, rs2_update_progress_callback_ptr callback, void* client_data, int timeout_ms, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read current calibration table from flash.
|
||||||
|
* \return Calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_get_calibration_table(const rs2_device* dev, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set current table to dynamic area.
|
||||||
|
* \param[in] Calibration table
|
||||||
|
*/
|
||||||
|
void rs2_set_calibration_table(const rs2_device* device, const void* calibration, int calibration_size, rs2_error** error);
|
||||||
|
|
||||||
|
/* Serialize JSON content, returns ASCII-serialized JSON string on success. otherwise nullptr */
|
||||||
|
rs2_raw_data_buffer* rs2_serialize_json(rs2_device* dev, rs2_error** error);
|
||||||
|
|
||||||
|
/* Load JSON and apply advanced-mode controls */
|
||||||
|
void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Run target-based focal length calibration
|
||||||
|
* \param[in] device: device to calibrate
|
||||||
|
* \param[in] left_queue: container for left IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI.
|
||||||
|
* \param[in] right_queue: container for right IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI
|
||||||
|
* \param[in] target_width: the rectangle width in mm on the target
|
||||||
|
* \param[in] target_height: the rectangle height in mm on the target
|
||||||
|
* \param[in] adjust_both_sides: 1 for adjusting both left and right camera calibration tables, and 0 for adjusting right camera calibraion table only
|
||||||
|
* \param[out] ratio: the corrected ratio from the calibration
|
||||||
|
* \param[out] angle: the target's tilt angle
|
||||||
|
* \param[in] callback: Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_focal_length_calibration_cpp(rs2_device* device, rs2_frame_queue* left_queue , rs2_frame_queue* right_queue, float target_width, float target_height, int adjust_both_sides,
|
||||||
|
float* ratio, float* angle, rs2_update_progress_callback * progress_callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Run target-based focal length calibration
|
||||||
|
* \param[in] device: device to calibrate
|
||||||
|
* \param[in] left_queue: container for left IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI.
|
||||||
|
* \param[in] right_queue: container for right IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI
|
||||||
|
* \param[in] target_width: the rectangle width in mm on the target
|
||||||
|
* \param[in] target_height: the rectangle height in mm on the target
|
||||||
|
* \param[in] adjust_both_sides: 1 for adjusting both left and right camera calibration tables, and 0 for adjusting right camera calibraion table only
|
||||||
|
* \param[out] ratio: the corrected ratio from the calibration
|
||||||
|
* \param[out] angle: the target's tilt angle
|
||||||
|
* \param[in] callback: Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] client_data: Optional client data for the callback
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_focal_length_calibration(rs2_device* device, rs2_frame_queue* left_queue, rs2_frame_queue* right_queue, float target_width, float target_height, int adjust_both_sides,
|
||||||
|
float* ratio, float* angle, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Depth-RGB UV-Map calibration. Applicable for D400 cameras
|
||||||
|
* \param[in] device: device to calibrate
|
||||||
|
* \param[in] left_queue: the frame queue for left IR frames with resoluton of 1280x720 and the target captured in the center of 320x240 pixels ROI.
|
||||||
|
* \param[in] color_queue: the frame queue for RGB frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI
|
||||||
|
* \param[in] depth_queue: the frame queue for Depth frames with resoluton of 1280x720
|
||||||
|
* \param[in] py_px_only: 1 for calibrating color camera py and px only, 1 for calibrating color camera py, px, fy, and fx.
|
||||||
|
* \param[out] health: The four health check numbers in order of px, py, fx, fy for the calibration
|
||||||
|
* \param[in] health_size: number of health check numbers, which is 4 by default
|
||||||
|
* \param[in] callback: Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_uv_map_calibration_cpp(rs2_device* device, rs2_frame_queue* left_queue, rs2_frame_queue* color_queue, rs2_frame_queue* depth_queue, int py_px_only,
|
||||||
|
float * health, int health_size, rs2_update_progress_callback * progress_callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Depth-RGB UV-Map calibration. Applicable for D400 cameras
|
||||||
|
* \param[in] device: device to calibrate
|
||||||
|
* \param[in] left_queue: the frame queue for left IR frames with resoluton of 1280x720 and the target captured in the center of 320x240 pixels ROI.
|
||||||
|
* \param[in] color_queue: the frame queue for RGB frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI
|
||||||
|
* \param[in] depth_queue: the frame queue for Depth frames with resoluton of 1280x720
|
||||||
|
* \param[in] py_px_only: 1 for calibrating color camera py and px only, 1 for calibrating color camera py, px, fy, and fx.
|
||||||
|
* \param[out] health: The four health check numbers in order of px, py, fx, fy for the calibration
|
||||||
|
* \param[in] health_size: number of health check numbers, which is 4 by default
|
||||||
|
* \param[in] callback: Optional callback for update progress notifications, the progress value is normailzed to 1
|
||||||
|
* \param[in] client_data: Optional client data for the callback
|
||||||
|
* \return New calibration table
|
||||||
|
*/
|
||||||
|
const rs2_raw_data_buffer* rs2_run_uv_map_calibration(rs2_device* device, rs2_frame_queue* left_queue, rs2_frame_queue* color_queue, rs2_frame_queue* depth_queue,
|
||||||
|
int py_px_only, float* health, int health_size, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Calculate Z for calibration target - distance to the target's plane
|
||||||
|
* \param[in] queue1-3: A frame queue of raw images used to calculate and extract the distance to a predefined target pattern.
|
||||||
|
* For D400 the indexes 1-3 correspond to Left IR, Right IR and Depth with only the Left IR being used
|
||||||
|
* \param[in] target_width: Expected target's horizontal dimension in mm
|
||||||
|
* \param[in] target_height: Expected target's vertical dimension in mm
|
||||||
|
* \param[in] callback: Optional callback for reporting progress status
|
||||||
|
* \return Calculated distance (Z) to target in millimeter, or negative number if failed
|
||||||
|
*/
|
||||||
|
float rs2_calculate_target_z_cpp(rs2_device* device, rs2_frame_queue* queue1, rs2_frame_queue* queue2, rs2_frame_queue* queue3,
|
||||||
|
float target_width, float target_height,
|
||||||
|
rs2_update_progress_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Calculate Z for calibration target - distance to the target's plane
|
||||||
|
* \param[in] queue1-3: A frame queue of raw images used to calculate and extract the distance to a predefined target pattern.
|
||||||
|
* For D400 the indexes 1-3 correspond to Left IR, Right IR and Depth with only the Left IR being used
|
||||||
|
* \param[in] target_width: Expected target's horizontal dimension in mm
|
||||||
|
* \param[in] target_height: Expected target's vertical dimension in mm
|
||||||
|
* \param[in] callback: Optional callback for reporting progress status
|
||||||
|
* \param[in] client_data: Optional client data for the callback
|
||||||
|
* \return Calculated distance (Z) to target in millimeter, or negative number if failed
|
||||||
|
*/
|
||||||
|
float rs2_calculate_target_z(rs2_device* device, rs2_frame_queue* queue1, rs2_frame_queue* queue2, rs2_frame_queue* queue3,
|
||||||
|
float target_width, float target_height, rs2_update_progress_callback_ptr progress_callback, void* client_data, rs2_error** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,367 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_frame.h
|
||||||
|
* \brief
|
||||||
|
* Exposes RealSense frame functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_FRAME_H
|
||||||
|
#define LIBREALSENSE_RS2_FRAME_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
#include "rs_types.h"
|
||||||
|
|
||||||
|
/** \brief Specifies the clock in relation to which the frame timestamp was measured. */
|
||||||
|
typedef enum rs2_timestamp_domain
|
||||||
|
{
|
||||||
|
RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, /**< Frame timestamp was measured in relation to the camera clock */
|
||||||
|
RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME, /**< Frame timestamp was measured in relation to the OS system clock */
|
||||||
|
RS2_TIMESTAMP_DOMAIN_GLOBAL_TIME, /**< Frame timestamp was measured in relation to the camera clock and converted to OS system clock by constantly measure the difference*/
|
||||||
|
RS2_TIMESTAMP_DOMAIN_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_timestamp_domain;
|
||||||
|
const char* rs2_timestamp_domain_to_string(rs2_timestamp_domain info);
|
||||||
|
|
||||||
|
/** \brief Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame. */
|
||||||
|
typedef enum rs2_frame_metadata_value
|
||||||
|
{
|
||||||
|
RS2_FRAME_METADATA_FRAME_COUNTER , /**< A sequential index managed per-stream. Integer value*/
|
||||||
|
RS2_FRAME_METADATA_FRAME_TIMESTAMP , /**< Timestamp set by device clock when data readout and transmit commence. usec*/
|
||||||
|
RS2_FRAME_METADATA_SENSOR_TIMESTAMP , /**< Timestamp of the middle of sensor's exposure calculated by device. usec*/
|
||||||
|
RS2_FRAME_METADATA_ACTUAL_EXPOSURE , /**< Sensor's exposure width. When Auto Exposure (AE) is on the value is controlled by firmware. usec*/
|
||||||
|
RS2_FRAME_METADATA_GAIN_LEVEL , /**< A relative value increasing which will increase the Sensor's gain factor. \
|
||||||
|
When AE is set On, the value is controlled by firmware. Integer value*/
|
||||||
|
RS2_FRAME_METADATA_AUTO_EXPOSURE , /**< Auto Exposure Mode indicator. Zero corresponds to AE switched off. */
|
||||||
|
RS2_FRAME_METADATA_WHITE_BALANCE , /**< White Balance setting as a color temperature. Kelvin degrees*/
|
||||||
|
RS2_FRAME_METADATA_TIME_OF_ARRIVAL , /**< Time of arrival in system clock */
|
||||||
|
RS2_FRAME_METADATA_TEMPERATURE , /**< Temperature of the device, measured at the time of the frame capture. Celsius degrees */
|
||||||
|
RS2_FRAME_METADATA_BACKEND_TIMESTAMP , /**< Timestamp get from uvc driver. usec*/
|
||||||
|
RS2_FRAME_METADATA_ACTUAL_FPS , /**< Actual fps */
|
||||||
|
RS2_FRAME_METADATA_FRAME_LASER_POWER , /**< Laser power value 0-360. */
|
||||||
|
RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE , /**< Laser power mode. Zero corresponds to Laser power switched off and one for switched on. deprecated, replaced by RS2_FRAME_METADATA_FRAME_EMITTER_MODE*/
|
||||||
|
RS2_FRAME_METADATA_EXPOSURE_PRIORITY , /**< Exposure priority. */
|
||||||
|
RS2_FRAME_METADATA_EXPOSURE_ROI_LEFT , /**< Left region of interest for the auto exposure Algorithm. */
|
||||||
|
RS2_FRAME_METADATA_EXPOSURE_ROI_RIGHT , /**< Right region of interest for the auto exposure Algorithm. */
|
||||||
|
RS2_FRAME_METADATA_EXPOSURE_ROI_TOP , /**< Top region of interest for the auto exposure Algorithm. */
|
||||||
|
RS2_FRAME_METADATA_EXPOSURE_ROI_BOTTOM , /**< Bottom region of interest for the auto exposure Algorithm. */
|
||||||
|
RS2_FRAME_METADATA_BRIGHTNESS , /**< Color image brightness. */
|
||||||
|
RS2_FRAME_METADATA_CONTRAST , /**< Color image contrast. */
|
||||||
|
RS2_FRAME_METADATA_SATURATION , /**< Color image saturation. */
|
||||||
|
RS2_FRAME_METADATA_SHARPNESS , /**< Color image sharpness. */
|
||||||
|
RS2_FRAME_METADATA_AUTO_WHITE_BALANCE_TEMPERATURE , /**< Auto white balance temperature Mode indicator. Zero corresponds to automatic mode switched off. */
|
||||||
|
RS2_FRAME_METADATA_BACKLIGHT_COMPENSATION , /**< Color backlight compensation. Zero corresponds to switched off. */
|
||||||
|
RS2_FRAME_METADATA_HUE , /**< Color image hue. */
|
||||||
|
RS2_FRAME_METADATA_GAMMA , /**< Color image gamma. */
|
||||||
|
RS2_FRAME_METADATA_MANUAL_WHITE_BALANCE , /**< Color image white balance. */
|
||||||
|
RS2_FRAME_METADATA_POWER_LINE_FREQUENCY , /**< Power Line Frequency for anti-flickering Off/50Hz/60Hz/Auto. */
|
||||||
|
RS2_FRAME_METADATA_LOW_LIGHT_COMPENSATION , /**< Color lowlight compensation. Zero corresponds to switched off. */
|
||||||
|
RS2_FRAME_METADATA_FRAME_EMITTER_MODE , /**< Emitter mode: 0 - all emitters disabled. 1 - laser enabled. 2 - auto laser enabled (opt). 3 - LED enabled (opt).*/
|
||||||
|
RS2_FRAME_METADATA_FRAME_LED_POWER , /**< Led power value 0-360. */
|
||||||
|
RS2_FRAME_METADATA_RAW_FRAME_SIZE , /**< The number of transmitted payload bytes, not including metadata */
|
||||||
|
RS2_FRAME_METADATA_GPIO_INPUT_DATA , /**< GPIO input data */
|
||||||
|
RS2_FRAME_METADATA_SEQUENCE_NAME , /**< sub-preset id */
|
||||||
|
RS2_FRAME_METADATA_SEQUENCE_ID , /**< sub-preset sequence id */
|
||||||
|
RS2_FRAME_METADATA_SEQUENCE_SIZE , /**< sub-preset sequence size */
|
||||||
|
RS2_FRAME_METADATA_COUNT
|
||||||
|
} rs2_frame_metadata_value;
|
||||||
|
const char* rs2_frame_metadata_to_string(rs2_frame_metadata_value metadata);
|
||||||
|
const char* rs2_frame_metadata_value_to_string(rs2_frame_metadata_value metadata);
|
||||||
|
|
||||||
|
/** \brief Calibration target type. */
|
||||||
|
typedef enum rs2_calib_target_type
|
||||||
|
{
|
||||||
|
RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES, /**< Flat rectangle with vertices as the centers of Gaussian dots */
|
||||||
|
RS2_CALIB_TARGET_ROI_RECT_GAUSSIAN_DOT_VERTICES, /**< Flat rectangle with vertices as the centers of Gaussian dots with target inside the ROI */
|
||||||
|
RS2_CALIB_TARGET_POS_GAUSSIAN_DOT_VERTICES, /**< Positions of vertices as the centers of Gaussian dots with target inside the ROI */
|
||||||
|
RS2_CALIB_TARGET_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_calib_target_type;
|
||||||
|
const char* rs2_calib_target_type_to_string(rs2_calib_target_type type);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve metadata from frame handle
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[in] frame_metadata the rs2_frame_metadata whose latest frame we are interested in
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the metadata value
|
||||||
|
*/
|
||||||
|
rs2_metadata_type rs2_get_frame_metadata(const rs2_frame* frame, rs2_frame_metadata_value frame_metadata, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* determine device metadata
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[in] frame_metadata the metadata to check for support
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if device has this metadata
|
||||||
|
*/
|
||||||
|
int rs2_supports_frame_metadata(const rs2_frame* frame, rs2_frame_metadata_value frame_metadata, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve timestamp domain from frame handle. timestamps can only be comparable if they are in common domain
|
||||||
|
* (for example, depth timestamp might come from system time while color timestamp might come from the device)
|
||||||
|
* this method is used to check if two timestamp values are comparable (generated from the same clock)
|
||||||
|
* \param[in] frameset handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the timestamp domain of the frame (camera / microcontroller / system time)
|
||||||
|
*/
|
||||||
|
rs2_timestamp_domain rs2_get_frame_timestamp_domain(const rs2_frame* frameset, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve timestamp from frame handle in milliseconds
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the timestamp of the frame in milliseconds
|
||||||
|
*/
|
||||||
|
rs2_time_t rs2_get_frame_timestamp(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve frame parent sensor from frame handle
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the parent sensor of the frame
|
||||||
|
*/
|
||||||
|
rs2_sensor* rs2_get_frame_sensor(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve frame number from frame handle
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the frame nubmer of the frame, in milliseconds since the device was started
|
||||||
|
*/
|
||||||
|
unsigned long long rs2_get_frame_number(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve data size from frame handle
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the size of the frame data
|
||||||
|
*/
|
||||||
|
int rs2_get_frame_data_size(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve data from frame handle
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the pointer to the start of the frame data
|
||||||
|
*/
|
||||||
|
const void* rs2_get_frame_data(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve frame width in pixels
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return frame width in pixels
|
||||||
|
*/
|
||||||
|
int rs2_get_frame_width(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve frame height in pixels
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return frame height in pixels
|
||||||
|
*/
|
||||||
|
int rs2_get_frame_height(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve the scaling factor to use when converting a depth frame's get_data() units to meters
|
||||||
|
* \return float - depth, in meters, per 1 unit stored in the frame data
|
||||||
|
*/
|
||||||
|
float rs2_depth_frame_get_units( const rs2_frame* frame, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve frame stride in bytes (number of bytes from start of line N to start of line N+1)
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return stride in bytes
|
||||||
|
*/
|
||||||
|
int rs2_get_frame_stride_in_bytes(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve bits per pixels in the frame image
|
||||||
|
* (note that bits per pixel is not necessarily divided by 8, as in 12bpp)
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return bits per pixel
|
||||||
|
*/
|
||||||
|
int rs2_get_frame_bits_per_pixel(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* create additional reference to a frame without duplicating frame data
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return new frame reference, has to be released by rs2_release_frame
|
||||||
|
*/
|
||||||
|
void rs2_frame_add_ref(rs2_frame* frame, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* relases the frame handle
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
*/
|
||||||
|
void rs2_release_frame(rs2_frame* frame);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* communicate to the library you intend to keep the frame alive for a while
|
||||||
|
* this will remove the frame from the regular count of the frame pool
|
||||||
|
* once this function is called, the SDK can no longer guarantee 0-allocations during frame cycling
|
||||||
|
* \param[in] frame handle returned from a callback
|
||||||
|
*/
|
||||||
|
void rs2_keep_frame(rs2_frame* frame);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* When called on Points frame type, this method returns a pointer to an array of 3D vertices of the model
|
||||||
|
* The coordinate system is: X right, Y up, Z away from the camera. Units: Meters
|
||||||
|
* \param[in] frame Points frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Pointer to an array of vertices, lifetime is managed by the frame
|
||||||
|
*/
|
||||||
|
rs2_vertex* rs2_get_frame_vertices(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* When called on Points frame type, this method creates a ply file of the model with the given file name.
|
||||||
|
* \param[in] frame Points frame
|
||||||
|
* \param[in] fname The name for the ply file
|
||||||
|
* \param[in] texture Texture frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_export_to_ply(const rs2_frame* frame, const char* fname, rs2_frame* texture, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* When called on Points frame type, this method returns a pointer to an array of texture coordinates per vertex
|
||||||
|
* Each coordinate represent a (u,v) pair within [0,1] range, to be mapped to texture image
|
||||||
|
* \param[in] frame Points frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Pointer to an array of texture coordinates, lifetime is managed by the frame
|
||||||
|
*/
|
||||||
|
rs2_pixel* rs2_get_frame_texture_coordinates(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* When called on Points frame type, this method returns the number of vertices in the frame
|
||||||
|
* \param[in] frame Points frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Number of vertices
|
||||||
|
*/
|
||||||
|
int rs2_get_frame_points_count(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the stream profile that was used to start the stream of this frame
|
||||||
|
* \param[in] frame frame reference, owned by the user
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Pointer to the stream profile object, lifetime is managed elsewhere
|
||||||
|
*/
|
||||||
|
const rs2_stream_profile* rs2_get_frame_stream_profile(const rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Test if the given frame can be extended to the requested extension
|
||||||
|
* \param[in] frame Realsense frame
|
||||||
|
* \param[in] extension_type The extension to which the frame should be tested if it is extendable
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return non-zero value iff the frame can be extended to the given extension
|
||||||
|
*/
|
||||||
|
int rs2_is_frame_extendable_to(const rs2_frame* frame, rs2_extension extension_type, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Allocate new video frame using a frame-source provided form a processing block
|
||||||
|
* \param[in] source Frame pool to allocate the frame from
|
||||||
|
* \param[in] new_stream New stream profile to assign to newly created frame
|
||||||
|
* \param[in] original A reference frame that can be used to fill in auxilary information like format, width, height, bpp, stride (if applicable)
|
||||||
|
* \param[in] new_bpp New value for bits per pixel for the allocated frame
|
||||||
|
* \param[in] new_width New value for width for the allocated frame
|
||||||
|
* \param[in] new_height New value for height for the allocated frame
|
||||||
|
* \param[in] new_stride New value for stride in bytes for the allocated frame
|
||||||
|
* \param[in] frame_type New value for frame type for the allocated frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return reference to a newly allocated frame, must be released with release_frame
|
||||||
|
* memory for the frame is likely to be re-used from previous frame, but in lack of available frames in the pool will be allocated from the free store
|
||||||
|
*/
|
||||||
|
rs2_frame* rs2_allocate_synthetic_video_frame(rs2_source* source, const rs2_stream_profile* new_stream, rs2_frame* original,
|
||||||
|
int new_bpp, int new_width, int new_height, int new_stride, rs2_extension frame_type, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Allocate new motion frame using a frame-source provided form a processing block
|
||||||
|
* \param[in] source Frame pool to allocate the frame from
|
||||||
|
* \param[in] new_stream New stream profile to assign to newly created frame
|
||||||
|
* \param[in] original A reference frame that can be used to fill in auxilary information like format, width, height, bpp, stride (if applicable)
|
||||||
|
* \param[in] frame_type New value for frame type for the allocated frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return reference to a newly allocated frame, must be released with release_frame
|
||||||
|
* memory for the frame is likely to be re-used from previous frame, but in lack of available frames in the pool will be allocated from the free store
|
||||||
|
*/
|
||||||
|
rs2_frame* rs2_allocate_synthetic_motion_frame(rs2_source* source, const rs2_stream_profile* new_stream, rs2_frame* original,
|
||||||
|
rs2_extension frame_type, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Allocate new points frame using a frame-source provided from a processing block
|
||||||
|
* \param[in] source Frame pool to allocate the frame from
|
||||||
|
* \param[in] new_stream New stream profile to assign to newly created frame
|
||||||
|
* \param[in] original A reference frame that can be used to fill in auxilary information like format, width, height, bpp, stride (if applicable)
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return reference to a newly allocated frame, must be released with release_frame
|
||||||
|
* memory for the frame is likely to be re-used from previous frame, but in lack of available frames in the pool will be allocated from the free store
|
||||||
|
*/
|
||||||
|
rs2_frame* rs2_allocate_points(rs2_source* source, const rs2_stream_profile* new_stream, rs2_frame* original, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Allocate new composite frame, aggregating a set of existing frames
|
||||||
|
* \param[in] source Frame pool to allocate the frame from
|
||||||
|
* \param[in] frames Array of existing frames
|
||||||
|
* \param[in] count Number of input frames
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return reference to a newly allocated frame, must be released with release_frame
|
||||||
|
* when composite frame gets released it will automatically release all of the input frames
|
||||||
|
*/
|
||||||
|
rs2_frame* rs2_allocate_composite_frame(rs2_source* source, rs2_frame** frames, int count, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extract frame from within a composite frame
|
||||||
|
* \param[in] composite Composite frame
|
||||||
|
* \param[in] index Index of the frame to extract within the composite frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return returns reference to a frame existing within the composite frame
|
||||||
|
* If you wish to keep this frame after the composite is released, you need to call acquire_ref
|
||||||
|
* Otherwise the resulting frame lifetime is bound by owning composite frame
|
||||||
|
*/
|
||||||
|
rs2_frame* rs2_extract_frame(rs2_frame* composite, int index, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get number of frames embedded within a composite frame
|
||||||
|
* \param[in] composite Composite input frame
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Number of embedded frames
|
||||||
|
*/
|
||||||
|
int rs2_embedded_frames_count(rs2_frame* composite, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method will dispatch frame callback on a frame
|
||||||
|
* \param[in] source Frame pool provided by the processing block
|
||||||
|
* \param[in] frame Frame to dispatch, frame ownership is passed to this function, so you don't have to call release_frame after it
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_synthetic_frame_ready(rs2_source* source, rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* When called on Pose frame type, this method returns the transformation represented by the pose data
|
||||||
|
* \param[in] frame Pose frame
|
||||||
|
* \param[out] pose Pointer to a user allocated struct, which contains the pose info after a successful return
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_pose_frame_get_pose_data(const rs2_frame* frame, rs2_pose* pose, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extract the target dimensions on the specific target
|
||||||
|
* \param[in] frame Left or right camera frame of specified size based on the target type
|
||||||
|
* \param[in] calib_type Calibration target type
|
||||||
|
* \param[out] target_dims The array to hold the result target dimensions calculated.
|
||||||
|
For type RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES and RS2_CALIB_TARGET_ROI_RECT_GAUSSIAN_DOT_VERTICES, the four rectangle side sizes in pixels with the order of top, bottom, left, and right
|
||||||
|
For type RS2_CALIB_TARGET_POS_GAUSSIAN_DOT_VERTICES, the four vertices coordinates in pixels with the order of top, bottom, left, and right
|
||||||
|
* \param[in] target_dims_size Target dimension array size. 4 for RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES and 8 for RS2_CALIB_TARGET_POS_GAUSSIAN_DOT_VERTICES.
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_extract_target_dimensions(const rs2_frame* frame, rs2_calib_target_type calib_type, float * target_dims, unsigned int target_dims_size, rs2_error** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,567 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_internal.h
|
||||||
|
* \brief
|
||||||
|
* Exposes RealSense internal functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_INTERNAL_H
|
||||||
|
#define LIBREALSENSE_RS2_INTERNAL_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
#include "rs_types.h"
|
||||||
|
#include "rs_context.h"
|
||||||
|
#include "rs_sensor.h"
|
||||||
|
#include "rs_frame.h"
|
||||||
|
#include "rs_option.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Firmware size constants
|
||||||
|
*/
|
||||||
|
const int signed_fw_size = 0x18031C;
|
||||||
|
const int signed_sr300_size = 0x0C025C;
|
||||||
|
const int unsigned_fw_size = 0x200000;
|
||||||
|
const int unsigned_sr300_size = 0x100000;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* librealsense Recorder is intended for effective unit-testing
|
||||||
|
* Currently supports three modes of operation:
|
||||||
|
*/
|
||||||
|
typedef enum rs2_recording_mode
|
||||||
|
{
|
||||||
|
RS2_RECORDING_MODE_BLANK_FRAMES, /* frame metadata will be recorded, but pixel data will be replaced with zeros to save space */
|
||||||
|
RS2_RECORDING_MODE_COMPRESSED, /* frames will be encoded using a proprietary lossy encoding, aiming at x5 compression at some CPU expense */
|
||||||
|
RS2_RECORDING_MODE_BEST_QUALITY, /* frames will not be compressed, but rather stored as-is. This gives best quality and low CPU overhead, but you might run out of memory */
|
||||||
|
RS2_RECORDING_MODE_COUNT
|
||||||
|
} rs2_recording_mode;
|
||||||
|
|
||||||
|
/** \brief All the parameters required to define a video stream. */
|
||||||
|
typedef struct rs2_video_stream
|
||||||
|
{
|
||||||
|
rs2_stream type;
|
||||||
|
int index;
|
||||||
|
int uid;
|
||||||
|
int width;
|
||||||
|
int height;
|
||||||
|
int fps;
|
||||||
|
int bpp;
|
||||||
|
rs2_format fmt;
|
||||||
|
rs2_intrinsics intrinsics;
|
||||||
|
} rs2_video_stream;
|
||||||
|
|
||||||
|
/** \brief All the parameters required to define a motion stream. */
|
||||||
|
typedef struct rs2_motion_stream
|
||||||
|
{
|
||||||
|
rs2_stream type;
|
||||||
|
int index;
|
||||||
|
int uid;
|
||||||
|
int fps;
|
||||||
|
rs2_format fmt;
|
||||||
|
rs2_motion_device_intrinsic intrinsics;
|
||||||
|
} rs2_motion_stream;
|
||||||
|
|
||||||
|
/** \brief All the parameters required to define a pose stream. */
|
||||||
|
typedef struct rs2_pose_stream
|
||||||
|
{
|
||||||
|
rs2_stream type;
|
||||||
|
int index;
|
||||||
|
int uid;
|
||||||
|
int fps;
|
||||||
|
rs2_format fmt;
|
||||||
|
} rs2_pose_stream;
|
||||||
|
|
||||||
|
/** \brief All the parameters required to define a video frame. */
|
||||||
|
typedef struct rs2_software_video_frame
|
||||||
|
{
|
||||||
|
void* pixels;
|
||||||
|
void(*deleter)(void*);
|
||||||
|
int stride;
|
||||||
|
int bpp;
|
||||||
|
rs2_time_t timestamp;
|
||||||
|
rs2_timestamp_domain domain;
|
||||||
|
int frame_number;
|
||||||
|
const rs2_stream_profile* profile;
|
||||||
|
float depth_units;
|
||||||
|
} rs2_software_video_frame;
|
||||||
|
|
||||||
|
/** \brief All the parameters required to define a motion frame. */
|
||||||
|
typedef struct rs2_software_motion_frame
|
||||||
|
{
|
||||||
|
void* data;
|
||||||
|
void(*deleter)(void*);
|
||||||
|
rs2_time_t timestamp;
|
||||||
|
rs2_timestamp_domain domain;
|
||||||
|
int frame_number;
|
||||||
|
const rs2_stream_profile* profile;
|
||||||
|
} rs2_software_motion_frame;
|
||||||
|
|
||||||
|
/** \brief All the parameters required to define a pose frame. */
|
||||||
|
typedef struct rs2_software_pose_frame
|
||||||
|
{
|
||||||
|
struct pose_frame_info
|
||||||
|
{
|
||||||
|
float translation[3];
|
||||||
|
float velocity[3];
|
||||||
|
float acceleration[3];
|
||||||
|
float rotation[4];
|
||||||
|
float angular_velocity[3];
|
||||||
|
float angular_acceleration[3];
|
||||||
|
int tracker_confidence;
|
||||||
|
int mapper_confidence;
|
||||||
|
};
|
||||||
|
void* data;
|
||||||
|
void(*deleter)(void*);
|
||||||
|
rs2_time_t timestamp;
|
||||||
|
rs2_timestamp_domain domain;
|
||||||
|
int frame_number;
|
||||||
|
const rs2_stream_profile* profile;
|
||||||
|
} rs2_software_pose_frame;
|
||||||
|
|
||||||
|
/** \brief All the parameters required to define a sensor notification. */
|
||||||
|
typedef struct rs2_software_notification
|
||||||
|
{
|
||||||
|
rs2_notification_category category;
|
||||||
|
int type;
|
||||||
|
rs2_log_severity severity;
|
||||||
|
const char* description;
|
||||||
|
const char* serialized_data;
|
||||||
|
} rs2_software_notification;
|
||||||
|
|
||||||
|
struct rs2_software_device_destruction_callback;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create librealsense context that will try to record all operations over librealsense into a file
|
||||||
|
* \param[in] api_version realsense API version as provided by RS2_API_VERSION macro
|
||||||
|
* \param[in] filename string representing the name of the file to record
|
||||||
|
* \param[in] section string representing the name of the section within existing recording
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return context object, should be released by rs2_delete_context
|
||||||
|
*/
|
||||||
|
rs2_context* rs2_create_recording_context(int api_version, const char* filename, const char* section, rs2_recording_mode mode, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create librealsense context that given a file will respond to calls exactly as the recording did
|
||||||
|
* if the user calls a method that was either not called during recording or violates causality of the recording error will be thrown
|
||||||
|
* \param[in] api_version realsense API version as provided by RS2_API_VERSION macro
|
||||||
|
* \param[in] filename string representing the name of the file to play back from
|
||||||
|
* \param[in] section string representing the name of the section within existing recording
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return context object, should be released by rs2_delete_context
|
||||||
|
*/
|
||||||
|
rs2_context* rs2_create_mock_context(int api_version, const char* filename, const char* section, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create librealsense context that given a file will respond to calls exactly as the recording did
|
||||||
|
* if the user calls a method that was either not called during recording or violates causality of the recording error will be thrown
|
||||||
|
* \param[in] api_version realsense API version as provided by RS2_API_VERSION macro
|
||||||
|
* \param[in] filename string representing the name of the file to play back from
|
||||||
|
* \param[in] section string representing the name of the section within existing recording
|
||||||
|
* \param[in] min_api_version reject any file that was recorded before this version
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return context object, should be released by rs2_delete_context
|
||||||
|
*/
|
||||||
|
rs2_context* rs2_create_mock_context_versioned(int api_version, const char* filename, const char* section, const char* min_api_version, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create software device to enable use librealsense logic without getting data from backend
|
||||||
|
* but inject the data from outside
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return software device object, should be released by rs2_delete_device
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_create_software_device(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add sensor to the software device
|
||||||
|
* \param[in] dev the software device
|
||||||
|
* \param[in] sensor_name the name of the sensor
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return software sensor object, should be released by rs2_delete_sensor
|
||||||
|
*/
|
||||||
|
rs2_sensor* rs2_software_device_add_sensor(rs2_device* dev, const char* sensor_name, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Inject video frame to software sonsor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] frame all the frame components
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_on_video_frame(rs2_sensor* sensor, rs2_software_video_frame frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Inject motion frame to software sonsor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] frame all the frame components
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_on_motion_frame(rs2_sensor* sensor, rs2_software_motion_frame frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Inject pose frame to software sonsor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] frame all the frame components
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_on_pose_frame(rs2_sensor* sensor, rs2_software_pose_frame frame, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Inject notification to software sonsor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] notif all the notification components
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_on_notification(rs2_sensor* sensor, rs2_software_notification notif, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set frame metadata for the upcoming frames
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] value metadata key to set
|
||||||
|
* \param[in] type metadata value
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_set_metadata(rs2_sensor* sensor, rs2_frame_metadata_value value, rs2_metadata_type type, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* set callback to be notified when a specific software device is destroyed
|
||||||
|
* \param[in] dev software device
|
||||||
|
* \param[in] on_notification function pointer to register as callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_device_set_destruction_callback(const rs2_device* dev, rs2_software_device_destruction_callback_ptr on_notification, void* user, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* set callback to be notified when a specific software device is destroyed
|
||||||
|
* \param[in] dev software device
|
||||||
|
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant device lock
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_device_set_destruction_callback_cpp(const rs2_device* dev, rs2_software_device_destruction_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the wanted matcher type that will be used by the syncer
|
||||||
|
* \param[in] dev the software device
|
||||||
|
* \param[in] matcher matcher type
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_device_create_matcher(rs2_device* dev, rs2_matchers matcher, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Register a camera info value for the software device
|
||||||
|
* \param[in] dev the software device
|
||||||
|
* \param[in] info identifier for the camera info to add.
|
||||||
|
* \param[in] val string value for this new camera info.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_device_register_info(rs2_device* dev, rs2_camera_info info, const char *val, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update an existing camera info value for the software device
|
||||||
|
* \param[in] dev the software device
|
||||||
|
* \param[in] info identifier for the camera info to add.
|
||||||
|
* \param[in] val string value for this new camera info.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_device_update_info(rs2_device* dev, rs2_camera_info info, const char * val, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add video stream to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] video_stream all the stream components
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_software_sensor_add_video_stream(rs2_sensor* sensor, rs2_video_stream video_stream, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add video stream to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] video_stream all the stream components
|
||||||
|
* \param[in] is_default whether or not the stream should be a default stream for the device
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_software_sensor_add_video_stream_ex(rs2_sensor* sensor, rs2_video_stream video_stream, int is_default, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add motion stream to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] motion_stream all the stream components
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_software_sensor_add_motion_stream(rs2_sensor* sensor, rs2_motion_stream motion_stream, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add motion stream to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] motion_stream all the stream components
|
||||||
|
* \param[in] is_default whether or not the stream should be a default stream for the device
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_software_sensor_add_motion_stream_ex(rs2_sensor* sensor, rs2_motion_stream motion_stream, int is_default, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add pose stream to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] pose_stream all the stream components
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_software_sensor_add_pose_stream(rs2_sensor* sensor, rs2_pose_stream pose_stream, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add pose stream to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] pose_stream all the stream components
|
||||||
|
* \param[in] is_default whether or not the stream should be a default stream for the device
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_software_sensor_add_pose_stream_ex(rs2_sensor* sensor, rs2_pose_stream pose_stream, int is_default, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add read only option to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] option the wanted option
|
||||||
|
* \param[in] val the initial value
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_add_read_only_option(rs2_sensor* sensor, rs2_option option, float val, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update the read only option added to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] option the wanted option
|
||||||
|
* \param[in] val the wanted value
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_update_read_only_option(rs2_sensor* sensor, rs2_option option, float val, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add an option to sensor
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[in] option the wanted option
|
||||||
|
* \param[in] min the minimum value which will be accepted for this option
|
||||||
|
* \param[in] max the maximum value which will be accepted for this option
|
||||||
|
* \param[in] step the granularity of options which accept discrete values, or zero if the option accepts continuous values
|
||||||
|
* \param[in] def the initial value of the option
|
||||||
|
* \param[in] is_writable should the option be read-only or not
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_add_option(rs2_sensor* sensor, rs2_option option, float min, float max, float step, float def, int is_writable, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sensors hold the parent device in scope via a shared_ptr. This function detaches that so that the software sensor doesn't keep the software device alive.
|
||||||
|
* Note that this is dangerous as it opens the door to accessing freed memory if care isn't taken.
|
||||||
|
* \param[in] sensor the software sensor
|
||||||
|
* \param[out] error if non-null, recieves any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_software_sensor_detach(rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Creates RealSense firmware log message.
|
||||||
|
* \param[in] dev Device from which the FW log will be taken using the created message
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return pointer to created empty firmware log message
|
||||||
|
*/
|
||||||
|
rs2_firmware_log_message* rs2_create_fw_log_message(rs2_device* dev, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log.
|
||||||
|
* \param[in] dev Device from which the FW log should be taken
|
||||||
|
* \param[in] fw_log_msg Firmware log message object to be filled
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor
|
||||||
|
*/
|
||||||
|
int rs2_get_fw_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device
|
||||||
|
* \param[in] dev Device from which the FW log should be taken
|
||||||
|
* \param[in] fw_log_msg Firmware log message object to be filled
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor
|
||||||
|
*/
|
||||||
|
int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delete RealSense firmware log message
|
||||||
|
* \param[in] device Realsense firmware log message to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_fw_log_message(rs2_firmware_log_message* msg);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log message data.
|
||||||
|
* \param[in] msg firmware log message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return pointer to start of the firmware log message data
|
||||||
|
*/
|
||||||
|
const unsigned char* rs2_fw_log_message_data(rs2_firmware_log_message* msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log message size.
|
||||||
|
* \param[in] msg firmware log message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return size of the firmware log message data
|
||||||
|
*/
|
||||||
|
int rs2_fw_log_message_size(rs2_firmware_log_message* msg, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log message timestamp.
|
||||||
|
* \param[in] msg firmware log message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return timestamp of the firmware log message
|
||||||
|
*/
|
||||||
|
unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log message severity.
|
||||||
|
* \param[in] msg firmware log message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return severity of the firmware log message data
|
||||||
|
*/
|
||||||
|
rs2_log_severity rs2_fw_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Initializes RealSense firmware logs parser in device.
|
||||||
|
* \param[in] dev Device from which the FW log will be taken
|
||||||
|
* \param[in] xml_content content of the xml file needed for parsing
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails
|
||||||
|
*/
|
||||||
|
int rs2_init_fw_log_parser(rs2_device* dev, const char* xml_content, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Creates RealSense firmware log parsed message.
|
||||||
|
* \param[in] dev Device from which the FW log will be taken using the created message
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return pointer to created empty firmware log message
|
||||||
|
*/
|
||||||
|
rs2_firmware_log_parsed_message* rs2_create_fw_log_parsed_message(rs2_device* dev, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Deletes RealSense firmware log parsed message.
|
||||||
|
* \param[in] msg message to be deleted
|
||||||
|
*/
|
||||||
|
void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parser
|
||||||
|
* \param[in] dev Device from which the FW log will be taken
|
||||||
|
* \param[in] fw_log_msg firmware log message to be parsed
|
||||||
|
* \param[in] parsed_msg firmware log parsed message - place holder for the resulting parsed message
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return true for success, false for failure - failure happens if message could not be parsed
|
||||||
|
*/
|
||||||
|
int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_firmware_log_parsed_message* parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Returns number of fw logs already polled from device but not by user yet
|
||||||
|
* \param[in] dev Device from which the FW log will be taken
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return number of fw logs already polled from device but not by user yet
|
||||||
|
*/
|
||||||
|
unsigned int rs2_get_number_of_fw_logs(rs2_device* dev, rs2_error** error);
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parsed message.
|
||||||
|
* \param[in] fw_log_parsed_msg firmware log parsed message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return message of the firmware log parsed message
|
||||||
|
*/
|
||||||
|
const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parsed message file name.
|
||||||
|
* \param[in] fw_log_parsed_msg firmware log parsed message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return file name of the firmware log parsed message
|
||||||
|
*/
|
||||||
|
const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parsed message thread name.
|
||||||
|
* \param[in] fw_log_parsed_msg firmware log parsed message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return thread name of the firmware log parsed message
|
||||||
|
*/
|
||||||
|
const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parsed message severity.
|
||||||
|
* \param[in] fw_log_parsed_msg firmware log parsed message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return severity of the firmware log parsed message
|
||||||
|
*/
|
||||||
|
rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_log_parsed_file_name).
|
||||||
|
* \param[in] fw_log_parsed_msg firmware log parsed message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return line number of the firmware log parsed message
|
||||||
|
*/
|
||||||
|
unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parsed message timestamp
|
||||||
|
* \param[in] fw_log_parsed_msg firmware log parsed message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return timestamp of the firmware log parsed message
|
||||||
|
*/
|
||||||
|
unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Gets RealSense firmware log parsed message sequence id - cyclic number of FW log with [0..15] range
|
||||||
|
* \param[in] fw_log_parsed_msg firmware log parsed message object
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return sequence of the firmware log parsed message
|
||||||
|
*/
|
||||||
|
unsigned int rs2_get_fw_log_parsed_sequence_id(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Creates RealSense terminal parser.
|
||||||
|
* \param[in] xml_content content of the xml file needed for parsing
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return pointer to created terminal parser object
|
||||||
|
*/
|
||||||
|
rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Deletes RealSense terminal parser.
|
||||||
|
* \param[in] terminal_parser terminal parser to be deleted
|
||||||
|
*/
|
||||||
|
void rs2_delete_terminal_parser(rs2_terminal_parser* terminal_parser);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Parses terminal command via RealSense terminal parser
|
||||||
|
* \param[in] terminal_parser Terminal parser object
|
||||||
|
* \param[in] command command to be sent to the hw monitor of the device
|
||||||
|
* \param[in] size_of_command size of command to be sent to the hw monitor of the device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return command to hw monitor, in hex
|
||||||
|
*/
|
||||||
|
rs2_raw_data_buffer* rs2_terminal_parse_command(rs2_terminal_parser* terminal_parser,
|
||||||
|
const char* command, unsigned int size_of_command, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Parses terminal response via RealSense terminal parser
|
||||||
|
* \param[in] terminal_parser Terminal parser object
|
||||||
|
* \param[in] command command sent to the hw monitor of the device
|
||||||
|
* \param[in] size_of_command size of the command to sent to the hw monitor of the device
|
||||||
|
* \param[in] response response received by the hw monitor of the device
|
||||||
|
* \param[in] size_of_response size of the response received by the hw monitor of the device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored.
|
||||||
|
* \return answer parsed
|
||||||
|
*/
|
||||||
|
rs2_raw_data_buffer* rs2_terminal_parse_response(rs2_terminal_parser* terminal_parser,
|
||||||
|
const char* command, unsigned int size_of_command,
|
||||||
|
const void* response, unsigned int size_of_response, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,313 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_option.h
|
||||||
|
* \brief
|
||||||
|
* Exposes sensor options functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_OPTION_H
|
||||||
|
#define LIBREALSENSE_RS2_OPTION_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rs_types.h"
|
||||||
|
|
||||||
|
/** \brief Defines general configuration controls.
|
||||||
|
These can generally be mapped to camera UVC controls, and can be set / queried at any time unless stated otherwise.
|
||||||
|
*/
|
||||||
|
typedef enum rs2_option
|
||||||
|
{
|
||||||
|
RS2_OPTION_BACKLIGHT_COMPENSATION, /**< Enable / disable color backlight compensation*/
|
||||||
|
RS2_OPTION_BRIGHTNESS, /**< Color image brightness*/
|
||||||
|
RS2_OPTION_CONTRAST, /**< Color image contrast*/
|
||||||
|
RS2_OPTION_EXPOSURE, /**< Controls exposure time of color camera. Setting any value will disable auto exposure*/
|
||||||
|
RS2_OPTION_GAIN, /**< Color image gain*/
|
||||||
|
RS2_OPTION_GAMMA, /**< Color image gamma setting*/
|
||||||
|
RS2_OPTION_HUE, /**< Color image hue*/
|
||||||
|
RS2_OPTION_SATURATION, /**< Color image saturation setting*/
|
||||||
|
RS2_OPTION_SHARPNESS, /**< Color image sharpness setting*/
|
||||||
|
RS2_OPTION_WHITE_BALANCE, /**< Controls white balance of color image. Setting any value will disable auto white balance*/
|
||||||
|
RS2_OPTION_ENABLE_AUTO_EXPOSURE, /**< Enable / disable color image auto-exposure*/
|
||||||
|
RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE, /**< Enable / disable color image auto-white-balance*/
|
||||||
|
RS2_OPTION_VISUAL_PRESET, /**< Provide access to several recommend sets of option presets for the depth camera */
|
||||||
|
RS2_OPTION_LASER_POWER, /**< Power of the laser emitter, with 0 meaning projector off*/
|
||||||
|
RS2_OPTION_ACCURACY, /**< Set the number of patterns projected per frame. The higher the accuracy value the more patterns projected. Increasing the number of patterns help to achieve better accuracy. Note that this control is affecting the Depth FPS */
|
||||||
|
RS2_OPTION_MOTION_RANGE, /**< Motion vs. Range trade-off, with lower values allowing for better motion sensitivity and higher values allowing for better depth range*/
|
||||||
|
RS2_OPTION_FILTER_OPTION, /**< Set the filter to apply to each depth frame. Each one of the filter is optimized per the application requirements*/
|
||||||
|
RS2_OPTION_CONFIDENCE_THRESHOLD, /**< The confidence level threshold used by the Depth algorithm pipe to set whether a pixel will get a valid range or will be marked with invalid range*/
|
||||||
|
RS2_OPTION_EMITTER_ENABLED, /**< Emitter select: 0 – disable all emitters. 1 – enable laser. 2 – enable auto laser. 3 – enable LED.*/
|
||||||
|
RS2_OPTION_FRAMES_QUEUE_SIZE, /**< Number of frames the user is allowed to keep per stream. Trying to hold-on to more frames will cause frame-drops.*/
|
||||||
|
RS2_OPTION_TOTAL_FRAME_DROPS, /**< Total number of detected frame drops from all streams */
|
||||||
|
RS2_OPTION_AUTO_EXPOSURE_MODE, /**< Auto-Exposure modes: Static, Anti-Flicker and Hybrid */
|
||||||
|
RS2_OPTION_POWER_LINE_FREQUENCY, /**< Power Line Frequency control for anti-flickering Off/50Hz/60Hz/Auto */
|
||||||
|
RS2_OPTION_ASIC_TEMPERATURE, /**< Current Asic Temperature */
|
||||||
|
RS2_OPTION_ERROR_POLLING_ENABLED, /**< disable error handling */
|
||||||
|
RS2_OPTION_PROJECTOR_TEMPERATURE, /**< Current Projector Temperature */
|
||||||
|
RS2_OPTION_OUTPUT_TRIGGER_ENABLED, /**< Enable / disable trigger to be outputed from the camera to any external device on every depth frame */
|
||||||
|
RS2_OPTION_MOTION_MODULE_TEMPERATURE, /**< Current Motion-Module Temperature */
|
||||||
|
RS2_OPTION_DEPTH_UNITS, /**< Number of meters represented by a single depth unit */
|
||||||
|
RS2_OPTION_ENABLE_MOTION_CORRECTION, /**< Enable/Disable automatic correction of the motion data */
|
||||||
|
RS2_OPTION_AUTO_EXPOSURE_PRIORITY, /**< Allows sensor to dynamically ajust the frame rate depending on lighting conditions */
|
||||||
|
RS2_OPTION_COLOR_SCHEME, /**< Color scheme for data visualization */
|
||||||
|
RS2_OPTION_HISTOGRAM_EQUALIZATION_ENABLED, /**< Perform histogram equalization post-processing on the depth data */
|
||||||
|
RS2_OPTION_MIN_DISTANCE, /**< Minimal distance to the target */
|
||||||
|
RS2_OPTION_MAX_DISTANCE, /**< Maximum distance to the target */
|
||||||
|
RS2_OPTION_TEXTURE_SOURCE, /**< Texture mapping stream unique ID */
|
||||||
|
RS2_OPTION_FILTER_MAGNITUDE, /**< The 2D-filter effect. The specific interpretation is given within the context of the filter */
|
||||||
|
RS2_OPTION_FILTER_SMOOTH_ALPHA, /**< 2D-filter parameter controls the weight/radius for smoothing.*/
|
||||||
|
RS2_OPTION_FILTER_SMOOTH_DELTA, /**< 2D-filter range/validity threshold*/
|
||||||
|
RS2_OPTION_HOLES_FILL, /**< Enhance depth data post-processing with holes filling where appropriate*/
|
||||||
|
RS2_OPTION_STEREO_BASELINE, /**< The distance in mm between the first and the second imagers in stereo-based depth cameras*/
|
||||||
|
RS2_OPTION_AUTO_EXPOSURE_CONVERGE_STEP, /**< Allows dynamically ajust the converge step value of the target exposure in Auto-Exposure algorithm*/
|
||||||
|
RS2_OPTION_INTER_CAM_SYNC_MODE, /**< Impose Inter-camera HW synchronization mode. Applicable for D400/L500/Rolling Shutter SKUs */
|
||||||
|
RS2_OPTION_STREAM_FILTER, /**< Select a stream to process */
|
||||||
|
RS2_OPTION_STREAM_FORMAT_FILTER, /**< Select a stream format to process */
|
||||||
|
RS2_OPTION_STREAM_INDEX_FILTER, /**< Select a stream index to process */
|
||||||
|
RS2_OPTION_EMITTER_ON_OFF, /**< When supported, this option make the camera to switch the emitter state every frame. 0 for disabled, 1 for enabled */
|
||||||
|
RS2_OPTION_ZERO_ORDER_POINT_X, /**< Deprecated!!! - Zero order point x*/
|
||||||
|
RS2_OPTION_ZERO_ORDER_POINT_Y, /**< Deprecated!!! - Zero order point y*/
|
||||||
|
RS2_OPTION_LLD_TEMPERATURE, /**< LDD temperature*/
|
||||||
|
RS2_OPTION_MC_TEMPERATURE, /**< MC temperature*/
|
||||||
|
RS2_OPTION_MA_TEMPERATURE, /**< MA temperature*/
|
||||||
|
RS2_OPTION_HARDWARE_PRESET, /**< Hardware stream configuration */
|
||||||
|
RS2_OPTION_GLOBAL_TIME_ENABLED, /**< disable global time */
|
||||||
|
RS2_OPTION_APD_TEMPERATURE, /**< APD temperature*/
|
||||||
|
RS2_OPTION_ENABLE_MAPPING, /**< Enable an internal map */
|
||||||
|
RS2_OPTION_ENABLE_RELOCALIZATION, /**< Enable appearance based relocalization */
|
||||||
|
RS2_OPTION_ENABLE_POSE_JUMPING, /**< Enable position jumping */
|
||||||
|
RS2_OPTION_ENABLE_DYNAMIC_CALIBRATION, /**< Enable dynamic calibration */
|
||||||
|
RS2_OPTION_DEPTH_OFFSET, /**< Offset from sensor to depth origin in millimetrers*/
|
||||||
|
RS2_OPTION_LED_POWER, /**< Power of the LED (light emitting diode), with 0 meaning LED off*/
|
||||||
|
RS2_OPTION_ZERO_ORDER_ENABLED, /**< DEPRECATED! - Toggle Zero-Order mode */
|
||||||
|
RS2_OPTION_ENABLE_MAP_PRESERVATION, /**< Preserve previous map when starting */
|
||||||
|
RS2_OPTION_FREEFALL_DETECTION_ENABLED, /**< Enable/disable sensor shutdown when a free-fall is detected (on by default) */
|
||||||
|
RS2_OPTION_AVALANCHE_PHOTO_DIODE, /**< Changes the exposure time of Avalanche Photo Diode in the receiver */
|
||||||
|
RS2_OPTION_POST_PROCESSING_SHARPENING, /**< Changes the amount of sharpening in the post-processed image */
|
||||||
|
RS2_OPTION_PRE_PROCESSING_SHARPENING, /**< Changes the amount of sharpening in the pre-processed image */
|
||||||
|
RS2_OPTION_NOISE_FILTERING, /**< Control edges and background noise */
|
||||||
|
RS2_OPTION_INVALIDATION_BYPASS, /**< Enable\disable pixel invalidation */
|
||||||
|
RS2_OPTION_AMBIENT_LIGHT, /**< DEPRECATED! - Use RS2_OPTION_DIGITAL_GAIN instead. */
|
||||||
|
RS2_OPTION_DIGITAL_GAIN = RS2_OPTION_AMBIENT_LIGHT, /**< Change the depth digital gain see rs2_digital_gain for values */
|
||||||
|
RS2_OPTION_SENSOR_MODE, /**< The resolution mode: see rs2_sensor_mode for values */
|
||||||
|
RS2_OPTION_EMITTER_ALWAYS_ON, /**< Enable Laser On constantly (GS SKU Only) */
|
||||||
|
RS2_OPTION_THERMAL_COMPENSATION, /**< Depth Thermal Compensation for selected D400 SKUs */
|
||||||
|
RS2_OPTION_TRIGGER_CAMERA_ACCURACY_HEALTH, /**< DEPRECATED as of 2.46! */
|
||||||
|
RS2_OPTION_RESET_CAMERA_ACCURACY_HEALTH, /**< DEPRECATED as of 2.46! */
|
||||||
|
RS2_OPTION_HOST_PERFORMANCE, /**< Set host performance mode to optimize device settings so host can keep up with workload, for example, USB transaction granularity, setting option to low performance host leads to larger USB transaction size and reduced number of transactions which improves performance and stability if host is relatively weak as compared to workload */
|
||||||
|
RS2_OPTION_HDR_ENABLED, /**< Enable / disable HDR */
|
||||||
|
RS2_OPTION_SEQUENCE_NAME, /**< HDR Sequence name */
|
||||||
|
RS2_OPTION_SEQUENCE_SIZE, /**< HDR Sequence size */
|
||||||
|
RS2_OPTION_SEQUENCE_ID, /**< HDR Sequence ID - 0 is not HDR; sequence ID for HDR configuration starts from 1 */
|
||||||
|
RS2_OPTION_HUMIDITY_TEMPERATURE, /**< Humidity temperature [Deg Celsius]*/
|
||||||
|
RS2_OPTION_ENABLE_MAX_USABLE_RANGE, /**< Turn on/off the maximum usable depth sensor range given the amount of ambient light in the scene */
|
||||||
|
RS2_OPTION_ALTERNATE_IR, /**< Turn on/off the alternate IR, When enabling alternate IR, the IR image is holding the amplitude of the depth correlation. */
|
||||||
|
RS2_OPTION_NOISE_ESTIMATION, /**< Noise estimation - indicates the noise on the IR image */
|
||||||
|
RS2_OPTION_ENABLE_IR_REFLECTIVITY, /**< Enables data collection for calculating IR pixel reflectivity */
|
||||||
|
RS2_OPTION_AUTO_EXPOSURE_LIMIT, /**< Set and get auto exposure limit in microseconds. Default is 0 which means full exposure range. If the requested exposure limit is greater than frame time, it will be set to frame time at runtime. Setting will not take effect until next streaming session. */
|
||||||
|
RS2_OPTION_AUTO_GAIN_LIMIT, /**< Set and get auto gain limits ranging from 16 to 248. Default is 0 which means full gain. If the requested gain limit is less than 16, it will be set to 16. If the requested gain limit is greater than 248, it will be set to 248. Setting will not take effect until next streaming session. */
|
||||||
|
RS2_OPTION_AUTO_RX_SENSITIVITY, /**< Enable receiver sensitivity according to ambient light, bounded by the Receiver Gain control. */
|
||||||
|
RS2_OPTION_TRANSMITTER_FREQUENCY, /**<changes the transmitter frequencies increasing effective range over sharpness. */
|
||||||
|
RS2_OPTION_VERTICAL_BINNING, /**< Enables vertical binning which increases the maximal sensed distance. */
|
||||||
|
RS2_OPTION_RECEIVER_SENSITIVITY, /**< Control receiver sensitivity to incoming light, both projected and ambient (same as APD on L515). */
|
||||||
|
RS2_OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE, /**< Enable / disable color image auto-exposure*/
|
||||||
|
RS2_OPTION_AUTO_GAIN_LIMIT_TOGGLE, /**< Enable / disable color image auto-gain*/
|
||||||
|
RS2_OPTION_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_option;
|
||||||
|
|
||||||
|
// This function is being deprecated. For existing options it will return option name, but for future API additions the user should call rs2_get_option_name instead.
|
||||||
|
const char* rs2_option_to_string(rs2_option option);
|
||||||
|
|
||||||
|
/** \brief For SR300 devices: provides optimized settings (presets) for specific types of usage. */
|
||||||
|
typedef enum rs2_sr300_visual_preset
|
||||||
|
{
|
||||||
|
RS2_SR300_VISUAL_PRESET_SHORT_RANGE, /**< Preset for short range */
|
||||||
|
RS2_SR300_VISUAL_PRESET_LONG_RANGE, /**< Preset for long range */
|
||||||
|
RS2_SR300_VISUAL_PRESET_BACKGROUND_SEGMENTATION, /**< Preset for background segmentation */
|
||||||
|
RS2_SR300_VISUAL_PRESET_GESTURE_RECOGNITION, /**< Preset for gesture recognition */
|
||||||
|
RS2_SR300_VISUAL_PRESET_OBJECT_SCANNING, /**< Preset for object scanning */
|
||||||
|
RS2_SR300_VISUAL_PRESET_FACE_ANALYTICS, /**< Preset for face analytics */
|
||||||
|
RS2_SR300_VISUAL_PRESET_FACE_LOGIN, /**< Preset for face login */
|
||||||
|
RS2_SR300_VISUAL_PRESET_GR_CURSOR, /**< Preset for GR cursor */
|
||||||
|
RS2_SR300_VISUAL_PRESET_DEFAULT, /**< Camera default settings */
|
||||||
|
RS2_SR300_VISUAL_PRESET_MID_RANGE, /**< Preset for mid-range */
|
||||||
|
RS2_SR300_VISUAL_PRESET_IR_ONLY, /**< Preset for IR only */
|
||||||
|
RS2_SR300_VISUAL_PRESET_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_sr300_visual_preset;
|
||||||
|
const char* rs2_sr300_visual_preset_to_string(rs2_sr300_visual_preset preset);
|
||||||
|
|
||||||
|
/** \brief For RS400 devices: provides optimized settings (presets) for specific types of usage. */
|
||||||
|
typedef enum rs2_rs400_visual_preset
|
||||||
|
{
|
||||||
|
RS2_RS400_VISUAL_PRESET_CUSTOM,
|
||||||
|
RS2_RS400_VISUAL_PRESET_DEFAULT,
|
||||||
|
RS2_RS400_VISUAL_PRESET_HAND,
|
||||||
|
RS2_RS400_VISUAL_PRESET_HIGH_ACCURACY,
|
||||||
|
RS2_RS400_VISUAL_PRESET_HIGH_DENSITY,
|
||||||
|
RS2_RS400_VISUAL_PRESET_MEDIUM_DENSITY,
|
||||||
|
RS2_RS400_VISUAL_PRESET_REMOVE_IR_PATTERN,
|
||||||
|
RS2_RS400_VISUAL_PRESET_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_rs400_visual_preset;
|
||||||
|
const char* rs2_rs400_visual_preset_to_string(rs2_rs400_visual_preset preset);
|
||||||
|
|
||||||
|
/** \brief For L500 devices: provides optimized settings (presets) for specific types of usage. */
|
||||||
|
typedef enum rs2_l500_visual_preset
|
||||||
|
{
|
||||||
|
RS2_L500_VISUAL_PRESET_CUSTOM,
|
||||||
|
RS2_L500_VISUAL_PRESET_DEFAULT,
|
||||||
|
RS2_L500_VISUAL_PRESET_NO_AMBIENT,
|
||||||
|
RS2_L500_VISUAL_PRESET_LOW_AMBIENT,
|
||||||
|
RS2_L500_VISUAL_PRESET_MAX_RANGE,
|
||||||
|
RS2_L500_VISUAL_PRESET_SHORT_RANGE,
|
||||||
|
RS2_L500_VISUAL_PRESET_AUTOMATIC,
|
||||||
|
RS2_L500_VISUAL_PRESET_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_l500_visual_preset;
|
||||||
|
const char* rs2_l500_visual_preset_to_string(rs2_l500_visual_preset preset);
|
||||||
|
|
||||||
|
/** \brief For setting the camera_mode option */
|
||||||
|
typedef enum rs2_sensor_mode
|
||||||
|
{
|
||||||
|
RS2_SENSOR_MODE_VGA,
|
||||||
|
RS2_SENSOR_MODE_XGA,
|
||||||
|
RS2_SENSOR_MODE_QVGA,
|
||||||
|
RS2_SENSOR_MODE_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_sensor_mode;
|
||||||
|
const char* rs2_sensor_mode_to_string(rs2_sensor_mode preset);
|
||||||
|
|
||||||
|
/** \brief DEPRECATED! - Use RS2_OPTION_DIGITAL_GAIN instead. */
|
||||||
|
typedef enum rs2_ambient_light
|
||||||
|
{
|
||||||
|
RS2_AMBIENT_LIGHT_NO_AMBIENT = 1,
|
||||||
|
RS2_AMBIENT_LIGHT_LOW_AMBIENT = 2,
|
||||||
|
} rs2_ambient_light;
|
||||||
|
const char* rs2_ambient_light_to_string(rs2_ambient_light preset);
|
||||||
|
|
||||||
|
/** \brief digital gain for RS2_OPTION_DIGITAL_GAIN option. */
|
||||||
|
typedef enum rs2_digital_gain
|
||||||
|
{
|
||||||
|
RS2_DIGITAL_GAIN_AUTO = 0,
|
||||||
|
RS2_DIGITAL_GAIN_HIGH = 1,
|
||||||
|
RS2_DIGITAL_GAIN_LOW = 2,
|
||||||
|
} rs2_digital_gain;
|
||||||
|
const char* rs2_digital_gain_to_string(rs2_digital_gain preset);
|
||||||
|
|
||||||
|
/** \brief values for RS2_OPTION_HOST_PERFORMANCE option. */
|
||||||
|
typedef enum rs2_host_perf_mode
|
||||||
|
{
|
||||||
|
RS2_HOST_PERF_DEFAULT = 0, /**< no change in settings, use device defaults */
|
||||||
|
RS2_HOST_PERF_LOW = 1, /**< low performance host mode, if host cannot keep up with workload, this option may improve stability, for example, it sets larger USB transaction granularity, reduces number of transactions and improve performance and stability on relatively weak hosts as compared to the workload */
|
||||||
|
RS2_HOST_PERF_HIGH = 2, /**< high performance host mode, if host is strong as compared to the work and can handle workload without delay, this option sets smaller USB transactions granularity and as result larger number of transactions and workload on host, but reduces chance in device frame drops */
|
||||||
|
RS2_HOST_PERF_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_host_perf_mode;
|
||||||
|
const char* rs2_host_perf_mode_to_string( rs2_host_perf_mode perf );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if an option is read-only
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if option is read-only
|
||||||
|
*/
|
||||||
|
int rs2_is_option_read_only(const rs2_options* options, rs2_option option, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* read option value from the sensor
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[in] option option id to be queried
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return value of the option
|
||||||
|
*/
|
||||||
|
float rs2_get_option(const rs2_options* options, rs2_option option, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* write new value to sensor option
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[in] option option id to be queried
|
||||||
|
* \param[in] value new value for the option
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_option(const rs2_options* options, rs2_option option, float value, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get the list of supported options of options container
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_options_list* rs2_get_options_list(const rs2_options* options, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get the size of options list
|
||||||
|
* \param[in] options the option list
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
int rs2_get_options_list_size(const rs2_options_list* options, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get option name
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return human-readable option name
|
||||||
|
*/
|
||||||
|
const char* rs2_get_option_name(const rs2_options* options, rs2_option option, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get the specific option from options list
|
||||||
|
* \param[in] i the index of the option
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_option rs2_get_option_from_list(const rs2_options_list* options, int i, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Deletes options list
|
||||||
|
* \param[in] list list to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_options_list(rs2_options_list* list);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if particular option is supported by a subdevice
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if option is supported
|
||||||
|
*/
|
||||||
|
int rs2_supports_option(const rs2_options* options, rs2_option option, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve the available range of values of a supported option
|
||||||
|
* \param[in] sensor the RealSense device
|
||||||
|
* \param[in] option the option whose range should be queried
|
||||||
|
* \param[out] min the minimum value which will be accepted for this option
|
||||||
|
* \param[out] max the maximum value which will be accepted for this option
|
||||||
|
* \param[out] step the granularity of options which accept discrete values, or zero if the option accepts continuous values
|
||||||
|
* \param[out] def the default value of the option
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_option_range(const rs2_options* sensor, rs2_option option, float* min, float* max, float* step, float* def, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get option description
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return human-readable option description
|
||||||
|
*/
|
||||||
|
const char* rs2_get_option_description(const rs2_options* options, rs2_option option, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get option value description (in case specific option value hold special meaning)
|
||||||
|
* \param[in] options the options container
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \param[in] value value of the option
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return human-readable description of a specific value of an option or null if no special meaning
|
||||||
|
*/
|
||||||
|
const char* rs2_get_option_value_description(const rs2_options* options, rs2_option option, float value, rs2_error ** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,247 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_pipeline.h
|
||||||
|
* \brief
|
||||||
|
* Exposes RealSense processing-block functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_PIPELINE_H
|
||||||
|
#define LIBREALSENSE_RS2_PIPELINE_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rs_types.h"
|
||||||
|
#include "rs_sensor.h"
|
||||||
|
#include "rs_config.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create a pipeline instance
|
||||||
|
* The pipeline simplifies the user interaction with the device and computer vision processing modules.
|
||||||
|
* The class abstracts the camera configuration and streaming, and the vision modules triggering and threading.
|
||||||
|
* It lets the application focus on the computer vision output of the modules, or the device output data.
|
||||||
|
* The pipeline can manage computer vision modules, which are implemented as a processing blocks.
|
||||||
|
* The pipeline is the consumer of the processing block interface, while the application consumes the
|
||||||
|
* computer vision interface.
|
||||||
|
* \param[in] ctx context
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_pipeline* rs2_create_pipeline(rs2_context* ctx, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stop the pipeline streaming.
|
||||||
|
* The pipeline stops delivering samples to the attached computer vision modules and processing blocks, stops the device streaming
|
||||||
|
* and releases the device resources used by the pipeline. It is the application's responsibility to release any frame reference it owns.
|
||||||
|
* The method takes effect only after \c start() was called, otherwise an exception is raised.
|
||||||
|
* \param[in] pipe pipeline
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_pipeline_stop(rs2_pipeline* pipe, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Wait until a new set of frames becomes available.
|
||||||
|
* The frames set includes time-synchronized frames of each enabled stream in the pipeline.
|
||||||
|
* The method blocks the calling thread, and fetches the latest unread frames set.
|
||||||
|
* Device frames, which were produced while the function wasn't called, are dropped. To avoid frame drops, this method should be called
|
||||||
|
* as fast as the device frame rate.
|
||||||
|
* The application can maintain the frames handles to defer processing. However, if the application maintains too long history, the device
|
||||||
|
* may lack memory resources to produce new frames, and the following call to this method shall fail to retrieve new frames, until resources
|
||||||
|
* are retained.
|
||||||
|
* \param[in] pipe the pipeline
|
||||||
|
* \param[in] timeout_ms Max time in milliseconds to wait until an exception will be thrown
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Set of coherent frames
|
||||||
|
*/
|
||||||
|
rs2_frame* rs2_pipeline_wait_for_frames(rs2_pipeline* pipe, unsigned int timeout_ms, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if a new set of frames is available and retrieve the latest undelivered set.
|
||||||
|
* The frames set includes time-synchronized frames of each enabled stream in the pipeline.
|
||||||
|
* The method returns without blocking the calling thread, with status of new frames available or not. If available, it fetches the
|
||||||
|
* latest frames set.
|
||||||
|
* Device frames, which were produced while the function wasn't called, are dropped. To avoid frame drops, this method should be called
|
||||||
|
* as fast as the device frame rate.
|
||||||
|
* The application can maintain the frames handles to defer processing. However, if the application maintains too long history, the device
|
||||||
|
* may lack memory resources to produce new frames, and the following calls to this method shall return no new frames, until resources are
|
||||||
|
* retained.
|
||||||
|
* \param[in] pipe the pipeline
|
||||||
|
* \param[out] output_frame frame handle to be released using rs2_release_frame
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if new frame was stored to output_frame
|
||||||
|
*/
|
||||||
|
int rs2_pipeline_poll_for_frames(rs2_pipeline* pipe, rs2_frame** output_frame, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Wait until a new set of frames becomes available.
|
||||||
|
* The frames set includes time-synchronized frames of each enabled stream in the pipeline.
|
||||||
|
* The method blocks the calling thread, and fetches the latest unread frames set.
|
||||||
|
* Device frames, which were produced while the function wasn't called, are dropped. To avoid frame drops, this method should be called
|
||||||
|
* as fast as the device frame rate.
|
||||||
|
* The application can maintain the frames handles to defer processing. However, if the application maintains too long history, the device
|
||||||
|
* may lack memory resources to produce new frames, and the following call to this method shall fail to retrieve new frames, until resources
|
||||||
|
* are retained.
|
||||||
|
* \param[in] pipe the pipeline
|
||||||
|
* \param[in] timeout_ms max time in milliseconds to wait until a frame becomes available
|
||||||
|
* \param[out] output_frame frame handle to be released using rs2_release_frame
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if new frame was stored to output_frame
|
||||||
|
*/
|
||||||
|
int rs2_pipeline_try_wait_for_frames(rs2_pipeline* pipe, rs2_frame** output_frame, unsigned int timeout_ms, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delete a pipeline instance.
|
||||||
|
* Upon destruction, the pipeline will implicitly stop itself
|
||||||
|
* \param[in] pipe to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_pipeline(rs2_pipeline* pipe);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming with its default configuration.
|
||||||
|
* The pipeline streaming loop captures samples from the device, and delivers them to the attached computer vision modules
|
||||||
|
* and processing blocks, according to each module requirements and threading model.
|
||||||
|
* During the loop execution, the application can access the camera streams by calling \c wait_for_frames() or \c poll_for_frames().
|
||||||
|
* The streaming loop runs until the pipeline is stopped.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
*
|
||||||
|
* \param[in] pipe a pointer to an instance of the pipeline
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_pipeline_start(rs2_pipeline* pipe, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming according to the configuraion.
|
||||||
|
* The pipeline streaming loop captures samples from the device, and delivers them to the attached computer vision modules
|
||||||
|
* and processing blocks, according to each module requirements and threading model.
|
||||||
|
* During the loop execution, the application can access the camera streams by calling \c wait_for_frames() or \c poll_for_frames().
|
||||||
|
* The streaming loop runs until the pipeline is stopped.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* The pipeline selects and activates the device upon start, according to configuration or a default configuration.
|
||||||
|
* When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result. If the application
|
||||||
|
* requests are conflicting with pipeline computer vision modules or no matching device is available on the platform, the method fails.
|
||||||
|
* Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices are connected
|
||||||
|
* or disconnected, or another application acquires ownership of a device.
|
||||||
|
*
|
||||||
|
* \param[in] pipe a pointer to an instance of the pipeline
|
||||||
|
* \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_pipeline_start_with_config(rs2_pipeline* pipe, rs2_config* config, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming with its default configuration.
|
||||||
|
* The pipeline captures samples from the device, and delivers them to the through the provided frame callback.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception.
|
||||||
|
*
|
||||||
|
* \param[in] pipe A pointer to an instance of the pipeline
|
||||||
|
* \param[in] on_frame function pointer to register as per-frame callback
|
||||||
|
* \param[in] user auxiliary data the user wishes to receive together with every frame callback
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_pipeline_start_with_callback(rs2_pipeline* pipe, rs2_frame_callback_ptr on_frame, void* user, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming with its default configuration.
|
||||||
|
* The pipeline captures samples from the device, and delivers them to the through the provided frame callback.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception.
|
||||||
|
*
|
||||||
|
* \param[in] pipe A pointer to an instance of the pipeline
|
||||||
|
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_pipeline_start_with_callback_cpp(rs2_pipeline* pipe, rs2_frame_callback* callback, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming according to the configuraion.
|
||||||
|
* The pipeline captures samples from the device, and delivers them to the through the provided frame callback.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception.
|
||||||
|
* The pipeline selects and activates the device upon start, according to configuration or a default configuration.
|
||||||
|
* When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result. If the application
|
||||||
|
* requests are conflicting with pipeline computer vision modules or no matching device is available on the platform, the method fails.
|
||||||
|
* Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices are connected
|
||||||
|
* or disconnected, or another application acquires ownership of a device.
|
||||||
|
*
|
||||||
|
* \param[in] pipe A pointer to an instance of the pipeline
|
||||||
|
* \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied.
|
||||||
|
* \param[in] on_frame function pointer to register as per-frame callback
|
||||||
|
* \param[in] user auxiliary data the user wishes to receive together with every frame callback
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_pipeline_start_with_config_and_callback(rs2_pipeline* pipe, rs2_config* config, rs2_frame_callback_ptr on_frame, void* user, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming according to the configuraion.
|
||||||
|
* The pipeline captures samples from the device, and delivers them to the through the provided frame callback.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception.
|
||||||
|
* The pipeline selects and activates the device upon start, according to configuration or a default configuration.
|
||||||
|
* When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result. If the application
|
||||||
|
* requests are conflicting with pipeline computer vision modules or no matching device is available on the platform, the method fails.
|
||||||
|
* Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices are connected
|
||||||
|
* or disconnected, or another application acquires ownership of a device.
|
||||||
|
*
|
||||||
|
* \param[in] pipe A pointer to an instance of the pipeline
|
||||||
|
* \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied.
|
||||||
|
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_pipeline_start_with_config_and_callback_cpp(rs2_pipeline* pipe, rs2_config* config, rs2_frame_callback* callback, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return the active device and streams profiles, used by the pipeline.
|
||||||
|
* The pipeline streams profiles are selected during \c start(). The method returns a valid result only when the pipeline is active -
|
||||||
|
* between calls to \c start() and \c stop().
|
||||||
|
* After \c stop() is called, the pipeline doesn't own the device, thus, the pipeline selected device may change in subsequent activations.
|
||||||
|
*
|
||||||
|
* \param[in] pipe a pointer to an instance of the pipeline
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device on start.
|
||||||
|
*/
|
||||||
|
rs2_pipeline_profile* rs2_pipeline_get_active_profile(rs2_pipeline* pipe, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve the device used by the pipeline.
|
||||||
|
* The device class provides the application access to control camera additional settings -
|
||||||
|
* get device information, sensor options information, options value query and set, sensor specific extensions.
|
||||||
|
* Since the pipeline controls the device streams configuration, activation state and frames reading, calling
|
||||||
|
* the device API functions, which execute those operations, results in unexpected behavior.
|
||||||
|
* The pipeline streaming device is selected during pipeline \c start(). Devices of profiles, which are not returned by
|
||||||
|
* pipeline \c start() or \c get_active_profile(), are not guaranteed to be used by the pipeline.
|
||||||
|
*
|
||||||
|
* \param[in] profile A pointer to an instance of a pipeline profile
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return rs2_device* The pipeline selected device
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_pipeline_profile_get_device(rs2_pipeline_profile* profile, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return the selected streams profiles, which are enabled in this profile.
|
||||||
|
*
|
||||||
|
* \param[in] profile A pointer to an instance of a pipeline profile
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return list of stream profiles
|
||||||
|
*/
|
||||||
|
rs2_stream_profile_list* rs2_pipeline_profile_get_streams(rs2_pipeline_profile* profile, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Deletes an instance of a pipeline profile
|
||||||
|
*
|
||||||
|
* \param[in] profile A pointer to an instance of a pipeline profile
|
||||||
|
*/
|
||||||
|
void rs2_delete_pipeline_profile(rs2_pipeline_profile* profile);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,318 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_processing.h
|
||||||
|
* \brief
|
||||||
|
* Exposes RealSense processing-block functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_PROCESSING_H
|
||||||
|
#define LIBREALSENSE_RS2_PROCESSING_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rs_types.h"
|
||||||
|
#include "rs_sensor.h"
|
||||||
|
#include "rs_option.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Depth-Colorizer processing block that can be used to quickly visualize the depth data
|
||||||
|
* This block will accept depth frames as input and replace them by depth frames with format RGB8
|
||||||
|
* Non-depth frames are passed through
|
||||||
|
* Further customization will be added soon (format, color-map, histogram equalization control)
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_colorizer(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Sync processing block. This block accepts arbitrary frames and output composite frames of best matches
|
||||||
|
* Some frames may be released within the syncer if they are waiting for match for too long
|
||||||
|
* Syncronization is done (mostly) based on timestamps so good hardware timestamps are a pre-condition
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_sync_processing_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Point-Cloud processing block. This block accepts depth frames and outputs Points frames
|
||||||
|
* In addition, given non-depth frame, the block will align texture coordinate to the non-depth stream
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_pointcloud(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates YUY decoder processing block. This block accepts raw YUY frames and outputs frames of other formats.
|
||||||
|
* YUY is a common video format used by a variety of web-cams. It benefits from packing pixels into 2 bytes per pixel
|
||||||
|
* without signficant quality drop. YUY representation can be converted back to more usable RGB form,
|
||||||
|
* but this requires somewhat costly conversion.
|
||||||
|
* The SDK will automatically try to use SSE2 and AVX instructions and CUDA where available to get
|
||||||
|
* best performance. Other implementations (using GLSL, OpenCL, Neon and NCS) should follow.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_yuy_decoder(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates y411 decoder processing block. This block accepts raw y411 frames and outputs frames in RGB8.
|
||||||
|
* https://www.fourcc.org/pixel-format/yuv-y411/
|
||||||
|
* Y411 is disguised as NV12 to allow Linux compatibility. Both are 12bpp encodings that allow high-resolution
|
||||||
|
* modes in the camera to still fit within the USB3 limits (YUY wasn't enough).
|
||||||
|
*
|
||||||
|
* The SDK will automatically try to use SSE2 and AVX instructions and CUDA where available to get
|
||||||
|
* best performance. Other implementations (using GLSL, OpenCL, Neon and NCS) should follow.
|
||||||
|
*
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_y411_decoder(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates depth thresholding processing block
|
||||||
|
* By controlling min and max options on the block, one could filter out depth values
|
||||||
|
* that are either too large or too small, as a software post-processing step
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_threshold(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates depth units transformation processing block
|
||||||
|
* All of the pixels are transformed from depth units into meters.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_units_transform(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method creates new custom processing block. This lets the users pass frames between module boundaries for processing
|
||||||
|
* This is an infrastructure function aimed at middleware developers, and also used by provided blocks such as sync, colorizer, etc..
|
||||||
|
* \param proc Processing function to be applied to every frame entering the block
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return new processing block, to be released by rs2_delete_processing_block
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_processing_block(rs2_frame_processor_callback* proc, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method creates new custom processing block from function pointer. This lets the users pass frames between module boundaries for processing
|
||||||
|
* This is an infrastructure function aimed at middleware developers, and also used by provided blocks such as sync, colorizer, etc..
|
||||||
|
* \param proc Processing function pointer to be applied to every frame entering the block
|
||||||
|
* \param context User context (can be anything or null) to be passed later as ctx param of the callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return new processing block, to be released by rs2_delete_processing_block
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_processing_block_fptr(rs2_frame_processor_callback_ptr proc, void * context, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method adds a custom option to a custom processing block. This is a simple float that can be accessed via rs2_set_option and rs2_get_option
|
||||||
|
* This is an infrastructure function aimed at middleware developers, and also used by provided blocks such as save_to_ply, etc..
|
||||||
|
* \param[in] block Processing block
|
||||||
|
* \param[in] option_id an int ID for referencing the option
|
||||||
|
* \param[in] min the minimum value which will be accepted for this option
|
||||||
|
* \param[in] max the maximum value which will be accepted for this option
|
||||||
|
* \param[in] step the granularity of options which accept discrete values, or zero if the option accepts continuous values
|
||||||
|
* \param[in] def the default value of the option. This will be the initial value.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if adding the option succeeds. false if it fails e.g. an option with this id is already registered
|
||||||
|
*/
|
||||||
|
int rs2_processing_block_register_simple_option(rs2_processing_block* block, rs2_option option_id, float min, float max, float step, float def, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method is used to direct the output from the processing block to some callback or sink object
|
||||||
|
* \param[in] block Processing block
|
||||||
|
* \param[in] on_frame Callback to be invoked every time the processing block calls frame_ready
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_start_processing(rs2_processing_block* block, rs2_frame_callback* on_frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method is used to direct the output from the processing block to some callback or sink object
|
||||||
|
* \param[in] block Processing block
|
||||||
|
* \param[in] on_frame Callback function to be invoked every time the processing block calls frame_ready
|
||||||
|
* \param[in] user User context for the callback (can be anything or null)
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_start_processing_fptr(rs2_processing_block* block, rs2_frame_callback_ptr on_frame, void* user, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method is used to direct the output from the processing block to a dedicated queue object
|
||||||
|
* \param[in] block Processing block
|
||||||
|
* \param[in] queue Queue to place the processed frames to
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_start_processing_queue(rs2_processing_block* block, rs2_frame_queue* queue, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This method is used to pass frame into a processing block
|
||||||
|
* \param[in] block Processing block
|
||||||
|
* \param[in] frame Frame to process, ownership is moved to the block object
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_process_frame(rs2_processing_block* block, rs2_frame* frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Deletes the processing block
|
||||||
|
* \param[in] block Processing block
|
||||||
|
*/
|
||||||
|
void rs2_delete_processing_block(rs2_processing_block* block);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* create frame queue. frame queues are the simplest x-platform synchronization primitive provided by librealsense
|
||||||
|
* to help developers who are not using async APIs
|
||||||
|
* \param[in] capacity max number of frames to allow to be stored in the queue before older frames will start to get dropped
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return handle to the frame queue, must be released using rs2_delete_frame_queue
|
||||||
|
*/
|
||||||
|
rs2_frame_queue* rs2_create_frame_queue(int capacity, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* deletes frame queue and releases all frames inside it
|
||||||
|
* \param[in] queue queue to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_frame_queue(rs2_frame_queue* queue);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* queries the number of frames
|
||||||
|
* \param[in] queue to delete
|
||||||
|
* \returns the number of frames currently stored in queue
|
||||||
|
*/
|
||||||
|
int rs2_frame_queue_size(rs2_frame_queue* queue, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* wait until new frame becomes available in the queue and dequeue it
|
||||||
|
* \param[in] queue the frame queue data structure
|
||||||
|
* \param[in] timeout_ms max time in milliseconds to wait until an exception will be thrown
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return frame handle to be released using rs2_release_frame
|
||||||
|
*/
|
||||||
|
rs2_frame* rs2_wait_for_frame(rs2_frame_queue* queue, unsigned int timeout_ms, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* poll if a new frame is available and dequeue if it is
|
||||||
|
* \param[in] queue the frame queue data structure
|
||||||
|
* \param[out] output_frame frame handle to be released using rs2_release_frame
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if new frame was stored to output_frame
|
||||||
|
*/
|
||||||
|
int rs2_poll_for_frame(rs2_frame_queue* queue, rs2_frame** output_frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* wait until new frame becomes available in the queue and dequeue it
|
||||||
|
* \param[in] queue the frame queue data structure
|
||||||
|
* \param[in] timeout_ms max time in milliseconds to wait until a frame becomes available
|
||||||
|
* \param[out] output_frame frame handle to be released using rs2_release_frame
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if new frame was stored to output_frame
|
||||||
|
*/
|
||||||
|
int rs2_try_wait_for_frame(rs2_frame_queue* queue, unsigned int timeout_ms, rs2_frame** output_frame, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* enqueue new frame into a queue
|
||||||
|
* \param[in] frame frame handle to enqueue (this operation passed ownership to the queue)
|
||||||
|
* \param[in] queue the frame queue data structure
|
||||||
|
*/
|
||||||
|
void rs2_enqueue_frame(rs2_frame* frame, void* queue);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Align processing block.
|
||||||
|
* \param[in] align_to stream type to be used as the target of frameset alignment
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_align(rs2_stream align_to, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Depth post-processing filter block. This block accepts depth frames, applies decimation filter and plots modified prames
|
||||||
|
* Note that due to the modifiedframe size, the decimated frame repaces the original one
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_decimation_filter_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Depth post-processing filter block. This block accepts depth frames, applies temporal filter
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_temporal_filter_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Depth post-processing spatial filter block. This block accepts depth frames, applies spatial filters and plots modified prames
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_spatial_filter_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a post processing block that provides for depth<->disparity domain transformation for stereo-based depth modules
|
||||||
|
* \param[in] transform_to_disparity flag select the transform direction: true = depth->disparity, and vice versa
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_disparity_transform_block(unsigned char transform_to_disparity, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Depth post-processing hole filling block. The filter replaces empty pixels with data from adjacent pixels based on the method selected
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_hole_filling_filter_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a rates printer block. The printer prints the actual FPS of the invoked frame stream.
|
||||||
|
* The block ignores reapiting frames and calculats the FPS only if the frame number of the relevant frame was changed.
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_rates_printer_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Depth post-processing zero order fix block. The filter invalidates pixels that has a wrong value due to zero order effect
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return zero order fix processing block
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_zero_order_invalidation_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates Depth frame decompression module. Decoded frames compressed and transmitted with Z16H variable-lenght Huffman code to
|
||||||
|
* standartized Z16 Depth data format. Using the compression allows to reduce the Depth frames bandwidth by more than 50 percent
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Huffman-code decompression processing block
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_huffman_depth_decompress_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a hdr_merge processing block.
|
||||||
|
* The block merges between two depth frames with different exposure values
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_hdr_merge_processing_block(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a sequence_id_filter processing block.
|
||||||
|
* The block lets frames with the selected sequence id pass and blocks frames with other values
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_create_sequence_id_filter(rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve processing block specific information, like name.
|
||||||
|
* \param[in] block The processing block
|
||||||
|
* \param[in] info processing block info type to retrieve
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The requested processing block info string, in a format specific to the device model
|
||||||
|
*/
|
||||||
|
const char* rs2_get_processing_block_info(const rs2_processing_block* block, rs2_camera_info info, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if a processing block supports a specific info type.
|
||||||
|
* \param[in] block The processing block to check
|
||||||
|
* \param[in] info The parameter to check for support
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return True if the parameter both exist and well-defined for the specific device
|
||||||
|
*/
|
||||||
|
int rs2_supports_processing_block_info(const rs2_processing_block* block, rs2_camera_info info, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Test if the given processing block can be extended to the requested extension
|
||||||
|
* \param[in] block processing block
|
||||||
|
* \param[in] extension The extension to which the sensor should be tested if it is extendable
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return non-zero value iff the processing block can be extended to the given extension
|
||||||
|
*/
|
||||||
|
int rs2_is_processing_block_extendable_to(const rs2_processing_block* block, rs2_extension extension_type, rs2_error** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,192 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_record_playback.h
|
||||||
|
* \brief
|
||||||
|
* Exposes record and playback functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_RECORD_PLAYBACK_H
|
||||||
|
#define LIBREALSENSE_RS2_RECORD_PLAYBACK_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rs_types.h"
|
||||||
|
|
||||||
|
typedef enum rs2_playback_status
|
||||||
|
{
|
||||||
|
RS2_PLAYBACK_STATUS_UNKNOWN, /**< Unknown state */
|
||||||
|
RS2_PLAYBACK_STATUS_PLAYING, /**< One or more sensors were started, playback is reading and raising data */
|
||||||
|
RS2_PLAYBACK_STATUS_PAUSED, /**< One or more sensors were started, but playback paused reading and paused raising data*/
|
||||||
|
RS2_PLAYBACK_STATUS_STOPPED, /**< All sensors were stopped, or playback has ended (all data was read). This is the initial playback status*/
|
||||||
|
RS2_PLAYBACK_STATUS_COUNT
|
||||||
|
} rs2_playback_status;
|
||||||
|
|
||||||
|
const char* rs2_playback_status_to_string(rs2_playback_status status);
|
||||||
|
|
||||||
|
typedef void (*rs2_playback_status_changed_callback_ptr)(rs2_playback_status);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a recording device to record the given device and save it to the given file
|
||||||
|
* \param[in] device The device to record
|
||||||
|
* \param[in] file The desired path to which the recorder should save the data
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return A pointer to a device that records its data to file, or null in case of failure
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_create_record_device(const rs2_device* device, const char* file, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a recording device to record the given device and save it to the given file
|
||||||
|
* \param[in] device The device to record
|
||||||
|
* \param[in] file The desired path to which the recorder should save the data
|
||||||
|
* \param[in] compression_enabled Indicates if compression is enabled, 0 means false, otherwise true
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return A pointer to a device that records its data to file, or null in case of failure
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_create_record_device_ex(const rs2_device* device, const char* file, int compression_enabled, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Pause the recording device without stopping the actual device from streaming.
|
||||||
|
* Pausing will cause the device to stop writing new data to the file, in particular, frames and changes to extensions
|
||||||
|
* \param[in] device A recording device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_record_device_pause(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Unpause the recording device. Resume will cause the device to continue writing new data to the file, in particular, frames and changes to extensions
|
||||||
|
* \param[in] device A recording device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_record_device_resume(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the name of the file to which the recorder is writing
|
||||||
|
* \param[in] device A recording device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return The name of the file to which the recorder is writing
|
||||||
|
*/
|
||||||
|
const char* rs2_record_device_filename(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a playback device to play the content of the given file
|
||||||
|
* \param[in] file Path to the file to play
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return A pointer to a device that plays data from the file, or null in case of failure
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_create_playback_device(const char* file, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the path of the file used by the playback device
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Path to the file used by the playback device
|
||||||
|
*/
|
||||||
|
const char* rs2_playback_device_get_file_path(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the total duration of the file in units of nanoseconds
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Total duration of the file in units of nanoseconds
|
||||||
|
*/
|
||||||
|
unsigned long long int rs2_playback_get_duration(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the playback to a specified time point of the played data
|
||||||
|
* \param[in] device A playback device.
|
||||||
|
* \param[in] time The time point to which playback should seek, expressed in units of nanoseconds (zero value = start)
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_playback_seek(const rs2_device* device, long long int time, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the current position of the playback in the file in terms of time. Units are expressed in nanoseconds
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Current position of the playback in the file in terms of time. Units are expressed in nanoseconds
|
||||||
|
*/
|
||||||
|
unsigned long long int rs2_playback_get_position(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Pauses the playback
|
||||||
|
* Calling pause() in "Paused" status does nothing
|
||||||
|
* If pause() is called while playback status is "Playing" or "Stopped", the playback will not play until resume() is called
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_playback_device_resume(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Un-pauses the playback
|
||||||
|
* Calling resume() while playback status is "Playing" or "Stopped" does nothing
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_playback_device_pause(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the playback to work in real time or non real time
|
||||||
|
*
|
||||||
|
* In real time mode, playback will play the same way the file was recorded.
|
||||||
|
* In real time mode if the application takes too long to handle the callback, frames may be dropped.
|
||||||
|
* In non real time mode, playback will wait for each callback to finish handling the data before
|
||||||
|
* reading the next frame. In this mode no frames will be dropped, and the application controls the
|
||||||
|
* frame rate of the playback (according to the callback handler duration).
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[in] real_time Indicates if real time is requested, 0 means false, otherwise true
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_playback_device_set_real_time(const rs2_device* device, int real_time, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Indicates if playback is in real time mode or non real time
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return True iff playback is in real time mode. 0 means false, otherwise true
|
||||||
|
*/
|
||||||
|
int rs2_playback_device_is_real_time(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Register to receive callback from playback device upon its status changes
|
||||||
|
*
|
||||||
|
* Callbacks are invoked from the reading thread, any heavy processing in the callback handler will affect
|
||||||
|
* the reading thread and may cause frame drops\ high latency
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[in] callback A callback handler that will be invoked when the playback status changes
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_playback_device_set_status_changed_callback(const rs2_device* device, rs2_playback_status_changed_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the current state of the playback device
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Current state of the playback
|
||||||
|
*/
|
||||||
|
rs2_playback_status rs2_playback_device_get_current_status(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the playing speed
|
||||||
|
*
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[in] speed Indicates a multiplication of the speed to play (e.g: 1 = normal, 0.5 twice as slow)
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_playback_device_set_playback_speed(const rs2_device* device, float speed, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stops the playback
|
||||||
|
* Calling stop() will stop all streaming playbakc sensors and will reset the playback (returning to beginning of file)
|
||||||
|
* \param[in] device A playback device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_playback_device_stop(const rs2_device* device, rs2_error** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,670 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_sensor.h
|
||||||
|
* \brief
|
||||||
|
* Exposes RealSense sensor functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_SENSOR_H
|
||||||
|
#define LIBREALSENSE_RS2_SENSOR_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rs_types.h"
|
||||||
|
|
||||||
|
/** \brief Read-only strings that can be queried from the device.
|
||||||
|
Not all information attributes are available on all camera types.
|
||||||
|
This information is mainly available for camera debug and troubleshooting and should not be used in applications. */
|
||||||
|
typedef enum rs2_camera_info {
|
||||||
|
RS2_CAMERA_INFO_NAME , /**< Friendly name */
|
||||||
|
RS2_CAMERA_INFO_SERIAL_NUMBER , /**< Device serial number */
|
||||||
|
RS2_CAMERA_INFO_FIRMWARE_VERSION , /**< Primary firmware version */
|
||||||
|
RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION , /**< Recommended firmware version */
|
||||||
|
RS2_CAMERA_INFO_PHYSICAL_PORT , /**< Unique identifier of the port the device is connected to (platform specific) */
|
||||||
|
RS2_CAMERA_INFO_DEBUG_OP_CODE , /**< If device supports firmware logging, this is the command to send to get logs from firmware */
|
||||||
|
RS2_CAMERA_INFO_ADVANCED_MODE , /**< True iff the device is in advanced mode */
|
||||||
|
RS2_CAMERA_INFO_PRODUCT_ID , /**< Product ID as reported in the USB descriptor */
|
||||||
|
RS2_CAMERA_INFO_CAMERA_LOCKED , /**< True iff EEPROM is locked */
|
||||||
|
RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR , /**< Designated USB specification: USB2/USB3 */
|
||||||
|
RS2_CAMERA_INFO_PRODUCT_LINE , /**< Device product line D400/SR300/L500/T200 */
|
||||||
|
RS2_CAMERA_INFO_ASIC_SERIAL_NUMBER , /**< ASIC serial number */
|
||||||
|
RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID , /**< Firmware update ID */
|
||||||
|
RS2_CAMERA_INFO_IP_ADDRESS , /**< IP address for remote camera. */
|
||||||
|
RS2_CAMERA_INFO_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_camera_info;
|
||||||
|
const char* rs2_camera_info_to_string(rs2_camera_info info);
|
||||||
|
|
||||||
|
/** \brief Streams are different types of data provided by RealSense devices. */
|
||||||
|
typedef enum rs2_stream
|
||||||
|
{
|
||||||
|
RS2_STREAM_ANY,
|
||||||
|
RS2_STREAM_DEPTH , /**< Native stream of depth data produced by RealSense device */
|
||||||
|
RS2_STREAM_COLOR , /**< Native stream of color data captured by RealSense device */
|
||||||
|
RS2_STREAM_INFRARED , /**< Native stream of infrared data captured by RealSense device */
|
||||||
|
RS2_STREAM_FISHEYE , /**< Native stream of fish-eye (wide) data captured from the dedicate motion camera */
|
||||||
|
RS2_STREAM_GYRO , /**< Native stream of gyroscope motion data produced by RealSense device */
|
||||||
|
RS2_STREAM_ACCEL , /**< Native stream of accelerometer motion data produced by RealSense device */
|
||||||
|
RS2_STREAM_GPIO , /**< Signals from external device connected through GPIO */
|
||||||
|
RS2_STREAM_POSE , /**< 6 Degrees of Freedom pose data, calculated by RealSense device */
|
||||||
|
RS2_STREAM_CONFIDENCE , /**< 4 bit per-pixel depth confidence level */
|
||||||
|
RS2_STREAM_COUNT
|
||||||
|
} rs2_stream;
|
||||||
|
const char* rs2_stream_to_string(rs2_stream stream);
|
||||||
|
|
||||||
|
/** \brief A stream's format identifies how binary data is encoded within a frame. */
|
||||||
|
typedef enum rs2_format
|
||||||
|
{
|
||||||
|
RS2_FORMAT_ANY , /**< When passed to enable stream, librealsense will try to provide best suited format */
|
||||||
|
RS2_FORMAT_Z16 , /**< 16-bit linear depth values. The depth is meters is equal to depth scale * pixel value. */
|
||||||
|
RS2_FORMAT_DISPARITY16 , /**< 16-bit float-point disparity values. Depth->Disparity conversion : Disparity = Baseline*FocalLength/Depth. */
|
||||||
|
RS2_FORMAT_XYZ32F , /**< 32-bit floating point 3D coordinates. */
|
||||||
|
RS2_FORMAT_YUYV , /**< 32-bit y0, u, y1, v data for every two pixels. Similar to YUV422 but packed in a different order - https://en.wikipedia.org/wiki/YUV */
|
||||||
|
RS2_FORMAT_RGB8 , /**< 8-bit red, green and blue channels */
|
||||||
|
RS2_FORMAT_BGR8 , /**< 8-bit blue, green, and red channels -- suitable for OpenCV */
|
||||||
|
RS2_FORMAT_RGBA8 , /**< 8-bit red, green and blue channels + constant alpha channel equal to FF */
|
||||||
|
RS2_FORMAT_BGRA8 , /**< 8-bit blue, green, and red channels + constant alpha channel equal to FF */
|
||||||
|
RS2_FORMAT_Y8 , /**< 8-bit per-pixel grayscale image */
|
||||||
|
RS2_FORMAT_Y16 , /**< 16-bit per-pixel grayscale image */
|
||||||
|
RS2_FORMAT_RAW10 , /**< Four 10 bits per pixel luminance values packed into a 5-byte macropixel */
|
||||||
|
RS2_FORMAT_RAW16 , /**< 16-bit raw image */
|
||||||
|
RS2_FORMAT_RAW8 , /**< 8-bit raw image */
|
||||||
|
RS2_FORMAT_UYVY , /**< Similar to the standard YUYV pixel format, but packed in a different order */
|
||||||
|
RS2_FORMAT_MOTION_RAW , /**< Raw data from the motion sensor */
|
||||||
|
RS2_FORMAT_MOTION_XYZ32F , /**< Motion data packed as 3 32-bit float values, for X, Y, and Z axis */
|
||||||
|
RS2_FORMAT_GPIO_RAW , /**< Raw data from the external sensors hooked to one of the GPIO's */
|
||||||
|
RS2_FORMAT_6DOF , /**< Pose data packed as floats array, containing translation vector, rotation quaternion and prediction velocities and accelerations vectors */
|
||||||
|
RS2_FORMAT_DISPARITY32 , /**< 32-bit float-point disparity values. Depth->Disparity conversion : Disparity = Baseline*FocalLength/Depth */
|
||||||
|
RS2_FORMAT_Y10BPACK , /**< 16-bit per-pixel grayscale image unpacked from 10 bits per pixel packed ([8:8:8:8:2222]) grey-scale image. The data is unpacked to LSB and padded with 6 zero bits */
|
||||||
|
RS2_FORMAT_DISTANCE , /**< 32-bit float-point depth distance value. */
|
||||||
|
RS2_FORMAT_MJPEG , /**< Bitstream encoding for video in which an image of each frame is encoded as JPEG-DIB */
|
||||||
|
RS2_FORMAT_Y8I , /**< 8-bit per pixel interleaved. 8-bit left, 8-bit right. */
|
||||||
|
RS2_FORMAT_Y12I , /**< 12-bit per pixel interleaved. 12-bit left, 12-bit right. Each pixel is stored in a 24-bit word in little-endian order. */
|
||||||
|
RS2_FORMAT_INZI , /**< multi-planar Depth 16bit + IR 10bit. */
|
||||||
|
RS2_FORMAT_INVI , /**< 8-bit IR stream. */
|
||||||
|
RS2_FORMAT_W10 , /**< Grey-scale image as a bit-packed array. 4 pixel data stream taking 5 bytes */
|
||||||
|
RS2_FORMAT_Z16H , /**< Variable-length Huffman-compressed 16-bit depth values. */
|
||||||
|
RS2_FORMAT_FG , /**< 16-bit per-pixel frame grabber format. */
|
||||||
|
RS2_FORMAT_Y411 , /**< 12-bit per-pixel. */
|
||||||
|
RS2_FORMAT_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_format;
|
||||||
|
const char* rs2_format_to_string(rs2_format format);
|
||||||
|
|
||||||
|
/** \brief Cross-stream extrinsics: encodes the topology describing how the different devices are oriented. */
|
||||||
|
typedef struct rs2_extrinsics
|
||||||
|
{
|
||||||
|
float rotation[9]; /**< Column-major 3x3 rotation matrix */
|
||||||
|
float translation[3]; /**< Three-element translation vector, in meters */
|
||||||
|
} rs2_extrinsics;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Deletes sensors list, any sensors created from this list will remain unaffected
|
||||||
|
* \param[in] info_list list to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_sensor_list(rs2_sensor_list* info_list);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Determines number of sensors in a list
|
||||||
|
* \param[in] info_list The list of connected sensors captured using rs2_query_sensors
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Sensors count
|
||||||
|
*/
|
||||||
|
int rs2_get_sensors_count(const rs2_sensor_list* info_list, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* delete relasense sensor
|
||||||
|
* \param[in] sensor realsense sensor to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_sensor(rs2_sensor* sensor);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* create sensor by index
|
||||||
|
* \param[in] index the zero based index of sensor to retrieve
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the requested sensor, should be released by rs2_delete_sensor
|
||||||
|
*/
|
||||||
|
rs2_sensor* rs2_create_sensor(const rs2_sensor_list* list, int index, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This is a helper function allowing the user to discover the device from one of its sensors
|
||||||
|
* \param[in] sensor Pointer to a sensor
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return new device wrapper for the device of the sensor. Needs to be released by delete_device
|
||||||
|
*/
|
||||||
|
rs2_device* rs2_create_device_from_sensor(const rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve sensor specific information, like versions of various internal components
|
||||||
|
* \param[in] sensor the RealSense sensor
|
||||||
|
* \param[in] info camera info type to retrieve
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the requested camera info string, in a format specific to the device model
|
||||||
|
*/
|
||||||
|
const char* rs2_get_sensor_info(const rs2_sensor* sensor, rs2_camera_info info, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if specific sensor info is supported
|
||||||
|
* \param[in] info the parameter to check for support
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return true if the parameter both exist and well-defined for the specific device
|
||||||
|
*/
|
||||||
|
int rs2_supports_sensor_info(const rs2_sensor* sensor, rs2_camera_info info, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Test if the given sensor can be extended to the requested extension
|
||||||
|
* \param[in] sensor Realsense sensor
|
||||||
|
* \param[in] extension The extension to which the sensor should be tested if it is extendable
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return non-zero value iff the sensor can be extended to the given extension
|
||||||
|
*/
|
||||||
|
int rs2_is_sensor_extendable_to(const rs2_sensor* sensor, rs2_extension extension, rs2_error** error);
|
||||||
|
|
||||||
|
/** When called on a depth sensor, this method will return the number of meters represented by a single depth unit
|
||||||
|
* \param[in] sensor depth sensor
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the number of meters represented by a single depth unit
|
||||||
|
*/
|
||||||
|
float rs2_get_depth_scale(rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve the stereoscopic baseline value from frame. Applicable to stereo-based depth modules
|
||||||
|
* \param[out] float Stereoscopic baseline in millimeters
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
float rs2_depth_stereo_frame_get_baseline(const rs2_frame* frame_ref, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve the stereoscopic baseline value from sensor. Applicable to stereo-based depth modules
|
||||||
|
* \param[out] float Stereoscopic baseline in millimeters
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
float rs2_get_stereo_baseline(rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief sets the active region of interest to be used by auto-exposure algorithm
|
||||||
|
* \param[in] sensor the RealSense sensor
|
||||||
|
* \param[in] min_x lower horizontal bound in pixels
|
||||||
|
* \param[in] min_y lower vertical bound in pixels
|
||||||
|
* \param[in] max_x upper horizontal bound in pixels
|
||||||
|
* \param[in] max_y upper vertical bound in pixels
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_region_of_interest(const rs2_sensor* sensor, int min_x, int min_y, int max_x, int max_y, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief gets the active region of interest to be used by auto-exposure algorithm
|
||||||
|
* \param[in] sensor the RealSense sensor
|
||||||
|
* \param[out] min_x lower horizontal bound in pixels
|
||||||
|
* \param[out] min_y lower vertical bound in pixels
|
||||||
|
* \param[out] max_x upper horizontal bound in pixels
|
||||||
|
* \param[out] max_y upper vertical bound in pixels
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_region_of_interest(const rs2_sensor* sensor, int* min_x, int* min_y, int* max_x, int* max_y, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* open subdevice for exclusive access, by committing to a configuration
|
||||||
|
* \param[in] device relevant RealSense device
|
||||||
|
* \param[in] profile stream profile that defines single stream configuration
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_open(rs2_sensor* device, const rs2_stream_profile* profile, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* open subdevice for exclusive access, by committing to composite configuration, specifying one or more stream profiles
|
||||||
|
* this method should be used for interdependent streams, such as depth and infrared, that have to be configured together
|
||||||
|
* \param[in] device relevant RealSense device
|
||||||
|
* \param[in] profiles list of stream profiles discovered by get_stream_profiles
|
||||||
|
* \param[in] count number of simultaneous stream profiles to configure
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_open_multiple(rs2_sensor* device, const rs2_stream_profile** profiles, int count, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* stop any streaming from specified subdevice
|
||||||
|
* \param[in] sensor RealSense device
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_close(const rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* start streaming from specified configured sensor
|
||||||
|
* \param[in] sensor RealSense device
|
||||||
|
* \param[in] on_frame function pointer to register as per-frame callback
|
||||||
|
* \param[in] user auxiliary data the user wishes to receive together with every frame callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_start(const rs2_sensor* sensor, rs2_frame_callback_ptr on_frame, void* user, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* start streaming from specified configured sensor
|
||||||
|
* \param[in] sensor RealSense device
|
||||||
|
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_start_cpp(const rs2_sensor* sensor, rs2_frame_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* start streaming from specified configured sensor of specific stream to frame queue
|
||||||
|
* \param[in] sensor RealSense Sensor
|
||||||
|
* \param[in] queue frame-queue to store new frames into
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_start_queue(const rs2_sensor* sensor, rs2_frame_queue* queue, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* stops streaming from specified configured device
|
||||||
|
* \param[in] sensor RealSense sensor
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_stop(const rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* set callback to get notifications from specified sensor
|
||||||
|
* \param[in] sensor RealSense device
|
||||||
|
* \param[in] on_notification function pointer to register as per-notifications callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_notifications_callback(const rs2_sensor* sensor, rs2_notification_callback_ptr on_notification, void* user, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* set callback to get notifications from specified device
|
||||||
|
* \param[in] sensor RealSense sensor
|
||||||
|
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant subdevice lock
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_notifications_callback_cpp(const rs2_sensor* sensor, rs2_notifications_callback* callback, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve description from notification handle
|
||||||
|
* \param[in] notification handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the notification description
|
||||||
|
*/
|
||||||
|
const char* rs2_get_notification_description(rs2_notification* notification, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve timestamp from notification handle
|
||||||
|
* \param[in] notification handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the notification timestamp
|
||||||
|
*/
|
||||||
|
rs2_time_t rs2_get_notification_timestamp(rs2_notification* notification, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve severity from notification handle
|
||||||
|
* \param[in] notification handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the notification severity
|
||||||
|
*/
|
||||||
|
rs2_log_severity rs2_get_notification_severity(rs2_notification* notification, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve category from notification handle
|
||||||
|
* \param[in] notification handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the notification category
|
||||||
|
*/
|
||||||
|
rs2_notification_category rs2_get_notification_category(rs2_notification* notification, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve serialized data from notification handle
|
||||||
|
* \param[in] notification handle returned from a callback
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the serialized data (in JSON format)
|
||||||
|
*/
|
||||||
|
const char* rs2_get_notification_serialized_data(rs2_notification* notification, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if physical subdevice is supported
|
||||||
|
* \param[in] sensor input RealSense subdevice
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return list of stream profiles that given subdevice can provide, should be released by rs2_delete_profiles_list
|
||||||
|
*/
|
||||||
|
rs2_stream_profile_list* rs2_get_stream_profiles(rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve list of debug stream profiles that given subdevice can provide
|
||||||
|
* \param[in] sensor input RealSense subdevice
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return list of debug stream profiles that given subdevice can provide, should be released by rs2_delete_profiles_list
|
||||||
|
*/
|
||||||
|
rs2_stream_profile_list * rs2_get_debug_stream_profiles( rs2_sensor * sensor, rs2_error ** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check how subdevice is streaming
|
||||||
|
* \param[in] sensor input RealSense subdevice
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return list of stream profiles that given subdevice is currently streaming, should be released by rs2_delete_profiles_list
|
||||||
|
*/
|
||||||
|
rs2_stream_profile_list* rs2_get_active_streams(rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get pointer to specific stream profile
|
||||||
|
* \param[in] list the list of supported profiles returned by rs2_get_supported_profiles
|
||||||
|
* \param[in] index the zero based index of the streaming mode
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
const rs2_stream_profile* rs2_get_stream_profile(const rs2_stream_profile_list* list, int index, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extract common parameters of a stream profiles
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[out] stream stream type of the input profile
|
||||||
|
* \param[out] format binary data format of the input profile
|
||||||
|
* \param[out] index stream index the input profile in case there are multiple streams of the same type
|
||||||
|
* \param[out] unique_id identifier for the stream profile, unique within the application
|
||||||
|
* \param[out] framerate expected rate for data frames to arrive, meaning expected number of frames per second
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_stream_profile_data(const rs2_stream_profile* mode, rs2_stream* stream, rs2_format* format, int* index, int* unique_id, int* framerate, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Override some of the parameters of the stream profile
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[in] stream stream type for the profile
|
||||||
|
* \param[in] format binary data format of the profile
|
||||||
|
* \param[in] index stream index the profile in case there are multiple streams of the same type
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_stream_profile_data(rs2_stream_profile* mode, rs2_stream stream, int index, rs2_format format, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a copy of stream profile, assigning new values to some of the fields
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[in] stream stream type for the profile
|
||||||
|
* \param[in] format binary data format of the profile
|
||||||
|
* \param[in] index stream index the profile in case there are multiple streams of the same type
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return new stream profile, must be deleted by rs2_delete_stream_profile
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_clone_stream_profile(const rs2_stream_profile* mode, rs2_stream stream, int index, rs2_format format, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a copy of stream profile, assigning new values to some of the fields
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[in] stream stream type for the profile
|
||||||
|
* \param[in] format binary data format of the profile
|
||||||
|
* \param[in] width new width for the profile
|
||||||
|
* \param[in] height new height for the profile
|
||||||
|
* \param[in] intr new intrinsics for the profile
|
||||||
|
* \param[in] index stream index the profile in case there are multiple streams of the same type
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return new stream profile, must be deleted by rs2_delete_stream_profile
|
||||||
|
*/
|
||||||
|
rs2_stream_profile* rs2_clone_video_stream_profile(const rs2_stream_profile* mode, rs2_stream stream, int index, rs2_format format, int width, int height, const rs2_intrinsics* intr, rs2_error** error);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delete stream profile allocated by rs2_clone_stream_profile
|
||||||
|
* Should not be called on stream profiles returned by the device
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
*/
|
||||||
|
void rs2_delete_stream_profile(rs2_stream_profile* mode);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Try to extend stream profile to an extension type
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[in] type extension type, for example RS2_EXTENSION_VIDEO_STREAM_PROFILE
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return non-zero if profile is extendable to specified extension, zero otherwise
|
||||||
|
*/
|
||||||
|
int rs2_stream_profile_is(const rs2_stream_profile* mode, rs2_extension type, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* When called on a video stream profile, will return the width and the height of the stream
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[out] width width in pixels of the video stream
|
||||||
|
* \param[out] height height in pixels of the video stream
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_video_stream_resolution(const rs2_stream_profile* mode, int* width, int* height, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Obtain the intrinsics of a specific stream configuration from the device.
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[out] intrinsics Pointer to the struct to store the data in
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_motion_intrinsics(const rs2_stream_profile* mode, rs2_motion_device_intrinsic * intrinsics, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns non-zero if selected profile is recommended for the sensor
|
||||||
|
* This is an optional hint we offer to suggest profiles with best performance-quality tradeof
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return non-zero if selected profile is recommended for the sensor
|
||||||
|
*/
|
||||||
|
int rs2_is_stream_profile_default(const rs2_stream_profile* mode, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get the number of supported stream profiles
|
||||||
|
* \param[in] list the list of supported profiles returned by rs2_get_supported_profiles
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return number of supported subdevice profiles
|
||||||
|
*/
|
||||||
|
int rs2_get_stream_profiles_count(const rs2_stream_profile_list* list, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* delete stream profiles list
|
||||||
|
* \param[in] list the list of supported profiles returned by rs2_get_supported_profiles
|
||||||
|
*/
|
||||||
|
void rs2_delete_stream_profiles_list(rs2_stream_profile_list* list);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \param[in] from origin stream profile
|
||||||
|
* \param[in] to target stream profile
|
||||||
|
* \param[out] extrin extrinsics from origin to target
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_extrinsics(const rs2_stream_profile* from,
|
||||||
|
const rs2_stream_profile* to,
|
||||||
|
rs2_extrinsics* extrin, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \param[in] from origin stream profile
|
||||||
|
* \param[in] to target stream profile
|
||||||
|
* \param[out] extrin extrinsics from origin to target
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_register_extrinsics(const rs2_stream_profile* from,
|
||||||
|
const rs2_stream_profile* to,
|
||||||
|
rs2_extrinsics extrin, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Override extrinsics of a given sensor that supports calibrated_sensor.
|
||||||
|
*
|
||||||
|
* This will affect extrinsics at the source device and may affect multiple profiles. Used for DEPTH_TO_RGB calibration.
|
||||||
|
*
|
||||||
|
* \param[in] sensor The sensor
|
||||||
|
* \param[in] extrinsics Extrinsics from Depth to the named sensor
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_override_extrinsics( const rs2_sensor* sensor, const rs2_extrinsics* extrinsics, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* When called on a video profile, returns the intrinsics of specific stream configuration
|
||||||
|
* \param[in] mode input stream profile
|
||||||
|
* \param[out] intrinsics resulting intrinsics for the video profile
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_video_stream_intrinsics(const rs2_stream_profile* mode, rs2_intrinsics* intrinsics, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the list of recommended processing blocks for a specific sensor.
|
||||||
|
* Order and configuration of the blocks are decided by the sensor
|
||||||
|
* \param[in] sensor input sensor
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return list of supported sensor recommended processing blocks
|
||||||
|
*/
|
||||||
|
rs2_processing_block_list* rs2_get_recommended_processing_blocks(rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns specific processing blocks from processing blocks list
|
||||||
|
* \param[in] list the processing blocks list
|
||||||
|
* \param[in] index the requested processing block
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return processing block
|
||||||
|
*/
|
||||||
|
rs2_processing_block* rs2_get_processing_block(const rs2_processing_block_list* list, int index, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the processing blocks list size
|
||||||
|
* \param[in] list the processing blocks list
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the processing block list size
|
||||||
|
*/
|
||||||
|
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list* list, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Deletes processing blocks list
|
||||||
|
* \param[in] list list to delete
|
||||||
|
*/
|
||||||
|
void rs2_delete_recommended_processing_blocks(rs2_processing_block_list* list);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Imports a localization map from file to tm2 tracking device
|
||||||
|
* \param[in] sensor TM2 position-tracking sensor
|
||||||
|
* \param[in] lmap_blob Localization map raw buffer, serialized
|
||||||
|
* \param[in] blob_size The buffer's size in bytes
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Non-zero if succeeded, otherwise 0
|
||||||
|
*/
|
||||||
|
int rs2_import_localization_map(const rs2_sensor* sensor, const unsigned char* lmap_blob, unsigned int blob_size, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extract and store the localization map of tm2 tracking device to file
|
||||||
|
* \param[in] sensor TM2 position-tracking sensor
|
||||||
|
* \param[in] lmap_fname The file name of the localization map
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Device's response in a rs2_raw_data_buffer, which should be released by rs2_delete_raw_data
|
||||||
|
*/
|
||||||
|
//void rs2_export_localization_map(const rs2_sensor* sensor, const char* lmap_fname, rs2_error** error);
|
||||||
|
const rs2_raw_data_buffer* rs2_export_localization_map(const rs2_sensor* sensor, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create a named location tag
|
||||||
|
* \param[in] sensor T2xx position-tracking sensor
|
||||||
|
* \param[in] guid Null-terminated string of up to 127 characters
|
||||||
|
* \param[in] pos Position in meters, relative to the current tracking session
|
||||||
|
* \param[in] orient Quaternion orientation, expressed the the coordinate system of the current tracking session
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Non-zero if succeeded, otherwise 0
|
||||||
|
*/
|
||||||
|
int rs2_set_static_node(const rs2_sensor* sensor, const char* guid, const rs2_vector pos, const rs2_quaternion orient, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve a named location tag
|
||||||
|
* \param[in] sensor T2xx position-tracking sensor
|
||||||
|
* \param[in] guid Null-terminated string of up to 127 characters
|
||||||
|
* \param[out] pos Position in meters of the tagged (stored) location
|
||||||
|
* \param[out] orient Quaternion orientation of the tagged (stored) location
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Non-zero if succeeded, otherwise 0
|
||||||
|
*/
|
||||||
|
int rs2_get_static_node(const rs2_sensor* sensor, const char* guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Remove a named location tag
|
||||||
|
* \param[in] sensor T2xx position-tracking sensor
|
||||||
|
* \param[in] guid Null-terminated string of up to 127 characters
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return Non-zero if succeeded, otherwise 0
|
||||||
|
*/
|
||||||
|
int rs2_remove_static_node(const rs2_sensor* sensor, const char* guid, rs2_error** error);
|
||||||
|
|
||||||
|
/** Load Wheel odometer settings from host to device
|
||||||
|
* \param[in] odometry_config_buf odometer configuration/calibration blob serialized from jsom file
|
||||||
|
* \return true on success
|
||||||
|
*/
|
||||||
|
int rs2_load_wheel_odometry_config(const rs2_sensor* sensor, const unsigned char* odometry_config_buf, unsigned int blob_size, rs2_error** error);
|
||||||
|
|
||||||
|
/** Send wheel odometry data for each individual sensor (wheel)
|
||||||
|
* \param[in] wo_sensor_id - Zero-based index of (wheel) sensor with the same type within device
|
||||||
|
* \param[in] frame_num - Monotonocally increasing frame number, managed per sensor.
|
||||||
|
* \param[in] translational_velocity - Translational velocity of the wheel sensor [meter/sec]
|
||||||
|
* \return true on success
|
||||||
|
*/
|
||||||
|
int rs2_send_wheel_odometry(const rs2_sensor* sensor, char wo_sensor_id, unsigned int frame_num,
|
||||||
|
const rs2_vector translational_velocity, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set intrinsics of a given sensor
|
||||||
|
* \param[in] sensor The RealSense device
|
||||||
|
* \param[in] profile Target stream profile
|
||||||
|
* \param[in] intrinsics Intrinsics value to be written to the device
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_intrinsics(const rs2_sensor* sensor, const rs2_stream_profile* profile , const rs2_intrinsics* intrinsics, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Override intrinsics of a given sensor that supports calibrated_sensor.
|
||||||
|
*
|
||||||
|
* This will affect intrinsics at the source and may affect multiple profiles. Used for DEPTH_TO_RGB calibration.
|
||||||
|
*
|
||||||
|
* \param[in] sensor The RealSense device
|
||||||
|
* \param[in] intrinsics Intrinsics value to be written to the sensor
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_override_intrinsics( const rs2_sensor* sensor, const rs2_intrinsics* intrinsics, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set extrinsics between two sensors
|
||||||
|
* \param[in] from_sensor Origin sensor
|
||||||
|
* \param[in] from_profile Origin profile
|
||||||
|
* \param[in] to_sensor Target sensor
|
||||||
|
* \param[in] to_profile Target profile
|
||||||
|
* \param[out] extrinsics Extrinsics from origin to target
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_extrinsics(const rs2_sensor* from_sensor, const rs2_stream_profile* from_profile, rs2_sensor* to_sensor, const rs2_stream_profile* to_profile, const rs2_extrinsics* extrinsics, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get the DSM parameters for a sensor
|
||||||
|
* \param[in] sensor Sensor that supports the CALIBRATED_SENSOR extension
|
||||||
|
* \param[out] p_params_out Pointer to the structure that will get the DSM parameters
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_get_dsm_params( rs2_sensor const * sensor, rs2_dsm_params * p_params_out, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the sensor DSM parameters
|
||||||
|
* This should ideally be done when the stream is NOT running. If it is, the
|
||||||
|
* parameters may not take effect immediately.
|
||||||
|
* \param[in] sensor Sensor that supports the CALIBRATED_SENSOR extension
|
||||||
|
* \param[out] p_params Pointer to the structure that contains the DSM parameters
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_override_dsm_params( rs2_sensor const * sensor, rs2_dsm_params const * p_params, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Reset the sensor DSM parameters
|
||||||
|
* This should ideally be done when the stream is NOT running. May not take effect immediately.
|
||||||
|
* \param[in] sensor Sensor that supports the CALIBRATED_SENSOR extension
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_reset_sensor_calibration( rs2_sensor const * sensor, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set motion device intrinsics
|
||||||
|
* \param[in] sensor Motion sensor
|
||||||
|
* \param[in] profile Motion stream profile
|
||||||
|
* \param[out] intrinsics Pointer to the struct to store the data in
|
||||||
|
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_set_motion_device_intrinsics(const rs2_sensor* sensor, const rs2_stream_profile* profile, const rs2_motion_device_intrinsic* intrinsics, rs2_error** error);
|
||||||
|
|
||||||
|
/** When called on a depth sensor, this method will return the maximum range of the camera given the amount of ambient light in the scene
|
||||||
|
* \param[in] sensor depth sensor
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the max usable range in meters
|
||||||
|
*/
|
||||||
|
float rs2_get_max_usable_depth_range(rs2_sensor const * sensor, rs2_error** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif // LIBREALSENSE_RS2_SENSOR_H
|
|
@ -0,0 +1,314 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs_types.h
|
||||||
|
* \brief
|
||||||
|
* Exposes RealSense structs
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_TYPES_H
|
||||||
|
#define LIBREALSENSE_RS2_TYPES_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** \brief Category of the librealsense notification. */
|
||||||
|
typedef enum rs2_notification_category{
|
||||||
|
RS2_NOTIFICATION_CATEGORY_FRAMES_TIMEOUT, /**< Frames didn't arrived within 5 seconds */
|
||||||
|
RS2_NOTIFICATION_CATEGORY_FRAME_CORRUPTED, /**< Received partial/incomplete frame */
|
||||||
|
RS2_NOTIFICATION_CATEGORY_HARDWARE_ERROR, /**< Error reported from the device */
|
||||||
|
RS2_NOTIFICATION_CATEGORY_HARDWARE_EVENT, /**< General Hardeware notification that is not an error */
|
||||||
|
RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR, /**< Received unknown error from the device */
|
||||||
|
RS2_NOTIFICATION_CATEGORY_FIRMWARE_UPDATE_RECOMMENDED, /**< Current firmware version installed is not the latest available */
|
||||||
|
RS2_NOTIFICATION_CATEGORY_POSE_RELOCALIZATION, /**< A relocalization event has updated the pose provided by a pose sensor */
|
||||||
|
RS2_NOTIFICATION_CATEGORY_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_notification_category;
|
||||||
|
const char* rs2_notification_category_to_string(rs2_notification_category category);
|
||||||
|
|
||||||
|
/** \brief Exception types are the different categories of errors that RealSense API might return. */
|
||||||
|
typedef enum rs2_exception_type
|
||||||
|
{
|
||||||
|
RS2_EXCEPTION_TYPE_UNKNOWN,
|
||||||
|
RS2_EXCEPTION_TYPE_CAMERA_DISCONNECTED, /**< Device was disconnected, this can be caused by outside intervention, by internal firmware error or due to insufficient power */
|
||||||
|
RS2_EXCEPTION_TYPE_BACKEND, /**< Error was returned from the underlying OS-specific layer */
|
||||||
|
RS2_EXCEPTION_TYPE_INVALID_VALUE, /**< Invalid value was passed to the API */
|
||||||
|
RS2_EXCEPTION_TYPE_WRONG_API_CALL_SEQUENCE, /**< Function precondition was violated */
|
||||||
|
RS2_EXCEPTION_TYPE_NOT_IMPLEMENTED, /**< The method is not implemented at this point */
|
||||||
|
RS2_EXCEPTION_TYPE_DEVICE_IN_RECOVERY_MODE, /**< Device is in recovery mode and might require firmware update */
|
||||||
|
RS2_EXCEPTION_TYPE_IO, /**< IO Device failure */
|
||||||
|
RS2_EXCEPTION_TYPE_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_exception_type;
|
||||||
|
const char* rs2_exception_type_to_string(rs2_exception_type type);
|
||||||
|
|
||||||
|
/** \brief Distortion model: defines how pixel coordinates should be mapped to sensor coordinates. */
|
||||||
|
typedef enum rs2_distortion
|
||||||
|
{
|
||||||
|
RS2_DISTORTION_NONE , /**< Rectilinear images. No distortion compensation required. */
|
||||||
|
RS2_DISTORTION_MODIFIED_BROWN_CONRADY, /**< Equivalent to Brown-Conrady distortion, except that tangential distortion is applied to radially distorted points */
|
||||||
|
RS2_DISTORTION_INVERSE_BROWN_CONRADY , /**< Equivalent to Brown-Conrady distortion, except undistorts image instead of distorting it */
|
||||||
|
RS2_DISTORTION_FTHETA , /**< F-Theta fish-eye distortion model */
|
||||||
|
RS2_DISTORTION_BROWN_CONRADY , /**< Unmodified Brown-Conrady distortion model */
|
||||||
|
RS2_DISTORTION_KANNALA_BRANDT4 , /**< Four parameter Kannala Brandt distortion model */
|
||||||
|
RS2_DISTORTION_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
} rs2_distortion;
|
||||||
|
const char* rs2_distortion_to_string(rs2_distortion distortion);
|
||||||
|
|
||||||
|
/** \brief Video stream intrinsics. */
|
||||||
|
typedef struct rs2_intrinsics
|
||||||
|
{
|
||||||
|
int width; /**< Width of the image in pixels */
|
||||||
|
int height; /**< Height of the image in pixels */
|
||||||
|
float ppx; /**< Horizontal coordinate of the principal point of the image, as a pixel offset from the left edge */
|
||||||
|
float ppy; /**< Vertical coordinate of the principal point of the image, as a pixel offset from the top edge */
|
||||||
|
float fx; /**< Focal length of the image plane, as a multiple of pixel width */
|
||||||
|
float fy; /**< Focal length of the image plane, as a multiple of pixel height */
|
||||||
|
rs2_distortion model; /**< Distortion model of the image */
|
||||||
|
float coeffs[5]; /**< Distortion coefficients. Order for Brown-Conrady: [k1, k2, p1, p2, k3]. Order for F-Theta Fish-eye: [k1, k2, k3, k4, 0]. Other models are subject to their own interpretations */
|
||||||
|
} rs2_intrinsics;
|
||||||
|
|
||||||
|
/** \brief Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params)
|
||||||
|
This is the block in MC that converts angles to dimensionless integers reported to MA (using "DSM coefficients").
|
||||||
|
*/
|
||||||
|
#pragma pack( push, 1 )
|
||||||
|
typedef struct rs2_dsm_params
|
||||||
|
{
|
||||||
|
unsigned long long timestamp; /**< system_clock::time_point::time_since_epoch().count() */
|
||||||
|
unsigned short version; /**< MAJOR<<12 | MINOR<<4 | PATCH */
|
||||||
|
unsigned char model; /**< rs2_dsm_correction_model */
|
||||||
|
unsigned char flags[5]; /**< TBD, now 0s */
|
||||||
|
float h_scale; /**< the scale factor to horizontal DSM scale thermal results */
|
||||||
|
float v_scale; /**< the scale factor to vertical DSM scale thermal results */
|
||||||
|
float h_offset; /**< the offset to horizontal DSM offset thermal results */
|
||||||
|
float v_offset; /**< the offset to vertical DSM offset thermal results */
|
||||||
|
float rtd_offset; /**< the offset to the Round-Trip-Distance delay thermal results */
|
||||||
|
unsigned char temp_x2; /**< the temperature recorded times 2 (ldd for depth; hum for rgb) */
|
||||||
|
float mc_h_scale; /**< the scale factor to horizontal LOS coefficients in MC */
|
||||||
|
float mc_v_scale; /**< the scale factor to vertical LOS coefficients in MC */
|
||||||
|
unsigned char weeks_since_calibration; /**< time (in weeks) since factory calibration */
|
||||||
|
unsigned char ac_weeks_since_calibaration; /**< time (in weeks) between factory calibration and last AC event */
|
||||||
|
unsigned char reserved[1];
|
||||||
|
} rs2_dsm_params;
|
||||||
|
#pragma pack( pop )
|
||||||
|
|
||||||
|
typedef enum rs2_dsm_correction_model
|
||||||
|
{
|
||||||
|
RS2_DSM_CORRECTION_NONE, /**< hFactor and hOffset are not used, and no artificial error is induced */
|
||||||
|
RS2_DSM_CORRECTION_AOT, /**< Aging-over-thermal (default); aging-induced error is uniform across temperature */
|
||||||
|
RS2_DSM_CORRECTION_TOA, /**< Thermal-over-aging; aging-induced error changes alongside temperature */
|
||||||
|
RS2_DSM_CORRECTION_COUNT
|
||||||
|
} rs2_dsm_correction_model;
|
||||||
|
|
||||||
|
/** \brief Motion device intrinsics: scale, bias, and variances. */
|
||||||
|
typedef struct rs2_motion_device_intrinsic
|
||||||
|
{
|
||||||
|
/* \internal
|
||||||
|
* Scale X cross axis cross axis Bias X \n
|
||||||
|
* cross axis Scale Y cross axis Bias Y \n
|
||||||
|
* cross axis cross axis Scale Z Bias Z */
|
||||||
|
float data[3][4]; /**< Interpret data array values */
|
||||||
|
|
||||||
|
float noise_variances[3]; /**< Variance of noise for X, Y, and Z axis */
|
||||||
|
float bias_variances[3]; /**< Variance of bias for X, Y, and Z axis */
|
||||||
|
} rs2_motion_device_intrinsic;
|
||||||
|
|
||||||
|
/** \brief 3D coordinates with origin at topmost left corner of the lense,
|
||||||
|
with positive Z pointing away from the camera, positive X pointing camera right and positive Y pointing camera down */
|
||||||
|
typedef struct rs2_vertex
|
||||||
|
{
|
||||||
|
float xyz[3];
|
||||||
|
} rs2_vertex;
|
||||||
|
|
||||||
|
/** \brief Pixel location within 2D image. (0,0) is the topmost, left corner. Positive X is right, positive Y is down */
|
||||||
|
typedef struct rs2_pixel
|
||||||
|
{
|
||||||
|
int ij[2];
|
||||||
|
} rs2_pixel;
|
||||||
|
|
||||||
|
/** \brief 3D vector in Euclidean coordinate space */
|
||||||
|
typedef struct rs2_vector
|
||||||
|
{
|
||||||
|
float x, y, z;
|
||||||
|
}rs2_vector;
|
||||||
|
|
||||||
|
/** \brief Quaternion used to represent rotation */
|
||||||
|
typedef struct rs2_quaternion
|
||||||
|
{
|
||||||
|
float x, y, z, w;
|
||||||
|
}rs2_quaternion;
|
||||||
|
|
||||||
|
typedef struct rs2_pose
|
||||||
|
{
|
||||||
|
rs2_vector translation; /**< X, Y, Z values of translation, in meters (relative to initial position) */
|
||||||
|
rs2_vector velocity; /**< X, Y, Z values of velocity, in meters/sec */
|
||||||
|
rs2_vector acceleration; /**< X, Y, Z values of acceleration, in meters/sec^2 */
|
||||||
|
rs2_quaternion rotation; /**< Qi, Qj, Qk, Qr components of rotation as represented in quaternion rotation (relative to initial position) */
|
||||||
|
rs2_vector angular_velocity; /**< X, Y, Z values of angular velocity, in radians/sec */
|
||||||
|
rs2_vector angular_acceleration; /**< X, Y, Z values of angular acceleration, in radians/sec^2 */
|
||||||
|
unsigned int tracker_confidence; /**< Pose confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High */
|
||||||
|
unsigned int mapper_confidence; /**< Pose map confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High */
|
||||||
|
} rs2_pose;
|
||||||
|
|
||||||
|
/** \brief Severity of the librealsense logger. */
|
||||||
|
typedef enum rs2_log_severity {
|
||||||
|
RS2_LOG_SEVERITY_DEBUG, /**< Detailed information about ordinary operations */
|
||||||
|
RS2_LOG_SEVERITY_INFO , /**< Terse information about ordinary operations */
|
||||||
|
RS2_LOG_SEVERITY_WARN , /**< Indication of possible failure */
|
||||||
|
RS2_LOG_SEVERITY_ERROR, /**< Indication of definite failure */
|
||||||
|
RS2_LOG_SEVERITY_FATAL, /**< Indication of unrecoverable failure */
|
||||||
|
RS2_LOG_SEVERITY_NONE , /**< No logging will occur */
|
||||||
|
RS2_LOG_SEVERITY_COUNT, /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
|
||||||
|
RS2_LOG_SEVERITY_ALL = RS2_LOG_SEVERITY_DEBUG /**< Include any/all log messages */
|
||||||
|
} rs2_log_severity;
|
||||||
|
const char* rs2_log_severity_to_string(rs2_log_severity info);
|
||||||
|
|
||||||
|
/** \brief Specifies advanced interfaces (capabilities) objects may implement. */
|
||||||
|
typedef enum rs2_extension
|
||||||
|
{
|
||||||
|
RS2_EXTENSION_UNKNOWN,
|
||||||
|
RS2_EXTENSION_DEBUG,
|
||||||
|
RS2_EXTENSION_INFO,
|
||||||
|
RS2_EXTENSION_MOTION,
|
||||||
|
RS2_EXTENSION_OPTIONS,
|
||||||
|
RS2_EXTENSION_VIDEO,
|
||||||
|
RS2_EXTENSION_ROI,
|
||||||
|
RS2_EXTENSION_DEPTH_SENSOR,
|
||||||
|
RS2_EXTENSION_VIDEO_FRAME,
|
||||||
|
RS2_EXTENSION_MOTION_FRAME,
|
||||||
|
RS2_EXTENSION_COMPOSITE_FRAME,
|
||||||
|
RS2_EXTENSION_POINTS,
|
||||||
|
RS2_EXTENSION_DEPTH_FRAME,
|
||||||
|
RS2_EXTENSION_ADVANCED_MODE,
|
||||||
|
RS2_EXTENSION_RECORD,
|
||||||
|
RS2_EXTENSION_VIDEO_PROFILE,
|
||||||
|
RS2_EXTENSION_PLAYBACK,
|
||||||
|
RS2_EXTENSION_DEPTH_STEREO_SENSOR,
|
||||||
|
RS2_EXTENSION_DISPARITY_FRAME,
|
||||||
|
RS2_EXTENSION_MOTION_PROFILE,
|
||||||
|
RS2_EXTENSION_POSE_FRAME,
|
||||||
|
RS2_EXTENSION_POSE_PROFILE,
|
||||||
|
RS2_EXTENSION_TM2,
|
||||||
|
RS2_EXTENSION_SOFTWARE_DEVICE,
|
||||||
|
RS2_EXTENSION_SOFTWARE_SENSOR,
|
||||||
|
RS2_EXTENSION_DECIMATION_FILTER,
|
||||||
|
RS2_EXTENSION_THRESHOLD_FILTER,
|
||||||
|
RS2_EXTENSION_DISPARITY_FILTER,
|
||||||
|
RS2_EXTENSION_SPATIAL_FILTER,
|
||||||
|
RS2_EXTENSION_TEMPORAL_FILTER,
|
||||||
|
RS2_EXTENSION_HOLE_FILLING_FILTER,
|
||||||
|
RS2_EXTENSION_ZERO_ORDER_FILTER,
|
||||||
|
RS2_EXTENSION_RECOMMENDED_FILTERS,
|
||||||
|
RS2_EXTENSION_POSE,
|
||||||
|
RS2_EXTENSION_POSE_SENSOR,
|
||||||
|
RS2_EXTENSION_WHEEL_ODOMETER,
|
||||||
|
RS2_EXTENSION_GLOBAL_TIMER,
|
||||||
|
RS2_EXTENSION_UPDATABLE,
|
||||||
|
RS2_EXTENSION_UPDATE_DEVICE,
|
||||||
|
RS2_EXTENSION_L500_DEPTH_SENSOR,
|
||||||
|
RS2_EXTENSION_TM2_SENSOR,
|
||||||
|
RS2_EXTENSION_AUTO_CALIBRATED_DEVICE,
|
||||||
|
RS2_EXTENSION_COLOR_SENSOR,
|
||||||
|
RS2_EXTENSION_MOTION_SENSOR,
|
||||||
|
RS2_EXTENSION_FISHEYE_SENSOR,
|
||||||
|
RS2_EXTENSION_DEPTH_HUFFMAN_DECODER,
|
||||||
|
RS2_EXTENSION_SERIALIZABLE,
|
||||||
|
RS2_EXTENSION_FW_LOGGER,
|
||||||
|
RS2_EXTENSION_AUTO_CALIBRATION_FILTER,
|
||||||
|
RS2_EXTENSION_DEVICE_CALIBRATION,
|
||||||
|
RS2_EXTENSION_CALIBRATED_SENSOR,
|
||||||
|
RS2_EXTENSION_HDR_MERGE,
|
||||||
|
RS2_EXTENSION_SEQUENCE_ID_FILTER,
|
||||||
|
RS2_EXTENSION_MAX_USABLE_RANGE_SENSOR,
|
||||||
|
RS2_EXTENSION_DEBUG_STREAM_SENSOR,
|
||||||
|
RS2_EXTENSION_CALIBRATION_CHANGE_DEVICE,
|
||||||
|
RS2_EXTENSION_COUNT
|
||||||
|
} rs2_extension;
|
||||||
|
const char* rs2_extension_type_to_string(rs2_extension type);
|
||||||
|
const char* rs2_extension_to_string(rs2_extension type);
|
||||||
|
|
||||||
|
/** \brief Specifies types of different matchers */
|
||||||
|
typedef enum rs2_matchers
|
||||||
|
{
|
||||||
|
RS2_MATCHER_DI, //compare depth and ir based on frame number
|
||||||
|
|
||||||
|
RS2_MATCHER_DI_C, //compare depth and ir based on frame number,
|
||||||
|
//compare the pair of corresponding depth and ir with color based on closest timestamp,
|
||||||
|
//commonly used by SR300
|
||||||
|
|
||||||
|
RS2_MATCHER_DLR_C, //compare depth, left and right ir based on frame number,
|
||||||
|
//compare the set of corresponding depth, left and right with color based on closest timestamp,
|
||||||
|
//commonly used by RS415, RS435
|
||||||
|
|
||||||
|
RS2_MATCHER_DLR, //compare depth, left and right ir based on frame number,
|
||||||
|
//commonly used by RS400, RS405, RS410, RS420, RS430
|
||||||
|
|
||||||
|
RS2_MATCHER_DIC, //compare depth, ir and confidence based on frame number used by RS500
|
||||||
|
|
||||||
|
RS2_MATCHER_DIC_C, //compare depth, ir and confidence based on frame number,
|
||||||
|
//compare the set of corresponding depth, ir and confidence with color based on closest timestamp,
|
||||||
|
//commonly used by RS515
|
||||||
|
|
||||||
|
RS2_MATCHER_DEFAULT, //the default matcher compare all the streams based on closest timestamp
|
||||||
|
|
||||||
|
RS2_MATCHER_COUNT
|
||||||
|
} rs2_matchers;
|
||||||
|
const char* rs2_matchers_to_string(rs2_matchers stream);
|
||||||
|
|
||||||
|
typedef struct rs2_device_info rs2_device_info;
|
||||||
|
typedef struct rs2_device rs2_device;
|
||||||
|
typedef struct rs2_error rs2_error;
|
||||||
|
typedef struct rs2_log_message rs2_log_message;
|
||||||
|
typedef struct rs2_raw_data_buffer rs2_raw_data_buffer;
|
||||||
|
typedef struct rs2_frame rs2_frame;
|
||||||
|
typedef struct rs2_frame_queue rs2_frame_queue;
|
||||||
|
typedef struct rs2_pipeline rs2_pipeline;
|
||||||
|
typedef struct rs2_pipeline_profile rs2_pipeline_profile;
|
||||||
|
typedef struct rs2_config rs2_config;
|
||||||
|
typedef struct rs2_device_list rs2_device_list;
|
||||||
|
typedef struct rs2_stream_profile_list rs2_stream_profile_list;
|
||||||
|
typedef struct rs2_processing_block_list rs2_processing_block_list;
|
||||||
|
typedef struct rs2_stream_profile rs2_stream_profile;
|
||||||
|
typedef struct rs2_frame_callback rs2_frame_callback;
|
||||||
|
typedef struct rs2_log_callback rs2_log_callback;
|
||||||
|
typedef struct rs2_syncer rs2_syncer;
|
||||||
|
typedef struct rs2_device_serializer rs2_device_serializer;
|
||||||
|
typedef struct rs2_source rs2_source;
|
||||||
|
typedef struct rs2_processing_block rs2_processing_block;
|
||||||
|
typedef struct rs2_frame_processor_callback rs2_frame_processor_callback;
|
||||||
|
typedef struct rs2_playback_status_changed_callback rs2_playback_status_changed_callback;
|
||||||
|
typedef struct rs2_update_progress_callback rs2_update_progress_callback;
|
||||||
|
typedef struct rs2_context rs2_context;
|
||||||
|
typedef struct rs2_device_hub rs2_device_hub;
|
||||||
|
typedef struct rs2_sensor_list rs2_sensor_list;
|
||||||
|
typedef struct rs2_sensor rs2_sensor;
|
||||||
|
typedef struct rs2_options rs2_options;
|
||||||
|
typedef struct rs2_options_list rs2_options_list;
|
||||||
|
typedef struct rs2_devices_changed_callback rs2_devices_changed_callback;
|
||||||
|
typedef struct rs2_notification rs2_notification;
|
||||||
|
typedef struct rs2_notifications_callback rs2_notifications_callback;
|
||||||
|
typedef struct rs2_firmware_log_message rs2_firmware_log_message;
|
||||||
|
typedef struct rs2_firmware_log_parsed_message rs2_firmware_log_parsed_message;
|
||||||
|
typedef struct rs2_firmware_log_parser rs2_firmware_log_parser;
|
||||||
|
typedef struct rs2_terminal_parser rs2_terminal_parser;
|
||||||
|
typedef void (*rs2_log_callback_ptr)(rs2_log_severity, rs2_log_message const *, void * arg);
|
||||||
|
typedef void (*rs2_notification_callback_ptr)(rs2_notification*, void*);
|
||||||
|
typedef void(*rs2_software_device_destruction_callback_ptr)(void*);
|
||||||
|
typedef void (*rs2_devices_changed_callback_ptr)(rs2_device_list*, rs2_device_list*, void*);
|
||||||
|
typedef void (*rs2_frame_callback_ptr)(rs2_frame*, void*);
|
||||||
|
typedef void (*rs2_frame_processor_callback_ptr)(rs2_frame*, rs2_source*, void*);
|
||||||
|
typedef void(*rs2_update_progress_callback_ptr)(const float, void*);
|
||||||
|
|
||||||
|
typedef double rs2_time_t; /**< Timestamp format. units are milliseconds */
|
||||||
|
typedef long long rs2_metadata_type; /**< Metadata attribute type is defined as 64 bit signed integer*/
|
||||||
|
|
||||||
|
rs2_error * rs2_create_error(const char* what, const char* name, const char* args, rs2_exception_type type);
|
||||||
|
rs2_exception_type rs2_get_librealsense_exception_type(const rs2_error* error);
|
||||||
|
const char* rs2_get_failed_function (const rs2_error* error);
|
||||||
|
const char* rs2_get_failed_args (const rs2_error* error);
|
||||||
|
const char* rs2_get_error_message (const rs2_error* error);
|
||||||
|
void rs2_free_error (rs2_error* error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,273 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_CONTEXT_HPP
|
||||||
|
#define LIBREALSENSE_RS2_CONTEXT_HPP
|
||||||
|
|
||||||
|
#include "rs_types.hpp"
|
||||||
|
#include "rs_record_playback.hpp"
|
||||||
|
#include "rs_processing.hpp"
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
class event_information
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
event_information(device_list removed, device_list added)
|
||||||
|
:_removed(removed), _added(added) {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if a specific device was disconnected
|
||||||
|
* \return true if device disconnected, false if device connected
|
||||||
|
*/
|
||||||
|
bool was_removed(const rs2::device& dev) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
if (!dev)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
auto res = rs2_device_list_contains(_removed.get_list(), dev.get().get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return res > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if a specific device was added
|
||||||
|
* \return true if device added, false otherwise
|
||||||
|
*/
|
||||||
|
bool was_added(const rs2::device& dev) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
if (!dev)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
auto res = rs2_device_list_contains(_added.get_list(), dev.get().get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return res > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* returns a list of all newly connected devices
|
||||||
|
* \return the list of all new connected devices
|
||||||
|
*/
|
||||||
|
device_list get_new_devices() const
|
||||||
|
{
|
||||||
|
return _added;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
device_list _removed;
|
||||||
|
device_list _added;
|
||||||
|
};
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
class devices_changed_callback : public rs2_devices_changed_callback
|
||||||
|
{
|
||||||
|
T _callback;
|
||||||
|
|
||||||
|
public:
|
||||||
|
explicit devices_changed_callback(T callback) : _callback(callback) {}
|
||||||
|
|
||||||
|
void on_devices_changed(rs2_device_list* removed, rs2_device_list* added) override
|
||||||
|
{
|
||||||
|
std::shared_ptr<rs2_device_list> old(removed, rs2_delete_device_list);
|
||||||
|
std::shared_ptr<rs2_device_list> news(added, rs2_delete_device_list);
|
||||||
|
|
||||||
|
|
||||||
|
event_information info({ device_list(old), device_list(news) });
|
||||||
|
_callback(info);
|
||||||
|
}
|
||||||
|
|
||||||
|
void release() override { delete this; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class pipeline;
|
||||||
|
class device_hub;
|
||||||
|
class software_device;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* default librealsense context class
|
||||||
|
* includes realsense API version as provided by RS2_API_VERSION macro
|
||||||
|
*/
|
||||||
|
class context
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
context()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_context = std::shared_ptr<rs2_context>(
|
||||||
|
rs2_create_context(RS2_API_VERSION, &e),
|
||||||
|
rs2_delete_context);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* create a static snapshot of all connected devices at the time of the call
|
||||||
|
* \return the list of devices connected devices at the time of the call
|
||||||
|
*/
|
||||||
|
device_list query_devices() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_device_list> list(
|
||||||
|
rs2_query_devices(_context.get(), &e),
|
||||||
|
rs2_delete_device_list);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return device_list(list);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* create a static snapshot of all connected devices at the time of the call
|
||||||
|
* \return the list of devices connected devices at the time of the call
|
||||||
|
*/
|
||||||
|
device_list query_devices(int mask) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_device_list> list(
|
||||||
|
rs2_query_devices_ex(_context.get(), mask, &e),
|
||||||
|
rs2_delete_device_list);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return device_list(list);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generate a flat list of all available sensors from all RealSense devices
|
||||||
|
* @return List of sensors
|
||||||
|
*/
|
||||||
|
std::vector<sensor> query_all_sensors() const
|
||||||
|
{
|
||||||
|
std::vector<sensor> results;
|
||||||
|
for (auto&& dev : query_devices())
|
||||||
|
{
|
||||||
|
auto sensors = dev.query_sensors();
|
||||||
|
std::copy(sensors.begin(), sensors.end(), std::back_inserter(results));
|
||||||
|
}
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
device get_sensor_parent(const sensor& s) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_device> dev(
|
||||||
|
rs2_create_device_from_sensor(s._sensor.get(), &e),
|
||||||
|
rs2_delete_device);
|
||||||
|
error::handle(e);
|
||||||
|
return device{ dev };
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* register devices changed callback
|
||||||
|
* \param[in] callback devices changed callback
|
||||||
|
*/
|
||||||
|
template<class T>
|
||||||
|
void set_devices_changed_callback(T callback)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_devices_changed_callback_cpp(_context.get(),
|
||||||
|
new devices_changed_callback<T>(std::move(callback)), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a device from a RealSense file
|
||||||
|
*
|
||||||
|
* On successful load, the device will be appended to the context and a devices_changed event triggered
|
||||||
|
* @param file Path to a RealSense File
|
||||||
|
* @return A playback device matching the given file
|
||||||
|
*/
|
||||||
|
playback load_device(const std::string& file)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto device = std::shared_ptr<rs2_device>(
|
||||||
|
rs2_context_add_device(_context.get(), file.c_str(), &e),
|
||||||
|
rs2_delete_device);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return playback { device };
|
||||||
|
}
|
||||||
|
|
||||||
|
void unload_device(const std::string& file)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_context_remove_device(_context.get(), file.c_str(), &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
void unload_tracking_module()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_context_unload_tracking_module(_context.get(), &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
context(std::shared_ptr<rs2_context> ctx)
|
||||||
|
: _context(ctx)
|
||||||
|
{}
|
||||||
|
explicit operator std::shared_ptr<rs2_context>() { return _context; };
|
||||||
|
protected:
|
||||||
|
friend class rs2::pipeline;
|
||||||
|
friend class rs2::device_hub;
|
||||||
|
friend class rs2::software_device;
|
||||||
|
|
||||||
|
std::shared_ptr<rs2_context> _context;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* device_hub class - encapsulate the handling of connect and disconnect events
|
||||||
|
*/
|
||||||
|
class device_hub
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit device_hub(context ctx)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_device_hub = std::shared_ptr<rs2_device_hub>(
|
||||||
|
rs2_create_device_hub(ctx._context.get(), &e),
|
||||||
|
rs2_delete_device_hub);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* If any device is connected return it, otherwise wait until next RealSense device connects.
|
||||||
|
* Calling this method multiple times will cycle through connected devices
|
||||||
|
*/
|
||||||
|
device wait_for_device() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_device> dev(
|
||||||
|
rs2_device_hub_wait_for_device(_device_hub.get(), &e),
|
||||||
|
rs2_delete_device);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return device(dev);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Checks if device is still connected
|
||||||
|
*/
|
||||||
|
bool is_connected(const device& dev) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_device_hub_is_device_connected(_device_hub.get(), dev._dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return res > 0 ? true : false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
explicit operator std::shared_ptr<rs2_device_hub>() { return _device_hub; }
|
||||||
|
explicit device_hub(std::shared_ptr<rs2_device_hub> hub) : _device_hub(std::move(hub)) {}
|
||||||
|
private:
|
||||||
|
std::shared_ptr<rs2_device_hub> _device_hub;
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
#endif // LIBREALSENSE_RS2_CONTEXT_HPP
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,389 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_EXPORT_HPP
|
||||||
|
#define LIBREALSENSE_RS2_EXPORT_HPP
|
||||||
|
|
||||||
|
#include <map>
|
||||||
|
#include <fstream>
|
||||||
|
#include <cmath>
|
||||||
|
#include <sstream>
|
||||||
|
#include <cassert>
|
||||||
|
#include "rs_processing.hpp"
|
||||||
|
#include "rs_internal.hpp"
|
||||||
|
#include <iostream>
|
||||||
|
#include <thread>
|
||||||
|
#include <chrono>
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
struct vec3d {
|
||||||
|
float x, y, z;
|
||||||
|
float length() const { return sqrt(x * x + y * y + z * z); }
|
||||||
|
|
||||||
|
vec3d normalize() const
|
||||||
|
{
|
||||||
|
auto len = length();
|
||||||
|
return { x / len, y / len, z / len };
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
inline vec3d operator + (const vec3d & a, const vec3d & b) { return{ a.x + b.x, a.y + b.y, a.z + b.z }; }
|
||||||
|
inline vec3d operator - (const vec3d & a, const vec3d & b) { return{ a.x - b.x, a.y - b.y, a.z - b.z }; }
|
||||||
|
inline vec3d cross(const vec3d & a, const vec3d & b) { return { a.y * b.z - a.z * b.y, a.z * b.x - a.x * b.z, a.x * b.y - a.y * b.x }; }
|
||||||
|
|
||||||
|
class save_to_ply : public filter
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
static const auto OPTION_IGNORE_COLOR = rs2_option(RS2_OPTION_COUNT + 10);
|
||||||
|
static const auto OPTION_PLY_MESH = rs2_option(RS2_OPTION_COUNT + 11);
|
||||||
|
static const auto OPTION_PLY_BINARY = rs2_option(RS2_OPTION_COUNT + 12);
|
||||||
|
static const auto OPTION_PLY_NORMALS = rs2_option(RS2_OPTION_COUNT + 13);
|
||||||
|
static const auto OPTION_PLY_THRESHOLD = rs2_option(RS2_OPTION_COUNT + 14);
|
||||||
|
|
||||||
|
save_to_ply(std::string filename = "RealSense Pointcloud ", pointcloud pc = pointcloud()) : filter([this](frame f, frame_source& s) { func(f, s); }),
|
||||||
|
_pc(std::move(pc)), fname(filename)
|
||||||
|
{
|
||||||
|
register_simple_option(OPTION_IGNORE_COLOR, option_range{ 0, 1, 0, 1 });
|
||||||
|
register_simple_option(OPTION_PLY_MESH, option_range{ 0, 1, 1, 1 });
|
||||||
|
register_simple_option(OPTION_PLY_NORMALS, option_range{ 0, 1, 0, 1 });
|
||||||
|
register_simple_option(OPTION_PLY_BINARY, option_range{ 0, 1, 1, 1 });
|
||||||
|
register_simple_option(OPTION_PLY_THRESHOLD, option_range{ 0, 1, 0.05f, 0 });
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
void func(frame data, frame_source& source)
|
||||||
|
{
|
||||||
|
frame depth, color;
|
||||||
|
if (auto fs = data.as<frameset>()) {
|
||||||
|
for (auto f : fs) {
|
||||||
|
if (f.is<points>()) depth = f;
|
||||||
|
else if (!depth && f.is<depth_frame>()) depth = f;
|
||||||
|
else if (!color && f.is<video_frame>()) color = f;
|
||||||
|
}
|
||||||
|
} else if (data.is<depth_frame>() || data.is<points>()) {
|
||||||
|
depth = data;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!depth) throw std::runtime_error("Need depth data to save PLY");
|
||||||
|
if (!depth.is<points>()) {
|
||||||
|
if (color) _pc.map_to(color);
|
||||||
|
depth = _pc.calculate(depth);
|
||||||
|
}
|
||||||
|
|
||||||
|
export_to_ply(depth, color);
|
||||||
|
source.frame_ready(data); // passthrough filter because processing_block::process doesn't support sinks
|
||||||
|
}
|
||||||
|
|
||||||
|
void export_to_ply(points p, video_frame color) {
|
||||||
|
const bool use_texcoords = color && !get_option(OPTION_IGNORE_COLOR);
|
||||||
|
bool mesh = get_option(OPTION_PLY_MESH) != 0;
|
||||||
|
bool binary = get_option(OPTION_PLY_BINARY) != 0;
|
||||||
|
bool use_normals = get_option(OPTION_PLY_NORMALS) != 0;
|
||||||
|
const auto verts = p.get_vertices();
|
||||||
|
const auto texcoords = p.get_texture_coordinates();
|
||||||
|
const uint8_t* texture_data;
|
||||||
|
if (use_texcoords) // texture might be on the gpu, get pointer to data before for-loop to avoid repeated access
|
||||||
|
texture_data = reinterpret_cast<const uint8_t*>(color.get_data());
|
||||||
|
std::vector<rs2::vertex> new_verts;
|
||||||
|
std::vector<vec3d> normals;
|
||||||
|
std::vector<std::array<uint8_t, 3>> new_tex;
|
||||||
|
std::map<size_t, size_t> idx_map;
|
||||||
|
std::map<size_t, std::vector<vec3d>> index_to_normals;
|
||||||
|
|
||||||
|
new_verts.reserve(p.size());
|
||||||
|
if (use_texcoords) new_tex.reserve(p.size());
|
||||||
|
|
||||||
|
static const auto min_distance = 1e-6;
|
||||||
|
|
||||||
|
for (size_t i = 0; i < p.size(); ++i) {
|
||||||
|
if (fabs(verts[i].x) >= min_distance || fabs(verts[i].y) >= min_distance ||
|
||||||
|
fabs(verts[i].z) >= min_distance)
|
||||||
|
{
|
||||||
|
idx_map[int(i)] = int(new_verts.size());
|
||||||
|
new_verts.push_back({ verts[i].x, -1 * verts[i].y, -1 * verts[i].z });
|
||||||
|
if (use_texcoords)
|
||||||
|
{
|
||||||
|
auto rgb = get_texcolor(color, texture_data, texcoords[i].u, texcoords[i].v);
|
||||||
|
new_tex.push_back(rgb);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
auto profile = p.get_profile().as<video_stream_profile>();
|
||||||
|
auto width = profile.width(), height = profile.height();
|
||||||
|
static const auto threshold = get_option(OPTION_PLY_THRESHOLD);
|
||||||
|
std::vector<std::array<size_t, 3>> faces;
|
||||||
|
if (mesh)
|
||||||
|
{
|
||||||
|
for (size_t x = 0; x < width - 1; ++x) {
|
||||||
|
for (size_t y = 0; y < height - 1; ++y) {
|
||||||
|
auto a = y * width + x, b = y * width + x + 1, c = (y + 1)*width + x, d = (y + 1)*width + x + 1;
|
||||||
|
if (verts[a].z && verts[b].z && verts[c].z && verts[d].z
|
||||||
|
&& fabs(verts[a].z - verts[b].z) < threshold && fabs(verts[a].z - verts[c].z) < threshold
|
||||||
|
&& fabs(verts[b].z - verts[d].z) < threshold && fabs(verts[c].z - verts[d].z) < threshold)
|
||||||
|
{
|
||||||
|
if (idx_map.count(a) == 0 || idx_map.count(b) == 0 || idx_map.count(c) == 0 ||
|
||||||
|
idx_map.count(d) == 0)
|
||||||
|
continue;
|
||||||
|
faces.push_back({ idx_map[a], idx_map[d], idx_map[b] });
|
||||||
|
faces.push_back({ idx_map[d], idx_map[a], idx_map[c] });
|
||||||
|
|
||||||
|
if (use_normals)
|
||||||
|
{
|
||||||
|
vec3d point_a = { verts[a].x , -1 * verts[a].y, -1 * verts[a].z };
|
||||||
|
vec3d point_b = { verts[b].x , -1 * verts[b].y, -1 * verts[b].z };
|
||||||
|
vec3d point_c = { verts[c].x , -1 * verts[c].y, -1 * verts[c].z };
|
||||||
|
vec3d point_d = { verts[d].x , -1 * verts[d].y, -1 * verts[d].z };
|
||||||
|
|
||||||
|
auto n1 = cross(point_d - point_a, point_b - point_a);
|
||||||
|
auto n2 = cross(point_c - point_a, point_d - point_a);
|
||||||
|
|
||||||
|
index_to_normals[idx_map[a]].push_back(n1);
|
||||||
|
index_to_normals[idx_map[a]].push_back(n2);
|
||||||
|
|
||||||
|
index_to_normals[idx_map[b]].push_back(n1);
|
||||||
|
|
||||||
|
index_to_normals[idx_map[c]].push_back(n2);
|
||||||
|
|
||||||
|
index_to_normals[idx_map[d]].push_back(n1);
|
||||||
|
index_to_normals[idx_map[d]].push_back(n2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (mesh && use_normals)
|
||||||
|
{
|
||||||
|
for (size_t i = 0; i < new_verts.size(); ++i)
|
||||||
|
{
|
||||||
|
auto normals_vec = index_to_normals[i];
|
||||||
|
vec3d sum = { 0, 0, 0 };
|
||||||
|
for (auto& n : normals_vec)
|
||||||
|
sum = sum + n;
|
||||||
|
if (normals_vec.size() > 0)
|
||||||
|
normals.push_back((sum.normalize()));
|
||||||
|
else
|
||||||
|
normals.push_back({ 0, 0, 0 });
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
std::ofstream out(fname);
|
||||||
|
out << "ply\n";
|
||||||
|
if (binary)
|
||||||
|
out << "format binary_little_endian 1.0\n";
|
||||||
|
else
|
||||||
|
out << "format ascii 1.0\n";
|
||||||
|
out << "comment pointcloud saved from Realsense Viewer\n";
|
||||||
|
out << "element vertex " << new_verts.size() << "\n";
|
||||||
|
out << "property float" << sizeof(float) * 8 << " x\n";
|
||||||
|
out << "property float" << sizeof(float) * 8 << " y\n";
|
||||||
|
out << "property float" << sizeof(float) * 8 << " z\n";
|
||||||
|
if (mesh && use_normals)
|
||||||
|
{
|
||||||
|
out << "property float" << sizeof(float) * 8 << " nx\n";
|
||||||
|
out << "property float" << sizeof(float) * 8 << " ny\n";
|
||||||
|
out << "property float" << sizeof(float) * 8 << " nz\n";
|
||||||
|
}
|
||||||
|
if (use_texcoords)
|
||||||
|
{
|
||||||
|
out << "property uchar red\n";
|
||||||
|
out << "property uchar green\n";
|
||||||
|
out << "property uchar blue\n";
|
||||||
|
}
|
||||||
|
if (mesh)
|
||||||
|
{
|
||||||
|
out << "element face " << faces.size() << "\n";
|
||||||
|
out << "property list uchar int vertex_indices\n";
|
||||||
|
}
|
||||||
|
out << "end_header\n";
|
||||||
|
|
||||||
|
if (binary)
|
||||||
|
{
|
||||||
|
out.close();
|
||||||
|
out.open(fname, std::ios_base::app | std::ios_base::binary);
|
||||||
|
for (size_t i = 0; i < new_verts.size(); ++i)
|
||||||
|
{
|
||||||
|
// we assume little endian architecture on your device
|
||||||
|
out.write(reinterpret_cast<const char*>(&(new_verts[i].x)), sizeof(float));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(new_verts[i].y)), sizeof(float));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(new_verts[i].z)), sizeof(float));
|
||||||
|
|
||||||
|
if (mesh && use_normals)
|
||||||
|
{
|
||||||
|
out.write(reinterpret_cast<const char*>(&(normals[i].x)), sizeof(float));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(normals[i].y)), sizeof(float));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(normals[i].z)), sizeof(float));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (use_texcoords)
|
||||||
|
{
|
||||||
|
out.write(reinterpret_cast<const char*>(&(new_tex[i][0])), sizeof(uint8_t));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(new_tex[i][1])), sizeof(uint8_t));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(new_tex[i][2])), sizeof(uint8_t));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (mesh)
|
||||||
|
{
|
||||||
|
auto size = faces.size();
|
||||||
|
for (size_t i = 0; i < size; ++i) {
|
||||||
|
static const int three = 3;
|
||||||
|
out.write(reinterpret_cast<const char*>(&three), sizeof(uint8_t));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(faces[i][0])), sizeof(int));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(faces[i][1])), sizeof(int));
|
||||||
|
out.write(reinterpret_cast<const char*>(&(faces[i][2])), sizeof(int));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
for (size_t i = 0; i <new_verts.size(); ++i)
|
||||||
|
{
|
||||||
|
out << new_verts[i].x << " ";
|
||||||
|
out << new_verts[i].y << " ";
|
||||||
|
out << new_verts[i].z << " ";
|
||||||
|
out << "\n";
|
||||||
|
|
||||||
|
if (mesh && use_normals)
|
||||||
|
{
|
||||||
|
out << normals[i].x << " ";
|
||||||
|
out << normals[i].y << " ";
|
||||||
|
out << normals[i].z << " ";
|
||||||
|
out << "\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
if (use_texcoords)
|
||||||
|
{
|
||||||
|
out << unsigned(new_tex[i][0]) << " ";
|
||||||
|
out << unsigned(new_tex[i][1]) << " ";
|
||||||
|
out << unsigned(new_tex[i][2]) << " ";
|
||||||
|
out << "\n";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (mesh)
|
||||||
|
{
|
||||||
|
auto size = faces.size();
|
||||||
|
for (size_t i = 0; i < size; ++i) {
|
||||||
|
int three = 3;
|
||||||
|
out << three << " ";
|
||||||
|
out << std::get<0>(faces[i]) << " ";
|
||||||
|
out << std::get<1>(faces[i]) << " ";
|
||||||
|
out << std::get<2>(faces[i]) << " ";
|
||||||
|
out << "\n";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
std::array<uint8_t, 3> get_texcolor(const video_frame& texture, const uint8_t* texture_data, float u, float v)
|
||||||
|
{
|
||||||
|
const int w = texture.get_width(), h = texture.get_height();
|
||||||
|
int x = std::min(std::max(int(u*w + .5f), 0), w - 1);
|
||||||
|
int y = std::min(std::max(int(v*h + .5f), 0), h - 1);
|
||||||
|
int idx = x * texture.get_bytes_per_pixel() + y * texture.get_stride_in_bytes();
|
||||||
|
return { texture_data[idx], texture_data[idx + 1], texture_data[idx + 2] };
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string fname;
|
||||||
|
pointcloud _pc;
|
||||||
|
};
|
||||||
|
|
||||||
|
class save_single_frameset : public filter {
|
||||||
|
public:
|
||||||
|
save_single_frameset(std::string filename = "RealSense Frameset ")
|
||||||
|
: filter([this](frame f, frame_source& s) { save(f, s); }), fname(filename)
|
||||||
|
{}
|
||||||
|
|
||||||
|
private:
|
||||||
|
void save(frame data, frame_source& source, bool do_signal=true)
|
||||||
|
{
|
||||||
|
software_device dev;
|
||||||
|
|
||||||
|
std::vector<std::tuple<software_sensor, stream_profile, int>> sensors;
|
||||||
|
std::vector<std::tuple<stream_profile, stream_profile>> extrinsics;
|
||||||
|
|
||||||
|
if (auto fs = data.as<frameset>()) {
|
||||||
|
for (int i = 0; size_t(i) < fs.size(); ++i) {
|
||||||
|
frame f = fs[i];
|
||||||
|
auto profile = f.get_profile();
|
||||||
|
std::stringstream sname;
|
||||||
|
sname << "Sensor (" << i << ")";
|
||||||
|
auto s = dev.add_sensor(sname.str());
|
||||||
|
stream_profile software_profile;
|
||||||
|
|
||||||
|
if (auto vf = f.as<video_frame>()) {
|
||||||
|
auto vp = profile.as<video_stream_profile>();
|
||||||
|
rs2_video_stream stream{ vp.stream_type(), vp.stream_index(), i, vp.width(), vp.height(), vp.fps(), vf.get_bytes_per_pixel(), vp.format(), vp.get_intrinsics() };
|
||||||
|
software_profile = s.add_video_stream(stream);
|
||||||
|
if (f.is<rs2::depth_frame>()) {
|
||||||
|
auto ds = sensor_from_frame(f)->as<rs2::depth_sensor>();
|
||||||
|
s.add_read_only_option(RS2_OPTION_DEPTH_UNITS, ds.get_option(RS2_OPTION_DEPTH_UNITS));
|
||||||
|
}
|
||||||
|
} else if (f.is<motion_frame>()) {
|
||||||
|
auto mp = profile.as<motion_stream_profile>();
|
||||||
|
rs2_motion_stream stream{ mp.stream_type(), mp.stream_index(), i, mp.fps(), mp.format(), mp.get_motion_intrinsics() };
|
||||||
|
software_profile = s.add_motion_stream(stream);
|
||||||
|
} else if (f.is<pose_frame>()) {
|
||||||
|
rs2_pose_stream stream{ profile.stream_type(), profile.stream_index(), i, profile.fps(), profile.format() };
|
||||||
|
software_profile = s.add_pose_stream(stream);
|
||||||
|
} else {
|
||||||
|
// TODO: How to handle other frame types? (e.g. points)
|
||||||
|
assert(false);
|
||||||
|
}
|
||||||
|
sensors.emplace_back(s, software_profile, i);
|
||||||
|
|
||||||
|
bool found_extrin = false;
|
||||||
|
for (auto& root : extrinsics) {
|
||||||
|
try {
|
||||||
|
std::get<0>(root).register_extrinsics_to(software_profile,
|
||||||
|
std::get<1>(root).get_extrinsics_to(profile)
|
||||||
|
);
|
||||||
|
found_extrin = true;
|
||||||
|
break;
|
||||||
|
} catch (...) {}
|
||||||
|
}
|
||||||
|
if (!found_extrin) {
|
||||||
|
extrinsics.emplace_back(software_profile, profile);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Recorder needs sensors to already exist when its created
|
||||||
|
std::stringstream name;
|
||||||
|
name << fname << data.get_frame_number() << ".bag";
|
||||||
|
recorder rec(name.str(), dev);
|
||||||
|
|
||||||
|
for (auto group : sensors) {
|
||||||
|
auto s = std::get<0>(group);
|
||||||
|
auto profile = std::get<1>(group);
|
||||||
|
s.open(profile);
|
||||||
|
s.start([](frame) {});
|
||||||
|
frame f = fs[std::get<2>(group)];
|
||||||
|
if (auto vf = f.as<video_frame>()) {
|
||||||
|
s.on_video_frame({ const_cast<void*>(vf.get_data()), [](void*) {}, vf.get_stride_in_bytes(), vf.get_bytes_per_pixel(),
|
||||||
|
vf.get_timestamp(), vf.get_frame_timestamp_domain(), static_cast<int>(vf.get_frame_number()), profile });
|
||||||
|
} else if (f.is<motion_frame>()) {
|
||||||
|
s.on_motion_frame({ const_cast<void*>(f.get_data()), [](void*) {}, f.get_timestamp(),
|
||||||
|
f.get_frame_timestamp_domain(), static_cast<int>(f.get_frame_number()), profile });
|
||||||
|
} else if (f.is<pose_frame>()) {
|
||||||
|
s.on_pose_frame({ const_cast<void*>(f.get_data()), [](void*) {}, f.get_timestamp(),
|
||||||
|
f.get_frame_timestamp_domain(), static_cast<int>(f.get_frame_number()), profile });
|
||||||
|
}
|
||||||
|
s.stop();
|
||||||
|
s.close();
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// single frame
|
||||||
|
auto set = source.allocate_composite_frame({ data });
|
||||||
|
save(set, source, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (do_signal)
|
||||||
|
source.frame_ready(data);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string fname;
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,631 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_INTERNAL_HPP
|
||||||
|
#define LIBREALSENSE_RS2_INTERNAL_HPP
|
||||||
|
|
||||||
|
#include "rs_types.hpp"
|
||||||
|
#include "rs_device.hpp"
|
||||||
|
#include "rs_context.hpp"
|
||||||
|
#include "../h/rs_internal.h"
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
class recording_context : public context
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
/**
|
||||||
|
* create librealsense context that will try to record all operations over librealsense into a file
|
||||||
|
* \param[in] filename string representing the name of the file to record
|
||||||
|
*/
|
||||||
|
recording_context(const std::string& filename,
|
||||||
|
const std::string& section = "",
|
||||||
|
rs2_recording_mode mode = RS2_RECORDING_MODE_BLANK_FRAMES)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_context = std::shared_ptr<rs2_context>(
|
||||||
|
rs2_create_recording_context(RS2_API_VERSION, filename.c_str(), section.c_str(), mode, &e),
|
||||||
|
rs2_delete_context);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
recording_context() = delete;
|
||||||
|
};
|
||||||
|
|
||||||
|
class mock_context : public context
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
/**
|
||||||
|
* create librealsense context that given a file will respond to calls exactly as the recording did
|
||||||
|
* if the user calls a method that was either not called during recording or violates causality of the recording error will be thrown
|
||||||
|
* \param[in] filename string of the name of the file
|
||||||
|
*/
|
||||||
|
mock_context(const std::string& filename,
|
||||||
|
const std::string& section = "",
|
||||||
|
const std::string& min_api_version = "0.0.0")
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_context = std::shared_ptr<rs2_context>(
|
||||||
|
rs2_create_mock_context_versioned(RS2_API_VERSION, filename.c_str(), section.c_str(), min_api_version.c_str(), &e),
|
||||||
|
rs2_delete_context);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
mock_context() = delete;
|
||||||
|
};
|
||||||
|
|
||||||
|
namespace internal
|
||||||
|
{
|
||||||
|
/**
|
||||||
|
* \return the time at specific time point, in live and redord contextes it will return the system time and in playback contextes it will return the recorded time
|
||||||
|
*/
|
||||||
|
inline double get_time()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto time = rs2_get_time( &e);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return time;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
class software_device_destruction_callback : public rs2_software_device_destruction_callback
|
||||||
|
{
|
||||||
|
T on_destruction_function;
|
||||||
|
public:
|
||||||
|
explicit software_device_destruction_callback(T on_destruction) : on_destruction_function(on_destruction) {}
|
||||||
|
|
||||||
|
void on_destruction() override
|
||||||
|
{
|
||||||
|
on_destruction_function();
|
||||||
|
}
|
||||||
|
|
||||||
|
void release() override { delete this; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class software_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
/**
|
||||||
|
* Add video stream to software sensor
|
||||||
|
*
|
||||||
|
* \param[in] video_stream all the parameters that required to defind video stream
|
||||||
|
*/
|
||||||
|
stream_profile add_video_stream(rs2_video_stream video_stream, bool is_default=false)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
auto profile = rs2_software_sensor_add_video_stream_ex(_sensor.get(), video_stream, is_default, &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
stream_profile stream(profile);
|
||||||
|
return stream;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add motion stream to software sensor
|
||||||
|
*
|
||||||
|
* \param[in] motion all the parameters that required to defind motion stream
|
||||||
|
*/
|
||||||
|
stream_profile add_motion_stream(rs2_motion_stream motion_stream, bool is_default=false)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
auto profile = rs2_software_sensor_add_motion_stream_ex(_sensor.get(), motion_stream, is_default, &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
stream_profile stream(profile);
|
||||||
|
return stream;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add pose stream to software sensor
|
||||||
|
*
|
||||||
|
* \param[in] pose all the parameters that required to defind pose stream
|
||||||
|
*/
|
||||||
|
stream_profile add_pose_stream(rs2_pose_stream pose_stream, bool is_default=false)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
auto profile = rs2_software_sensor_add_pose_stream_ex(_sensor.get(), pose_stream, is_default, &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
stream_profile stream(profile);
|
||||||
|
return stream;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Inject video frame into the sensor
|
||||||
|
*
|
||||||
|
* \param[in] frame all the parameters that required to define video frame
|
||||||
|
*/
|
||||||
|
void on_video_frame(rs2_software_video_frame frame)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_sensor_on_video_frame(_sensor.get(), frame, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Inject motion frame into the sensor
|
||||||
|
*
|
||||||
|
* \param[in] frame all the parameters that required to define motion frame
|
||||||
|
*/
|
||||||
|
void on_motion_frame(rs2_software_motion_frame frame)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_sensor_on_motion_frame(_sensor.get(), frame, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Inject pose frame into the sensor
|
||||||
|
*
|
||||||
|
* \param[in] frame all the parameters that required to define pose frame
|
||||||
|
*/
|
||||||
|
void on_pose_frame(rs2_software_pose_frame frame)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_sensor_on_pose_frame(_sensor.get(), frame, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set frame metadata for the upcoming frames
|
||||||
|
* \param[in] value metadata key to set
|
||||||
|
* \param[in] type metadata value
|
||||||
|
*/
|
||||||
|
void set_metadata(rs2_frame_metadata_value value, rs2_metadata_type type)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_sensor_set_metadata(_sensor.get(), value, type, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Register read-only option that will be supported by the sensor
|
||||||
|
*
|
||||||
|
* \param[in] option the option
|
||||||
|
* \param[in] val the initial value
|
||||||
|
*/
|
||||||
|
void add_read_only_option(rs2_option option, float val)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_sensor_add_read_only_option(_sensor.get(), option, val, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update value of registered read-only option
|
||||||
|
*
|
||||||
|
* \param[in] option the option
|
||||||
|
* \param[in] val the initial value
|
||||||
|
*/
|
||||||
|
void set_read_only_option(rs2_option option, float val)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_sensor_update_read_only_option(_sensor.get(), option, val, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* Register option that will be supported by the sensor
|
||||||
|
*
|
||||||
|
* \param[in] option the option
|
||||||
|
* \param[in] range range data for the option. range.def will be used as the initial value
|
||||||
|
*/
|
||||||
|
void add_option(rs2_option option, const option_range& range, bool is_writable=true)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_sensor_add_option(_sensor.get(), option, range.min,
|
||||||
|
range.max, range.step, range.def, is_writable, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
void on_notification(rs2_software_notification notif)
|
||||||
|
{
|
||||||
|
rs2_error * e = nullptr;
|
||||||
|
rs2_software_sensor_on_notification(_sensor.get(), notif, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* Sensors hold the parent device in scope via a shared_ptr. This function detaches that so that the
|
||||||
|
* software sensor doesn't keep the software device alive. Note that this is dangerous as it opens the
|
||||||
|
* door to accessing freed memory if care isn't taken.
|
||||||
|
*/
|
||||||
|
void detach()
|
||||||
|
{
|
||||||
|
rs2_error * e = nullptr;
|
||||||
|
rs2_software_sensor_detach(_sensor.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
friend class software_device;
|
||||||
|
|
||||||
|
software_sensor(std::shared_ptr<rs2_sensor> s)
|
||||||
|
: rs2::sensor(s)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_SOFTWARE_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor = nullptr;
|
||||||
|
}
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
class software_device : public device
|
||||||
|
{
|
||||||
|
std::shared_ptr<rs2_device> create_device_ptr(std::function<void(rs2_device*)> deleter)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_device> dev(
|
||||||
|
rs2_create_software_device(&e),
|
||||||
|
deleter);
|
||||||
|
error::handle(e);
|
||||||
|
return dev;
|
||||||
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
software_device(std::function<void(rs2_device*)> deleter = &rs2_delete_device)
|
||||||
|
: device(create_device_ptr(deleter))
|
||||||
|
{
|
||||||
|
this->set_destruction_callback([]{});
|
||||||
|
}
|
||||||
|
|
||||||
|
software_device(std::string name)
|
||||||
|
: device(create_device_ptr(&rs2_delete_device))
|
||||||
|
{
|
||||||
|
update_info(RS2_CAMERA_INFO_NAME, name);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add software sensor with given name to the software device.
|
||||||
|
*
|
||||||
|
* \param[in] name the name of the sensor
|
||||||
|
*/
|
||||||
|
software_sensor add_sensor(std::string name)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_sensor> sensor(
|
||||||
|
rs2_software_device_add_sensor(_dev.get(), name.c_str(), &e),
|
||||||
|
rs2_delete_sensor);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return software_sensor(sensor);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Register destruction callback
|
||||||
|
* \param[in] callback destruction callback
|
||||||
|
*/
|
||||||
|
template<class T>
|
||||||
|
void set_destruction_callback(T callback) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_device_set_destruction_callback_cpp(_dev.get(),
|
||||||
|
new software_device_destruction_callback<T>(std::move(callback)), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add software device to existing context.
|
||||||
|
* Any future queries on the context will return this device.
|
||||||
|
* This operation cannot be undone (except for destroying the context)
|
||||||
|
*
|
||||||
|
* \param[in] ctx context to add the device to
|
||||||
|
*/
|
||||||
|
void add_to(context& ctx)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_context_add_software_device(ctx._context.get(), _dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add a new camera info value, like serial number
|
||||||
|
*
|
||||||
|
* \param[in] info Identifier of the camera info type
|
||||||
|
* \param[in] val string value to set to this camera info type
|
||||||
|
*/
|
||||||
|
void register_info(rs2_camera_info info, const std::string& val)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_device_register_info(_dev.get(), info, val.c_str(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Update an existing camera info value, like serial number
|
||||||
|
*
|
||||||
|
* \param[in] info Identifier of the camera info type
|
||||||
|
* \param[in] val string value to set to this camera info type
|
||||||
|
*/
|
||||||
|
void update_info(rs2_camera_info info, const std::string& val)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_device_update_info(_dev.get(), info, val.c_str(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the wanted matcher type that will be used by the syncer
|
||||||
|
* \param[in] matcher matcher type
|
||||||
|
*/
|
||||||
|
void create_matcher(rs2_matchers matcher)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_software_device_create_matcher(_dev.get(), matcher, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class firmware_log_message
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit firmware_log_message(std::shared_ptr<rs2_firmware_log_message> msg) :
|
||||||
|
_fw_log_message(msg) {}
|
||||||
|
|
||||||
|
rs2_log_severity get_severity() const {
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_log_severity severity = rs2_fw_log_message_severity(_fw_log_message.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return severity;
|
||||||
|
}
|
||||||
|
std::string get_severity_str() const {
|
||||||
|
return rs2_log_severity_to_string(get_severity());
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t get_timestamp() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
uint32_t timestamp = rs2_fw_log_message_timestamp(_fw_log_message.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return timestamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
int size() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
int size = rs2_fw_log_message_size(_fw_log_message.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return size;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<uint8_t> data() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto size = rs2_fw_log_message_size(_fw_log_message.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
std::vector<uint8_t> result;
|
||||||
|
if (size > 0)
|
||||||
|
{
|
||||||
|
auto start = rs2_fw_log_message_data(_fw_log_message.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
result.insert(result.begin(), start, start + size);
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::shared_ptr<rs2_firmware_log_message> get_message() const { return _fw_log_message; }
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::shared_ptr<rs2_firmware_log_message> _fw_log_message;
|
||||||
|
};
|
||||||
|
|
||||||
|
class firmware_log_parsed_message
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit firmware_log_parsed_message(std::shared_ptr<rs2_firmware_log_parsed_message> msg) :
|
||||||
|
_parsed_fw_log(msg) {}
|
||||||
|
|
||||||
|
std::string message() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e));
|
||||||
|
error::handle(e);
|
||||||
|
return msg;
|
||||||
|
}
|
||||||
|
std::string file_name() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e));
|
||||||
|
error::handle(e);
|
||||||
|
return file_name;
|
||||||
|
}
|
||||||
|
std::string thread_name() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e));
|
||||||
|
error::handle(e);
|
||||||
|
return thread_name;
|
||||||
|
}
|
||||||
|
std::string severity() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return std::string(rs2_log_severity_to_string(sev));
|
||||||
|
}
|
||||||
|
uint32_t line() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e));
|
||||||
|
error::handle(e);
|
||||||
|
return line;
|
||||||
|
}
|
||||||
|
uint32_t timestamp() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e));
|
||||||
|
error::handle(e);
|
||||||
|
return timestamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t sequence_id() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
uint32_t sequence(rs2_get_fw_log_parsed_sequence_id(_parsed_fw_log.get(), &e));
|
||||||
|
error::handle(e);
|
||||||
|
return sequence;
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::shared_ptr<rs2_firmware_log_parsed_message> get_message() const { return _parsed_fw_log; }
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::shared_ptr<rs2_firmware_log_parsed_message> _parsed_fw_log;
|
||||||
|
};
|
||||||
|
|
||||||
|
class firmware_logger : public device
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
firmware_logger(device d)
|
||||||
|
: device(d.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_FW_LOGGER, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_dev.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
rs2::firmware_log_message create_message()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_firmware_log_message> msg(
|
||||||
|
rs2_create_fw_log_message(_dev.get(), &e),
|
||||||
|
rs2_delete_fw_log_message);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return firmware_log_message(msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
rs2::firmware_log_parsed_message create_parsed_message()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_firmware_log_parsed_message> msg(
|
||||||
|
rs2_create_fw_log_parsed_message(_dev.get(), &e),
|
||||||
|
rs2_delete_fw_log_parsed_message);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return firmware_log_parsed_message(msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool get_firmware_log(rs2::firmware_log_message& msg) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_firmware_log_message* m = msg.get_message().get();
|
||||||
|
bool fw_log_pulling_status =
|
||||||
|
!!rs2_get_fw_log(_dev.get(), m, &e);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return fw_log_pulling_status;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool get_flash_log(rs2::firmware_log_message& msg) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_firmware_log_message* m = msg.get_message().get();
|
||||||
|
bool flash_log_pulling_status =
|
||||||
|
!!rs2_get_flash_log(_dev.get(), m, &e);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return flash_log_pulling_status;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool init_parser(const std::string& xml_content)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
bool parser_initialized = !!rs2_init_fw_log_parser(_dev.get(), xml_content.c_str(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return parser_initialized;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool parse_log(const rs2::firmware_log_message& msg, const rs2::firmware_log_parsed_message& parsed_msg)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
bool parsingResult = !!rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), parsed_msg.get_message().get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return parsingResult;
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned int get_number_of_fw_logs() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
unsigned int num_of_fw_logs = rs2_get_number_of_fw_logs(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return num_of_fw_logs;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class terminal_parser
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
terminal_parser(const std::string& xml_content)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
_terminal_parser = std::shared_ptr<rs2_terminal_parser>(
|
||||||
|
rs2_create_terminal_parser(xml_content.c_str(), &e),
|
||||||
|
rs2_delete_terminal_parser);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<uint8_t> parse_command(const std::string& command)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
std::shared_ptr<const rs2_raw_data_buffer> list(
|
||||||
|
rs2_terminal_parse_command(_terminal_parser.get(), command.c_str(), (unsigned int)command.size(), &e),
|
||||||
|
rs2_delete_raw_data);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto size = rs2_get_raw_data_size(list.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto start = rs2_get_raw_data(list.get(), &e);
|
||||||
|
|
||||||
|
std::vector<uint8_t> results;
|
||||||
|
results.insert(results.begin(), start, start + size);
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string parse_response(const std::string& command, const std::vector<uint8_t>& response)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
std::shared_ptr<const rs2_raw_data_buffer> list(
|
||||||
|
rs2_terminal_parse_response(_terminal_parser.get(), command.c_str(), (unsigned int)command.size(),
|
||||||
|
(void*)response.data(), (unsigned int)response.size(), &e),
|
||||||
|
rs2_delete_raw_data);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto size = rs2_get_raw_data_size(list.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto start = rs2_get_raw_data(list.get(), &e);
|
||||||
|
|
||||||
|
std::string results;
|
||||||
|
results.insert(results.begin(), start, start + size);
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::shared_ptr<rs2_terminal_parser> _terminal_parser;
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
#endif // LIBREALSENSE_RS2_INTERNAL_HPP
|
|
@ -0,0 +1,159 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2019 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_OPTIONS_HPP
|
||||||
|
#define LIBREALSENSE_RS2_OPTIONS_HPP
|
||||||
|
|
||||||
|
#include "rs_types.hpp"
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
class options
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
/**
|
||||||
|
* check if particular option is supported
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \return true if option is supported
|
||||||
|
*/
|
||||||
|
bool supports(rs2_option option) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_supports_option(_options, option, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get option description
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \return human-readable option description
|
||||||
|
*/
|
||||||
|
const char* get_option_description(rs2_option option) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_option_description(_options, option, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get option name
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \return human-readable option name
|
||||||
|
*/
|
||||||
|
const char* get_option_name(rs2_option option) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_option_name(_options, option, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get option value description (in case specific option value hold special meaning)
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \param[in] val value of the option
|
||||||
|
* \return human-readable description of a specific value of an option or null if no special meaning
|
||||||
|
*/
|
||||||
|
const char* get_option_value_description(rs2_option option, float val) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_option_value_description(_options, option, val, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* read option's value
|
||||||
|
* \param[in] option option id to be queried
|
||||||
|
* \return value of the option
|
||||||
|
*/
|
||||||
|
float get_option(rs2_option option) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_option(_options, option, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve the available range of values of a supported option
|
||||||
|
* \return option range containing minimum and maximum values, step and default value
|
||||||
|
*/
|
||||||
|
option_range get_option_range(rs2_option option) const
|
||||||
|
{
|
||||||
|
option_range result;
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_get_option_range(_options, option,
|
||||||
|
&result.min, &result.max, &result.step, &result.def, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* write new value to the option
|
||||||
|
* \param[in] option option id to be queried
|
||||||
|
* \param[in] value new value for the option
|
||||||
|
*/
|
||||||
|
void set_option(rs2_option option, float value) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_option(_options, option, value, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if particular option is read-only
|
||||||
|
* \param[in] option option id to be checked
|
||||||
|
* \return true if option is read-only
|
||||||
|
*/
|
||||||
|
bool is_option_read_only(rs2_option option) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_is_option_read_only(_options, option, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<rs2_option> get_supported_options()
|
||||||
|
{
|
||||||
|
std::vector<rs2_option> res;
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_options_list> options_list(
|
||||||
|
rs2_get_options_list(_options, &e),
|
||||||
|
rs2_delete_options_list);
|
||||||
|
|
||||||
|
for (auto opt = 0; opt < rs2_get_options_list_size(options_list.get(), &e);opt++)
|
||||||
|
{
|
||||||
|
res.push_back(rs2_get_option_from_list(options_list.get(), opt, &e));
|
||||||
|
}
|
||||||
|
return res;
|
||||||
|
};
|
||||||
|
|
||||||
|
options& operator=(const options& other)
|
||||||
|
{
|
||||||
|
_options = other._options;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
// if operator= is ok, this should be ok too
|
||||||
|
options(const options& other) : _options(other._options) {}
|
||||||
|
|
||||||
|
virtual ~options() = default;
|
||||||
|
protected:
|
||||||
|
explicit options(rs2_options* o = nullptr) : _options(o)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
options& operator=(const T& dev)
|
||||||
|
{
|
||||||
|
_options = (rs2_options*)(dev.get());
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
rs2_options* _options;
|
||||||
|
};
|
||||||
|
}
|
||||||
|
#endif // LIBREALSENSE_RS2_OIPTIONS_HPP
|
|
@ -0,0 +1,593 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_PIPELINE_HPP
|
||||||
|
#define LIBREALSENSE_RS2_PIPELINE_HPP
|
||||||
|
|
||||||
|
#include "rs_types.hpp"
|
||||||
|
#include "rs_frame.hpp"
|
||||||
|
#include "rs_context.hpp"
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
/**
|
||||||
|
* The pipeline profile includes a device and a selection of active streams, with specific profiles.
|
||||||
|
* The profile is a selection of the above under filters and conditions defined by the pipeline.
|
||||||
|
* Streams may belong to more than one sensor of the device.
|
||||||
|
*/
|
||||||
|
class pipeline_profile
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
pipeline_profile() : _pipeline_profile(nullptr) {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return the selected streams profiles, which are enabled in this profile.
|
||||||
|
*
|
||||||
|
* \return Vector of stream profiles
|
||||||
|
*/
|
||||||
|
std::vector<stream_profile> get_streams() const
|
||||||
|
{
|
||||||
|
std::vector<stream_profile> results;
|
||||||
|
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_stream_profile_list> list(
|
||||||
|
rs2_pipeline_profile_get_streams(_pipeline_profile.get(), &e),
|
||||||
|
rs2_delete_stream_profiles_list);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto size = rs2_get_stream_profiles_count(list.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
for (auto i = 0; i < size; i++)
|
||||||
|
{
|
||||||
|
stream_profile profile(rs2_get_stream_profile(list.get(), i, &e));
|
||||||
|
error::handle(e);
|
||||||
|
results.push_back(profile);
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return the stream profile that is enabled for the specified stream in this profile.
|
||||||
|
*
|
||||||
|
* \param[in] stream_type Stream type of the desired profile
|
||||||
|
* \param[in] stream_index Stream index of the desired profile. -1 for any matching.
|
||||||
|
* \return The first matching stream profile
|
||||||
|
*/
|
||||||
|
|
||||||
|
stream_profile get_stream(rs2_stream stream_type, int stream_index = -1) const
|
||||||
|
{
|
||||||
|
for (auto&& s : get_streams())
|
||||||
|
{
|
||||||
|
if (s.stream_type() == stream_type && (stream_index == -1 || s.stream_index() == stream_index))
|
||||||
|
{
|
||||||
|
return s;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
throw std::runtime_error("Profile does not contain the requested stream");
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve the device used by the pipeline.
|
||||||
|
* The device class provides the application access to control camera additional settings -
|
||||||
|
* get device information, sensor options information, options value query and set, sensor specific extensions.
|
||||||
|
* Since the pipeline controls the device streams configuration, activation state and frames reading, calling
|
||||||
|
* the device API functions, which execute those operations, results in unexpected behavior.
|
||||||
|
* The pipeline streaming device is selected during pipeline \c start(). Devices of profiles, which are not returned by
|
||||||
|
* pipeline \c start() or \c get_active_profile(), are not guaranteed to be used by the pipeline.
|
||||||
|
*
|
||||||
|
* \return rs2::device The pipeline selected device
|
||||||
|
*/
|
||||||
|
device get_device() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_device> dev(
|
||||||
|
rs2_pipeline_profile_get_device(_pipeline_profile.get(), &e),
|
||||||
|
rs2_delete_device);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return device(dev);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Conversion to boolean value to test for the object's validity
|
||||||
|
*
|
||||||
|
* \return true iff the profile is valid
|
||||||
|
*/
|
||||||
|
operator bool() const
|
||||||
|
{
|
||||||
|
return _pipeline_profile != nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
explicit operator std::shared_ptr<rs2_pipeline_profile>() { return _pipeline_profile; }
|
||||||
|
pipeline_profile(std::shared_ptr<rs2_pipeline_profile> profile) :
|
||||||
|
_pipeline_profile(profile){}
|
||||||
|
private:
|
||||||
|
|
||||||
|
std::shared_ptr<rs2_pipeline_profile> _pipeline_profile;
|
||||||
|
friend class config;
|
||||||
|
friend class pipeline;
|
||||||
|
};
|
||||||
|
|
||||||
|
class pipeline;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The config allows pipeline users to request filters for the pipeline streams and device selection and configuration.
|
||||||
|
* This is an optional step in pipeline creation, as the pipeline resolves its streaming device internally.
|
||||||
|
* Config provides its users a way to set the filters and test if there is no conflict with the pipeline requirements
|
||||||
|
* from the device. It also allows the user to find a matching device for the config filters and the pipeline, in order to
|
||||||
|
* select a device explicitly, and modify its controls before streaming starts.
|
||||||
|
*/
|
||||||
|
class config
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
config()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_config = std::shared_ptr<rs2_config>(
|
||||||
|
rs2_create_config(&e),
|
||||||
|
rs2_delete_config);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable a device stream explicitly, with selected stream parameters.
|
||||||
|
* The method allows the application to request a stream with specific configuration. If no stream is explicitly enabled,
|
||||||
|
* the pipeline configures the device and its streams according to the attached computer vision modules and processing
|
||||||
|
* blocks requirements, or default configuration for the first available device.
|
||||||
|
* The application can configure any of the input stream parameters according to its requirement, or set to 0 for don't
|
||||||
|
* care value.
|
||||||
|
* The config accumulates the application calls for enable configuration methods, until the configuration is applied.
|
||||||
|
* Multiple enable stream calls for the same stream override each other, and the last call is maintained.
|
||||||
|
* Upon calling \c resolve(), the config checks for conflicts between the application configuration requests and the
|
||||||
|
* attached computer vision modules and processing blocks requirements, and fails if conflicts are found.
|
||||||
|
* Before \c resolve() is called, no conflict check is done.
|
||||||
|
*
|
||||||
|
* \param[in] stream_type Stream type to be enabled
|
||||||
|
* \param[in] stream_index Stream index, used for multiple streams of the same type. -1 indicates any.
|
||||||
|
* \param[in] width Stream image width - for images streams. 0 indicates any.
|
||||||
|
* \param[in] height Stream image height - for images streams. 0 indicates any.
|
||||||
|
* \param[in] format Stream data format - pixel format for images streams, of data type for other streams. RS2_FORMAT_ANY indicates any.
|
||||||
|
* \param[in] framerate Stream frames per second. 0 indicates any.
|
||||||
|
*/
|
||||||
|
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format = RS2_FORMAT_ANY, int framerate = 0)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_config_enable_stream(_config.get(), stream_type, stream_index, width, height, format, framerate, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stream type and possibly also stream index. Other parameters are resolved internally.
|
||||||
|
*
|
||||||
|
* \param[in] stream_type Stream type to be enabled
|
||||||
|
* \param[in] stream_index Stream index, used for multiple streams of the same type. -1 indicates any.
|
||||||
|
*/
|
||||||
|
void enable_stream(rs2_stream stream_type, int stream_index = -1)
|
||||||
|
{
|
||||||
|
enable_stream(stream_type, stream_index, 0, 0, RS2_FORMAT_ANY, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stream type and resolution, and possibly format and frame rate. Other parameters are resolved internally.
|
||||||
|
*
|
||||||
|
* \param[in] stream_type Stream type to be enabled
|
||||||
|
* \param[in] width Stream image width - for images streams. 0 indicates any.
|
||||||
|
* \param[in] height Stream image height - for images streams. 0 indicates any.
|
||||||
|
* \param[in] format Stream data format - pixel format for images streams, of data type for other streams. RS2_FORMAT_ANY indicates any.
|
||||||
|
* \param[in] framerate Stream frames per second. 0 indicates any.
|
||||||
|
*/
|
||||||
|
void enable_stream(rs2_stream stream_type, int width, int height, rs2_format format = RS2_FORMAT_ANY, int framerate = 0)
|
||||||
|
{
|
||||||
|
enable_stream(stream_type, -1, width, height, format, framerate);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stream type and format, and possibly frame rate. Other parameters are resolved internally.
|
||||||
|
*
|
||||||
|
* \param[in] stream_type Stream type to be enabled
|
||||||
|
* \param[in] format Stream data format - pixel format for images streams, of data type for other streams. RS2_FORMAT_ANY indicates any.
|
||||||
|
* \param[in] framerate Stream frames per second. 0 indicates any.
|
||||||
|
*/
|
||||||
|
void enable_stream(rs2_stream stream_type, rs2_format format, int framerate = 0)
|
||||||
|
{
|
||||||
|
enable_stream(stream_type, -1, 0, 0, format, framerate);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stream type, index, and format, and possibly framerate. Other parameters are resolved internally.
|
||||||
|
*
|
||||||
|
* \param[in] stream_type Stream type to be enabled
|
||||||
|
* \param[in] stream_index Stream index, used for multiple streams of the same type. -1 indicates any.
|
||||||
|
* \param[in] format Stream data format - pixel format for images streams, of data type for other streams. RS2_FORMAT_ANY indicates any.
|
||||||
|
* \param[in] framerate Stream frames per second. 0 indicates any.
|
||||||
|
*/
|
||||||
|
void enable_stream(rs2_stream stream_type, int stream_index, rs2_format format, int framerate = 0)
|
||||||
|
{
|
||||||
|
enable_stream(stream_type, stream_index, 0, 0, format, framerate);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable all device streams explicitly.
|
||||||
|
* The conditions and behavior of this method are similar to those of \c enable_stream().
|
||||||
|
* This filter enables all raw streams of the selected device. The device is either selected explicitly by the
|
||||||
|
* application, or by the pipeline requirements or default. The list of streams is device dependent.
|
||||||
|
*/
|
||||||
|
void enable_all_streams()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_config_enable_all_stream(_config.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Select a specific device explicitly by its serial number, to be used by the pipeline.
|
||||||
|
* The conditions and behavior of this method are similar to those of \c enable_stream().
|
||||||
|
* This method is required if the application needs to set device or sensor settings prior to pipeline streaming,
|
||||||
|
* to enforce the pipeline to use the configured device.
|
||||||
|
*
|
||||||
|
* \param[in] serial device serial number, as returned by RS2_CAMERA_INFO_SERIAL_NUMBER
|
||||||
|
*/
|
||||||
|
void enable_device(const std::string& serial)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_config_enable_device(_config.get(), serial.c_str(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Select a recorded device from a file, to be used by the pipeline through playback.
|
||||||
|
* The device available streams are as recorded to the file, and \c resolve() considers only this device and
|
||||||
|
* configuration as available.
|
||||||
|
* This request cannot be used if \c enable_record_to_file() is called for the current config, and vice versa.
|
||||||
|
*
|
||||||
|
* \param[in] file_name The playback file of the device
|
||||||
|
*/
|
||||||
|
void enable_device_from_file(const std::string& file_name, bool repeat_playback = true)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_config_enable_device_from_file_repeat_option(_config.get(), file_name.c_str(), repeat_playback, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Requires that the resolved device would be recorded to file.
|
||||||
|
* This request cannot be used if \c enable_device_from_file() is called for the current config, and vice versa.
|
||||||
|
* as available.
|
||||||
|
*
|
||||||
|
* \param[in] file_name The desired file for the output record
|
||||||
|
*/
|
||||||
|
void enable_record_to_file(const std::string& file_name)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_config_enable_record_to_file(_config.get(), file_name.c_str(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Disable a device stream explicitly, to remove any requests on this stream profile.
|
||||||
|
* The stream can still be enabled due to pipeline computer vision module request. This call removes any filter on the
|
||||||
|
* stream configuration.
|
||||||
|
*
|
||||||
|
* \param[in] stream Stream type, for which the filters are cleared
|
||||||
|
*/
|
||||||
|
void disable_stream(rs2_stream stream, int index = -1)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_config_disable_indexed_stream(_config.get(), stream, index, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Disable all device stream explicitly, to remove any requests on the streams profiles.
|
||||||
|
* The streams can still be enabled due to pipeline computer vision module request. This call removes any filter on the
|
||||||
|
* streams configuration.
|
||||||
|
*/
|
||||||
|
void disable_all_streams()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_config_disable_all_streams(_config.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Resolve the configuration filters, to find a matching device and streams profiles.
|
||||||
|
* The method resolves the user configuration filters for the device and streams, and combines them with the requirements
|
||||||
|
* of the computer vision modules and processing blocks attached to the pipeline. If there are no conflicts of requests,
|
||||||
|
* it looks for an available device, which can satisfy all requests, and selects the first matching streams configuration.
|
||||||
|
* In the absence of any request, the rs2::config selects the first available device and the first color and depth
|
||||||
|
* streams configuration.
|
||||||
|
* The pipeline profile selection during \c start() follows the same method. Thus, the selected profile is the same, if no
|
||||||
|
* change occurs to the available devices.
|
||||||
|
* Resolving the pipeline configuration provides the application access to the pipeline selected device for advanced
|
||||||
|
* control.
|
||||||
|
* The returned configuration is not applied to the device, so the application doesn't own the device sensors. However,
|
||||||
|
* the application can call \c enable_device(), to enforce the device returned by this method is selected by pipeline \c
|
||||||
|
* start(), and configure the device and sensors options or extensions before streaming starts.
|
||||||
|
*
|
||||||
|
* \param[in] p The pipeline for which the selected filters are applied
|
||||||
|
* \return A matching device and streams profile, which satisfies the filters and pipeline requests.
|
||||||
|
*/
|
||||||
|
pipeline_profile resolve(std::shared_ptr<rs2_pipeline> p) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto profile = std::shared_ptr<rs2_pipeline_profile>(
|
||||||
|
rs2_config_resolve(_config.get(), p.get(), &e),
|
||||||
|
rs2_delete_pipeline_profile);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
return pipeline_profile(profile);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if the config can resolve the configuration filters, to find a matching device and streams profiles.
|
||||||
|
* The resolution conditions are as described in \c resolve().
|
||||||
|
*
|
||||||
|
* \param[in] p The pipeline for which the selected filters are applied
|
||||||
|
* \return True if a valid profile selection exists, false if no selection can be found under the config filters and the available devices.
|
||||||
|
*/
|
||||||
|
bool can_resolve(std::shared_ptr<rs2_pipeline> p) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
int res = rs2_config_can_resolve(_config.get(), p.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res != 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_ptr<rs2_config> get() const
|
||||||
|
{
|
||||||
|
return _config;
|
||||||
|
}
|
||||||
|
explicit operator std::shared_ptr<rs2_config>() const
|
||||||
|
{
|
||||||
|
return _config;
|
||||||
|
}
|
||||||
|
|
||||||
|
config(std::shared_ptr<rs2_config> cfg) : _config(cfg) {}
|
||||||
|
private:
|
||||||
|
std::shared_ptr<rs2_config> _config;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The pipeline simplifies the user interaction with the device and computer vision processing modules.
|
||||||
|
* The class abstracts the camera configuration and streaming, and the vision modules triggering and threading.
|
||||||
|
* It lets the application focus on the computer vision output of the modules, or the device output data.
|
||||||
|
* The pipeline can manage computer vision modules, which are implemented as a processing blocks.
|
||||||
|
* The pipeline is the consumer of the processing block interface, while the application consumes the
|
||||||
|
* computer vision interface.
|
||||||
|
*/
|
||||||
|
class pipeline
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Create a pipeline for processing data from a single device.
|
||||||
|
* The caller can provide a context created by the application, usually for playback or testing purposes.
|
||||||
|
*
|
||||||
|
* \param[in] ctx The context allocated by the application. Using the platform context by default.
|
||||||
|
*/
|
||||||
|
pipeline(context ctx = context())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_pipeline = std::shared_ptr<rs2_pipeline>(
|
||||||
|
rs2_create_pipeline(ctx._context.get(), &e),
|
||||||
|
rs2_delete_pipeline);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming with its default configuration.
|
||||||
|
* The pipeline streaming loop captures samples from the device, and delivers them to the attached computer vision
|
||||||
|
* modules and processing blocks, according to each module requirements and threading model.
|
||||||
|
* During the loop execution, the application can access the camera streams by calling \c wait_for_frames() or
|
||||||
|
* \c poll_for_frames().
|
||||||
|
* The streaming loop runs until the pipeline is stopped.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
*
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
pipeline_profile start()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto p = std::shared_ptr<rs2_pipeline_profile>(
|
||||||
|
rs2_pipeline_start(_pipeline.get(), &e),
|
||||||
|
rs2_delete_pipeline_profile);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
return pipeline_profile(p);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming according to the configuraion.
|
||||||
|
* The pipeline streaming loop captures samples from the device, and delivers them to the attached computer vision modules
|
||||||
|
* and processing blocks, according to each module requirements and threading model.
|
||||||
|
* During the loop execution, the application can access the camera streams by calling \c wait_for_frames() or
|
||||||
|
* \c poll_for_frames().
|
||||||
|
* The streaming loop runs until the pipeline is stopped.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* The pipeline selects and activates the device upon start, according to configuration or a default configuration.
|
||||||
|
* When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result.
|
||||||
|
* If the application requests are conflicting with pipeline computer vision modules or no matching device is available on
|
||||||
|
* the platform, the method fails.
|
||||||
|
* Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices
|
||||||
|
* are connected or disconnected, or another application acquires ownership of a device.
|
||||||
|
*
|
||||||
|
* \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied.
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
pipeline_profile start(const config& config)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto p = std::shared_ptr<rs2_pipeline_profile>(
|
||||||
|
rs2_pipeline_start_with_config(_pipeline.get(), config.get().get(), &e),
|
||||||
|
rs2_delete_pipeline_profile);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
return pipeline_profile(p);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming with its default configuration.
|
||||||
|
* The pipeline captures samples from the device, and delivers them to the provided frame callback.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* When starting the pipeline with a callback both \c wait_for_frames() and \c poll_for_frames() will throw exception.
|
||||||
|
*
|
||||||
|
* \param[in] callback Stream callback, can be any callable object accepting rs2::frame
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
template<class S>
|
||||||
|
pipeline_profile start(S callback)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto p = std::shared_ptr<rs2_pipeline_profile>(
|
||||||
|
rs2_pipeline_start_with_callback_cpp(_pipeline.get(), new frame_callback<S>(callback), &e),
|
||||||
|
rs2_delete_pipeline_profile);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
return pipeline_profile(p);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the pipeline streaming according to the configuraion.
|
||||||
|
* The pipeline captures samples from the device, and delivers them to the provided frame callback.
|
||||||
|
* Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised.
|
||||||
|
* When starting the pipeline with a callback both \c wait_for_frames() and \c poll_for_frames() will throw exception.
|
||||||
|
* The pipeline selects and activates the device upon start, according to configuration or a default configuration.
|
||||||
|
* When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result.
|
||||||
|
* If the application requests are conflicting with pipeline computer vision modules or no matching device is available on
|
||||||
|
* the platform, the method fails.
|
||||||
|
* Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices
|
||||||
|
* are connected or disconnected, or another application acquires ownership of a device.
|
||||||
|
*
|
||||||
|
* \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied.
|
||||||
|
* \param[in] callback Stream callback, can be any callable object accepting rs2::frame
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device.
|
||||||
|
*/
|
||||||
|
template<class S>
|
||||||
|
pipeline_profile start(const config& config, S callback)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto p = std::shared_ptr<rs2_pipeline_profile>(
|
||||||
|
rs2_pipeline_start_with_config_and_callback_cpp(_pipeline.get(), config.get().get(), new frame_callback<S>(callback), &e),
|
||||||
|
rs2_delete_pipeline_profile);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
return pipeline_profile(p);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stop the pipeline streaming.
|
||||||
|
* The pipeline stops delivering samples to the attached computer vision modules and processing blocks, stops the device
|
||||||
|
* streaming and releases the device resources used by the pipeline. It is the application's responsibility to release any
|
||||||
|
* frame reference it owns.
|
||||||
|
* The method takes effect only after \c start() was called, otherwise an exception is raised.
|
||||||
|
*/
|
||||||
|
void stop()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_pipeline_stop(_pipeline.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Wait until a new set of frames becomes available.
|
||||||
|
* The frames set includes time-synchronized frames of each enabled stream in the pipeline.
|
||||||
|
* In case of different frame rates of the streams, the frames set include a matching frame of the slow stream,
|
||||||
|
* which may have been included in previous frames set.
|
||||||
|
* The method blocks the calling thread, and fetches the latest unread frames set.
|
||||||
|
* Device frames, which were produced while the function wasn't called, are dropped. To avoid frame drops, this method
|
||||||
|
* should be called as fast as the device frame rate.
|
||||||
|
* The application can maintain the frames handles to defer processing. However, if the application maintains too long
|
||||||
|
* history, the device may lack memory resources to produce new frames, and the following call to this method shall fail
|
||||||
|
* to retrieve new frames, until resources become available.
|
||||||
|
*
|
||||||
|
* \param[in] timeout_ms Max time in milliseconds to wait until an exception will be thrown
|
||||||
|
* \return Set of time synchronized frames, one from each active stream
|
||||||
|
*/
|
||||||
|
frameset wait_for_frames(unsigned int timeout_ms = RS2_DEFAULT_TIMEOUT) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
frame f(rs2_pipeline_wait_for_frames(_pipeline.get(), timeout_ms, &e));
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
return frameset(f);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if a new set of frames is available and retrieve the latest undelivered set.
|
||||||
|
* The frames set includes time-synchronized frames of each enabled stream in the pipeline.
|
||||||
|
* The method returns without blocking the calling thread, with status of new frames available or not.
|
||||||
|
* If available, it fetches the latest frames set.
|
||||||
|
* Device frames, which were produced while the function wasn't called, are dropped.
|
||||||
|
* To avoid frame drops, this method should be called as fast as the device frame rate.
|
||||||
|
* The application can maintain the frames handles to defer processing. However, if the application maintains too long
|
||||||
|
* history, the device may lack memory resources to produce new frames, and the following calls to this method shall
|
||||||
|
* return no new frames, until resources become available.
|
||||||
|
*
|
||||||
|
* \param[out] f Frames set handle
|
||||||
|
* \return True if new set of time synchronized frames was stored to f, false if no new frames set is available
|
||||||
|
*/
|
||||||
|
bool poll_for_frames(frameset* f) const
|
||||||
|
{
|
||||||
|
if (!f)
|
||||||
|
{
|
||||||
|
throw std::invalid_argument("null frameset");
|
||||||
|
}
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_frame* frame_ref = nullptr;
|
||||||
|
auto res = rs2_pipeline_poll_for_frames(_pipeline.get(), &frame_ref, &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
if (res) *f = frameset(frame(frame_ref));
|
||||||
|
return res > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool try_wait_for_frames(frameset* f, unsigned int timeout_ms = RS2_DEFAULT_TIMEOUT) const
|
||||||
|
{
|
||||||
|
if (!f)
|
||||||
|
{
|
||||||
|
throw std::invalid_argument("null frameset");
|
||||||
|
}
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_frame* frame_ref = nullptr;
|
||||||
|
auto res = rs2_pipeline_try_wait_for_frames(_pipeline.get(), &frame_ref, timeout_ms, &e);
|
||||||
|
error::handle(e);
|
||||||
|
if (res) *f = frameset(frame(frame_ref));
|
||||||
|
return res > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return the active device and streams profiles, used by the pipeline.
|
||||||
|
* The pipeline streams profiles are selected during \c start(). The method returns a valid result only when the pipeline is active -
|
||||||
|
* between calls to \c start() and \c stop().
|
||||||
|
* After \c stop() is called, the pipeline doesn't own the device, thus, the pipeline selected device may change in
|
||||||
|
* subsequent activations.
|
||||||
|
*
|
||||||
|
* \return The actual pipeline device and streams profile, which was successfully configured to the streaming device on start.
|
||||||
|
*/
|
||||||
|
pipeline_profile get_active_profile() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto p = std::shared_ptr<rs2_pipeline_profile>(
|
||||||
|
rs2_pipeline_get_active_profile(_pipeline.get(), &e),
|
||||||
|
rs2_delete_pipeline_profile);
|
||||||
|
|
||||||
|
error::handle(e);
|
||||||
|
return pipeline_profile(p);
|
||||||
|
}
|
||||||
|
|
||||||
|
operator std::shared_ptr<rs2_pipeline>() const
|
||||||
|
{
|
||||||
|
return _pipeline;
|
||||||
|
}
|
||||||
|
explicit pipeline(std::shared_ptr<rs2_pipeline> ptr) : _pipeline(ptr) {}
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::shared_ptr<rs2_pipeline> _pipeline;
|
||||||
|
friend class config;
|
||||||
|
};
|
||||||
|
}
|
||||||
|
#endif // LIBREALSENSE_RS2_PROCESSING_HPP
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,281 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_RECORD_PLAYBACK_HPP
|
||||||
|
#define LIBREALSENSE_RS2_RECORD_PLAYBACK_HPP
|
||||||
|
|
||||||
|
#include "rs_types.hpp"
|
||||||
|
#include "rs_device.hpp"
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
template<class T>
|
||||||
|
class status_changed_callback : public rs2_playback_status_changed_callback
|
||||||
|
{
|
||||||
|
T on_status_changed_function;
|
||||||
|
public:
|
||||||
|
explicit status_changed_callback(T on_status_changed) : on_status_changed_function(on_status_changed) {}
|
||||||
|
|
||||||
|
void on_playback_status_changed(rs2_playback_status status) override
|
||||||
|
{
|
||||||
|
on_status_changed_function(status);
|
||||||
|
}
|
||||||
|
|
||||||
|
void release() override { delete this; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class playback : public device
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
playback(device d) : playback(d.get()) {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Pauses the playback
|
||||||
|
* Calling pause() in "Paused" status does nothing
|
||||||
|
* If pause() is called while playback status is "Playing" or "Stopped", the playback will not play until resume() is called
|
||||||
|
*/
|
||||||
|
void pause()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_device_pause(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Un-pauses the playback
|
||||||
|
* Calling resume() while playback status is "Playing" or "Stopped" does nothing
|
||||||
|
*/
|
||||||
|
void resume()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_device_resume(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieves the name of the playback file
|
||||||
|
* \return Name of the playback file
|
||||||
|
*/
|
||||||
|
std::string file_name() const
|
||||||
|
{
|
||||||
|
return m_file; //cached in construction
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieves the current position of the playback in the file in terms of time. Units are expressed in nanoseconds
|
||||||
|
* \return Current position of the playback in the file in terms of time. Units are expressed in nanoseconds
|
||||||
|
*/
|
||||||
|
uint64_t get_position() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
uint64_t pos = rs2_playback_get_position(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieves the total duration of the file
|
||||||
|
* \return Total duration of the file
|
||||||
|
*/
|
||||||
|
std::chrono::nanoseconds get_duration() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::chrono::nanoseconds duration(rs2_playback_get_duration(_dev.get(), &e));
|
||||||
|
error::handle(e);
|
||||||
|
return duration;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sets the playback to a specified time point of the played data
|
||||||
|
* \param[in] time The time point to which playback should seek, expressed in units of nanoseconds (zero value = start)
|
||||||
|
*/
|
||||||
|
void seek(std::chrono::nanoseconds time)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_seek(_dev.get(), time.count(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Indicates if playback is in real time mode or non real time
|
||||||
|
* \return True iff playback is in real time mode
|
||||||
|
*/
|
||||||
|
bool is_real_time() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
bool real_time = rs2_playback_device_is_real_time(_dev.get(), &e) != 0;
|
||||||
|
error::handle(e);
|
||||||
|
return real_time;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the playback to work in real time or non real time
|
||||||
|
*
|
||||||
|
* In real time mode, playback will play the same way the file was recorded.
|
||||||
|
* In real time mode if the application takes too long to handle the callback, frames may be dropped.
|
||||||
|
* In non real time mode, playback will wait for each callback to finish handling the data before
|
||||||
|
* reading the next frame. In this mode no frames will be dropped, and the application controls the
|
||||||
|
* frame rate of the playback (according to the callback handler duration).
|
||||||
|
* \param[in] real_time Indicates if real time is requested, 0 means false, otherwise true
|
||||||
|
* \return True on successfully setting the requested mode
|
||||||
|
*/
|
||||||
|
void set_real_time(bool real_time) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_device_set_real_time(_dev.get(), (real_time ? 1 : 0), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the playing speed
|
||||||
|
* \param[in] speed Indicates a multiplication of the speed to play (e.g: 1 = normal, 0.5 twice as slow)
|
||||||
|
*/
|
||||||
|
void set_playback_speed(float speed) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_device_set_playback_speed(_dev.get(), speed, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start passing frames into user provided callback
|
||||||
|
* \param[in] callback Stream callback, can be any callable object accepting rs2::frame
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Register to receive callback from playback device upon its status changes
|
||||||
|
*
|
||||||
|
* Callbacks are invoked from the reading thread, and as such any heavy processing in the callback handler will affect
|
||||||
|
* the reading thread and may cause frame drops\ high latency
|
||||||
|
* \param[in] callback A callback handler that will be invoked when the playback status changes, can be any callable object accepting rs2_playback_status
|
||||||
|
*/
|
||||||
|
template <typename T>
|
||||||
|
void set_status_changed_callback(T callback)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_device_set_status_changed_callback(_dev.get(), new status_changed_callback<T>(std::move(callback)), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the current state of the playback device
|
||||||
|
* \return Current state of the playback
|
||||||
|
*/
|
||||||
|
rs2_playback_status current_status() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_status sts = rs2_playback_device_get_current_status(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return sts;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stops the playback, effectively stopping all streaming playback sensors, and resetting the playback.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void stop()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_playback_device_stop(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
protected:
|
||||||
|
friend context;
|
||||||
|
explicit playback(std::shared_ptr<rs2_device> dev) : device(dev)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if(rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_PLAYBACK, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_dev.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
if(_dev)
|
||||||
|
{
|
||||||
|
e = nullptr;
|
||||||
|
m_file = rs2_playback_device_get_file_path(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
private:
|
||||||
|
std::string m_file;
|
||||||
|
};
|
||||||
|
class recorder : public device
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
recorder(device d) : recorder(d.get()) {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a recording device to record the given device and save it to the given file as rosbag format
|
||||||
|
* \param[in] file The desired path to which the recorder should save the data
|
||||||
|
* \param[in] device The device to record
|
||||||
|
*/
|
||||||
|
recorder(const std::string& file, rs2::device dev)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_dev = std::shared_ptr<rs2_device>(
|
||||||
|
rs2_create_record_device(dev.get().get(), file.c_str(), &e),
|
||||||
|
rs2_delete_device);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a recording device to record the given device and save it to the given file as rosbag format
|
||||||
|
* \param[in] file The desired path to which the recorder should save the data
|
||||||
|
* \param[in] device The device to record
|
||||||
|
* \param[in] compression_enabled Indicates if compression is enabled
|
||||||
|
*/
|
||||||
|
recorder(const std::string& file, rs2::device dev, bool compression_enabled)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_dev = std::shared_ptr<rs2_device>(
|
||||||
|
rs2_create_record_device_ex(dev.get().get(), file.c_str(), compression_enabled, &e),
|
||||||
|
rs2_delete_device);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Pause the recording device without stopping the actual device from streaming.
|
||||||
|
*/
|
||||||
|
void pause()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_record_device_pause(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Unpauses the recording device, making it resume recording.
|
||||||
|
*/
|
||||||
|
void resume()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_record_device_resume(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the name of the file to which the recorder is writing
|
||||||
|
* \return The name of the file to which the recorder is writing
|
||||||
|
*/
|
||||||
|
std::string filename() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::string filename = rs2_record_device_filename(_dev.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return filename;
|
||||||
|
}
|
||||||
|
protected:
|
||||||
|
explicit recorder(std::shared_ptr<rs2_device> dev) : device(dev)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_RECORD, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_dev.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
#endif // LIBREALSENSE_RS2_RECORD_PLAYBACK_HPP
|
|
@ -0,0 +1,800 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_SENSOR_HPP
|
||||||
|
#define LIBREALSENSE_RS2_SENSOR_HPP
|
||||||
|
|
||||||
|
#include "rs_types.hpp"
|
||||||
|
#include "rs_frame.hpp"
|
||||||
|
#include "rs_processing.hpp"
|
||||||
|
#include "rs_options.hpp"
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
|
||||||
|
class notification
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
notification(rs2_notification* nt)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
_description = rs2_get_notification_description(nt, &e);
|
||||||
|
error::handle(e);
|
||||||
|
_timestamp = rs2_get_notification_timestamp(nt, &e);
|
||||||
|
error::handle(e);
|
||||||
|
_severity = rs2_get_notification_severity(nt, &e);
|
||||||
|
error::handle(e);
|
||||||
|
_category = rs2_get_notification_category(nt, &e);
|
||||||
|
error::handle(e);
|
||||||
|
_serialized_data = rs2_get_notification_serialized_data(nt, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
notification() = default;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve the notification category
|
||||||
|
* \return the notification category
|
||||||
|
*/
|
||||||
|
rs2_notification_category get_category() const
|
||||||
|
{
|
||||||
|
return _category;
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* retrieve the notification description
|
||||||
|
* \return the notification description
|
||||||
|
*/
|
||||||
|
std::string get_description() const
|
||||||
|
{
|
||||||
|
return _description;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve the notification arrival timestamp
|
||||||
|
* \return the arrival timestamp
|
||||||
|
*/
|
||||||
|
double get_timestamp() const
|
||||||
|
{
|
||||||
|
return _timestamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve the notification severity
|
||||||
|
* \return the severity
|
||||||
|
*/
|
||||||
|
rs2_log_severity get_severity() const
|
||||||
|
{
|
||||||
|
return _severity;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve the notification's serialized data
|
||||||
|
* \return the serialized data (in JSON format)
|
||||||
|
*/
|
||||||
|
std::string get_serialized_data() const
|
||||||
|
{
|
||||||
|
return _serialized_data;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::string _description;
|
||||||
|
double _timestamp = -1;
|
||||||
|
rs2_log_severity _severity = RS2_LOG_SEVERITY_COUNT;
|
||||||
|
rs2_notification_category _category = RS2_NOTIFICATION_CATEGORY_COUNT;
|
||||||
|
std::string _serialized_data;
|
||||||
|
};
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
class notifications_callback : public rs2_notifications_callback
|
||||||
|
{
|
||||||
|
T on_notification_function;
|
||||||
|
public:
|
||||||
|
explicit notifications_callback(T on_notification) : on_notification_function(on_notification) {}
|
||||||
|
|
||||||
|
void on_notification(rs2_notification* _notification) override
|
||||||
|
{
|
||||||
|
on_notification_function(notification{ _notification });
|
||||||
|
}
|
||||||
|
|
||||||
|
void release() override { delete this; }
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
class sensor : public options
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
using options::supports;
|
||||||
|
/**
|
||||||
|
* open sensor for exclusive access, by committing to a configuration
|
||||||
|
* \param[in] profile configuration committed by the sensor
|
||||||
|
*/
|
||||||
|
void open(const stream_profile& profile) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_open(_sensor.get(),
|
||||||
|
profile.get(),
|
||||||
|
&e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check if specific camera info is supported
|
||||||
|
* \param[in] info the parameter to check for support
|
||||||
|
* \return true if the parameter both exist and well-defined for the specific sensor
|
||||||
|
*/
|
||||||
|
bool supports(rs2_camera_info info) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto is_supported = rs2_supports_sensor_info(_sensor.get(), info, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return is_supported > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* retrieve camera specific information, like versions of various internal components
|
||||||
|
* \param[in] info camera info type to retrieve
|
||||||
|
* \return the requested camera info string, in a format specific to the sensor model
|
||||||
|
*/
|
||||||
|
const char* get_info(rs2_camera_info info) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto result = rs2_get_sensor_info(_sensor.get(), info, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* open sensor for exclusive access, by committing to composite configuration, specifying one or more stream profiles
|
||||||
|
* this method should be used for interdependent streams, such as depth and infrared, that have to be configured together
|
||||||
|
* \param[in] profiles vector of configurations to be commited by the sensor
|
||||||
|
*/
|
||||||
|
void open(const std::vector<stream_profile>& profiles) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
|
||||||
|
std::vector<const rs2_stream_profile*> profs;
|
||||||
|
profs.reserve(profiles.size());
|
||||||
|
for (auto& p : profiles)
|
||||||
|
{
|
||||||
|
profs.push_back(p.get());
|
||||||
|
}
|
||||||
|
|
||||||
|
rs2_open_multiple(_sensor.get(),
|
||||||
|
profs.data(),
|
||||||
|
static_cast<int>(profiles.size()),
|
||||||
|
&e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* close sensor for exclusive access
|
||||||
|
* this method should be used for releasing sensor resource
|
||||||
|
*/
|
||||||
|
void close() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_close(_sensor.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start passing frames into user provided callback
|
||||||
|
* \param[in] callback Stream callback, can be any callable object accepting rs2::frame
|
||||||
|
*/
|
||||||
|
template<class T>
|
||||||
|
void start(T callback) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_start_cpp(_sensor.get(), new frame_callback<T>(std::move(callback)), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* stop streaming
|
||||||
|
*/
|
||||||
|
void stop() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_stop(_sensor.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* register notifications callback
|
||||||
|
* \param[in] callback notifications callback
|
||||||
|
*/
|
||||||
|
template<class T>
|
||||||
|
void set_notifications_callback(T callback) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_notifications_callback_cpp(_sensor.get(),
|
||||||
|
new notifications_callback<T>(std::move(callback)), &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieves the list of stream profiles supported by the sensor.
|
||||||
|
* \return list of stream profiles that given sensor can provide
|
||||||
|
*/
|
||||||
|
std::vector<stream_profile> get_stream_profiles() const
|
||||||
|
{
|
||||||
|
std::vector<stream_profile> results{};
|
||||||
|
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_stream_profile_list> list(
|
||||||
|
rs2_get_stream_profiles(_sensor.get(), &e),
|
||||||
|
rs2_delete_stream_profiles_list);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto size = rs2_get_stream_profiles_count(list.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
for (auto i = 0; i < size; i++)
|
||||||
|
{
|
||||||
|
stream_profile profile(rs2_get_stream_profile(list.get(), i, &e));
|
||||||
|
error::handle(e);
|
||||||
|
results.push_back(profile);
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieves the list of stream profiles currently streaming on the sensor.
|
||||||
|
* \return list of stream profiles that given sensor is streaming
|
||||||
|
*/
|
||||||
|
std::vector<stream_profile> get_active_streams() const
|
||||||
|
{
|
||||||
|
std::vector<stream_profile> results{};
|
||||||
|
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_stream_profile_list> list(
|
||||||
|
rs2_get_active_streams(_sensor.get(), &e),
|
||||||
|
rs2_delete_stream_profiles_list);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto size = rs2_get_stream_profiles_count(list.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
for (auto i = 0; i < size; i++)
|
||||||
|
{
|
||||||
|
stream_profile profile(rs2_get_stream_profile(list.get(), i, &e));
|
||||||
|
error::handle(e);
|
||||||
|
results.push_back(profile);
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get the recommended list of filters by the sensor
|
||||||
|
* \return list of filters that recommended by sensor
|
||||||
|
*/
|
||||||
|
std::vector<filter> get_recommended_filters() const
|
||||||
|
{
|
||||||
|
std::vector<filter> results{};
|
||||||
|
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_processing_block_list> list(
|
||||||
|
rs2_get_recommended_processing_blocks(_sensor.get(), &e),
|
||||||
|
rs2_delete_recommended_processing_blocks);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
auto size = rs2_get_recommended_processing_blocks_count(list.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
for (auto i = 0; i < size; i++)
|
||||||
|
{
|
||||||
|
auto f = std::shared_ptr<rs2_processing_block>(
|
||||||
|
rs2_get_processing_block(list.get(), i, &e),
|
||||||
|
rs2_delete_processing_block);
|
||||||
|
error::handle(e);
|
||||||
|
results.push_back(f);
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
sensor& operator=(const std::shared_ptr<rs2_sensor> other)
|
||||||
|
{
|
||||||
|
options::operator=(other);
|
||||||
|
_sensor.reset();
|
||||||
|
_sensor = other;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
sensor& operator=(const sensor& other)
|
||||||
|
{
|
||||||
|
*this = nullptr;
|
||||||
|
options::operator=(other._sensor);
|
||||||
|
_sensor = other._sensor;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
sensor() : _sensor(nullptr) {}
|
||||||
|
|
||||||
|
operator bool() const
|
||||||
|
{
|
||||||
|
return _sensor != nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::shared_ptr<rs2_sensor>& get() const
|
||||||
|
{
|
||||||
|
return _sensor;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
bool is() const
|
||||||
|
{
|
||||||
|
T extension(*this);
|
||||||
|
return extension;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
T as() const
|
||||||
|
{
|
||||||
|
T extension(*this);
|
||||||
|
return extension;
|
||||||
|
}
|
||||||
|
|
||||||
|
explicit sensor(std::shared_ptr<rs2_sensor> dev)
|
||||||
|
:options((rs2_options*)dev.get()), _sensor(dev)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
explicit operator std::shared_ptr<rs2_sensor>() { return _sensor; }
|
||||||
|
|
||||||
|
protected:
|
||||||
|
friend context;
|
||||||
|
friend device_list;
|
||||||
|
friend device;
|
||||||
|
friend device_base;
|
||||||
|
friend roi_sensor;
|
||||||
|
|
||||||
|
std::shared_ptr<rs2_sensor> _sensor;
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
inline std::shared_ptr<sensor> sensor_from_frame(frame f)
|
||||||
|
{
|
||||||
|
std::shared_ptr<rs2_sensor> psens(f.get_sensor(), rs2_delete_sensor);
|
||||||
|
return std::make_shared<sensor>(psens);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const sensor& lhs, const sensor& rhs)
|
||||||
|
{
|
||||||
|
if (!(lhs.supports(RS2_CAMERA_INFO_NAME) && lhs.supports(RS2_CAMERA_INFO_SERIAL_NUMBER)
|
||||||
|
&& rhs.supports(RS2_CAMERA_INFO_NAME) && rhs.supports(RS2_CAMERA_INFO_SERIAL_NUMBER)))
|
||||||
|
return false;
|
||||||
|
|
||||||
|
return std::string(lhs.get_info(RS2_CAMERA_INFO_NAME)) == rhs.get_info(RS2_CAMERA_INFO_NAME)
|
||||||
|
&& std::string(lhs.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER)) == rhs.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER);
|
||||||
|
}
|
||||||
|
|
||||||
|
class color_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
color_sensor(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_COLOR_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class motion_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
motion_sensor(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_MOTION_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class fisheye_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
fisheye_sensor(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_FISHEYE_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class roi_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
roi_sensor(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if(rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_ROI, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_region_of_interest(const region_of_interest& roi)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_region_of_interest(_sensor.get(), roi.min_x, roi.min_y, roi.max_x, roi.max_y, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
region_of_interest get_region_of_interest() const
|
||||||
|
{
|
||||||
|
region_of_interest roi {};
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_get_region_of_interest(_sensor.get(), &roi.min_x, &roi.min_y, &roi.max_x, &roi.max_y, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return roi;
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class depth_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
depth_sensor(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_DEPTH_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Retrieves mapping between the units of the depth image and meters
|
||||||
|
* \return depth in meters corresponding to a depth value of 1
|
||||||
|
*/
|
||||||
|
float get_depth_scale() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_depth_scale(_sensor.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
explicit depth_sensor(std::shared_ptr<rs2_sensor> dev) : depth_sensor(sensor(dev)) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
class depth_stereo_sensor : public depth_sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
depth_stereo_sensor(sensor s): depth_sensor(s)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (_sensor && rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_DEPTH_STEREO_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve the stereoscopic baseline value from the sensor.
|
||||||
|
*/
|
||||||
|
float get_stereo_baseline() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_stereo_baseline(_sensor.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
class pose_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
pose_sensor(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_POSE_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Load relocalization map onto device. Only one relocalization map can be imported at a time;
|
||||||
|
* any previously existing map will be overwritten.
|
||||||
|
* The imported map exists simultaneously with the map created during the most recent tracking session after start(),
|
||||||
|
* and they are merged after the imported map is relocalized.
|
||||||
|
* This operation must be done before start().
|
||||||
|
* \param[in] lmap_buf map data as a binary blob
|
||||||
|
* \return true if success
|
||||||
|
*/
|
||||||
|
bool import_localization_map(const std::vector<uint8_t>& lmap_buf) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_import_localization_map(_sensor.get(), lmap_buf.data(), uint32_t(lmap_buf.size()), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return !!res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get relocalization map that is currently on device, created and updated during most recent tracking session.
|
||||||
|
* Can be called before or after stop().
|
||||||
|
* \return map data as a binary blob
|
||||||
|
*/
|
||||||
|
std::vector<uint8_t> export_localization_map() const
|
||||||
|
{
|
||||||
|
std::vector<uint8_t> results;
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
const rs2_raw_data_buffer *map = rs2_export_localization_map(_sensor.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
std::shared_ptr<const rs2_raw_data_buffer> loc_map(map, rs2_delete_raw_data);
|
||||||
|
|
||||||
|
auto start = rs2_get_raw_data(loc_map.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
if (start)
|
||||||
|
{
|
||||||
|
auto size = rs2_get_raw_data_size(loc_map.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
|
||||||
|
results = std::vector<uint8_t>(start, start + size);
|
||||||
|
}
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Creates a named virtual landmark in the current map, known as static node.
|
||||||
|
* The static node's pose is provided relative to the origin of current coordinate system of device poses.
|
||||||
|
* This function fails if the current tracker confidence is below 3 (high confidence).
|
||||||
|
* \param[in] guid unique name of the static node (limited to 127 chars).
|
||||||
|
* If a static node with the same name already exists in the current map or the imported map, the static node is overwritten.
|
||||||
|
* \param[in] pos position of the static node in the 3D space.
|
||||||
|
* \param[in] orient_quat orientation of the static node in the 3D space, represented by a unit quaternion.
|
||||||
|
* \return true if success.
|
||||||
|
*/
|
||||||
|
bool set_static_node(const std::string& guid, const rs2_vector& pos, const rs2_quaternion& orient) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_set_static_node(_sensor.get(), guid.c_str(), pos, orient, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return !!res;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the current pose of a static node that was created in the current map or in an imported map.
|
||||||
|
* Static nodes of imported maps are available after relocalizing the imported map.
|
||||||
|
* The static node's pose is returned relative to the current origin of coordinates of device poses.
|
||||||
|
* Thus, poses of static nodes of an imported map are consistent with current device poses after relocalization.
|
||||||
|
* This function fails if the current tracker confidence is below 3 (high confidence).
|
||||||
|
* \param[in] guid unique name of the static node (limited to 127 chars).
|
||||||
|
* \param[out] pos position of the static node in the 3D space.
|
||||||
|
* \param[out] orient_quat orientation of the static node in the 3D space, represented by a unit quaternion.
|
||||||
|
* \return true if success.
|
||||||
|
*/
|
||||||
|
bool get_static_node(const std::string& guid, rs2_vector& pos, rs2_quaternion& orient) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_static_node(_sensor.get(), guid.c_str(), &pos, &orient, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return !!res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Removes a static node from the current map.
|
||||||
|
* \param[in] guid unique name of the static node (limited to 127 chars).
|
||||||
|
*/
|
||||||
|
bool remove_static_node(const std::string& guid) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_remove_static_node(_sensor.get(), guid.c_str(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return !!res;
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
explicit pose_sensor(std::shared_ptr<rs2_sensor> dev) : pose_sensor(sensor(dev)) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
class wheel_odometer : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
wheel_odometer(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_WHEEL_ODOMETER, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Load Wheel odometer settings from host to device
|
||||||
|
* \param[in] odometry_config_buf odometer configuration/calibration blob serialized from jsom file
|
||||||
|
* \return true on success
|
||||||
|
*/
|
||||||
|
bool load_wheel_odometery_config(const std::vector<uint8_t>& odometry_config_buf) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_load_wheel_odometry_config(_sensor.get(), odometry_config_buf.data(), uint32_t(odometry_config_buf.size()), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return !!res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Send wheel odometry data for each individual sensor (wheel)
|
||||||
|
* \param[in] wo_sensor_id - Zero-based index of (wheel) sensor with the same type within device
|
||||||
|
* \param[in] frame_num - Monotonocally increasing frame number, managed per sensor.
|
||||||
|
* \param[in] translational_velocity - Translational velocity in meter/sec
|
||||||
|
* \return true on success
|
||||||
|
*/
|
||||||
|
bool send_wheel_odometry(uint8_t wo_sensor_id, uint32_t frame_num, const rs2_vector& translational_velocity)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_send_wheel_odometry(_sensor.get(), wo_sensor_id, frame_num, translational_velocity, &e);
|
||||||
|
error::handle(e);
|
||||||
|
return !!res;
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
explicit wheel_odometer(std::shared_ptr<rs2_sensor> dev) : wheel_odometer(sensor(dev)) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
class calibrated_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
calibrated_sensor( sensor s )
|
||||||
|
: sensor( s.get() )
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if( rs2_is_sensor_extendable_to( _sensor.get(), RS2_EXTENSION_CALIBRATED_SENSOR, &e ) == 0 && !e )
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
|
||||||
|
/** Override the intrinsics at the sensor level, as DEPTH_TO_RGB calibration does */
|
||||||
|
void override_intrinsics( rs2_intrinsics const& intr )
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_override_intrinsics( _sensor.get(), &intr, &e );
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Override the intrinsics at the sensor level, as DEPTH_TO_RGB calibration does */
|
||||||
|
void override_extrinsics( rs2_extrinsics const& extr )
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_override_extrinsics( _sensor.get(), &extr, &e );
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Override the intrinsics at the sensor level, as DEPTH_TO_RGB calibration does */
|
||||||
|
rs2_dsm_params get_dsm_params() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_dsm_params params;
|
||||||
|
rs2_get_dsm_params( _sensor.get(), ¶ms, &e );
|
||||||
|
error::handle( e );
|
||||||
|
return params;
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Set the sensor DSM parameters
|
||||||
|
* This should ideally be done when the stream is NOT running. If it is, the
|
||||||
|
* parameters may not take effect immediately. */
|
||||||
|
void override_dsm_params( rs2_dsm_params const & params )
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_override_dsm_params( _sensor.get(), ¶ms, &e );
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Reset the sensor DSM calibration
|
||||||
|
*/
|
||||||
|
void reset_calibration()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_reset_sensor_calibration( _sensor.get(), &e );
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class max_usable_range_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
max_usable_range_sensor(sensor s)
|
||||||
|
: sensor(s.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_MAX_USABLE_RANGE_SENSOR, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
|
||||||
|
/** Retrieves the maximum range of the camera given the amount of ambient light in the scene.
|
||||||
|
* \return max usable range in meters
|
||||||
|
*/
|
||||||
|
float get_max_usable_depth_range() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
auto res = rs2_get_max_usable_depth_range(_sensor.get(), &e);
|
||||||
|
error::handle(e);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class debug_stream_sensor : public sensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
debug_stream_sensor( sensor s )
|
||||||
|
: sensor( s.get() )
|
||||||
|
{
|
||||||
|
rs2_error * e = nullptr;
|
||||||
|
if( rs2_is_sensor_extendable_to( _sensor.get(), RS2_EXTENSION_DEBUG_STREAM_SENSOR, &e ) == 0 && ! e )
|
||||||
|
{
|
||||||
|
_sensor.reset();
|
||||||
|
}
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
|
||||||
|
operator bool() const { return _sensor.get() != nullptr; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieves the list of debug stream profiles supported by the sensor.
|
||||||
|
* \return list of debug stream profiles that given sensor can provide
|
||||||
|
*/
|
||||||
|
std::vector< stream_profile > get_debug_stream_profiles() const
|
||||||
|
{
|
||||||
|
std::vector< stream_profile > results;
|
||||||
|
|
||||||
|
rs2_error * e = nullptr;
|
||||||
|
std::shared_ptr< rs2_stream_profile_list > list(
|
||||||
|
rs2_get_debug_stream_profiles( _sensor.get(), &e ),
|
||||||
|
rs2_delete_stream_profiles_list );
|
||||||
|
error::handle( e );
|
||||||
|
|
||||||
|
auto size = rs2_get_stream_profiles_count( list.get(), &e );
|
||||||
|
error::handle( e );
|
||||||
|
|
||||||
|
for( auto i = 0; i < size; i++ )
|
||||||
|
{
|
||||||
|
stream_profile profile( rs2_get_stream_profile( list.get(), i, &e ) );
|
||||||
|
error::handle( e );
|
||||||
|
results.push_back( profile );
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
#endif // LIBREALSENSE_RS2_SENSOR_HPP
|
|
@ -0,0 +1,57 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
#include "rs_types.hpp"
|
||||||
|
#include "rs_device.hpp"
|
||||||
|
#include <array>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
class serializable_device : public rs2::device
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
serializable_device(rs2::device d)
|
||||||
|
: rs2::device(d.get())
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_SERIALIZABLE, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_dev = nullptr;
|
||||||
|
}
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string serialize_json() const
|
||||||
|
{
|
||||||
|
std::string results;
|
||||||
|
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
std::shared_ptr<rs2_raw_data_buffer> json_data(
|
||||||
|
rs2_serialize_json(_dev.get(), &e),
|
||||||
|
rs2_delete_raw_data);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
auto size = rs2_get_raw_data_size(json_data.get(), &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
auto start = rs2_get_raw_data(json_data.get(), &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
results.insert(results.begin(), start, start + size);
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
void load_json(const std::string& json_content) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_load_json(_dev.get(),
|
||||||
|
json_content.data(),
|
||||||
|
(unsigned int)json_content.size(),
|
||||||
|
&e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
|
@ -0,0 +1,196 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_TYPES_HPP
|
||||||
|
#define LIBREALSENSE_RS2_TYPES_HPP
|
||||||
|
|
||||||
|
#include "../rs.h"
|
||||||
|
#include "../h/rs_context.h"
|
||||||
|
#include "../h/rs_device.h"
|
||||||
|
#include "../h/rs_frame.h"
|
||||||
|
#include "../h/rs_processing.h"
|
||||||
|
#include "../h/rs_record_playback.h"
|
||||||
|
#include "../h/rs_sensor.h"
|
||||||
|
#include "../h/rs_pipeline.h"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
#include <memory>
|
||||||
|
#include <functional>
|
||||||
|
#include <exception>
|
||||||
|
#include <iterator>
|
||||||
|
#include <sstream>
|
||||||
|
#include <chrono>
|
||||||
|
|
||||||
|
struct rs2_frame_callback
|
||||||
|
{
|
||||||
|
virtual void on_frame(rs2_frame * f) = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_frame_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct rs2_frame_processor_callback
|
||||||
|
{
|
||||||
|
virtual void on_frame(rs2_frame * f, rs2_source * source) = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_frame_processor_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct rs2_notifications_callback
|
||||||
|
{
|
||||||
|
virtual void on_notification(rs2_notification* n) = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_notifications_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef void ( *log_callback_function_ptr )(rs2_log_severity severity, rs2_log_message const * msg );
|
||||||
|
|
||||||
|
struct rs2_software_device_destruction_callback
|
||||||
|
{
|
||||||
|
virtual void on_destruction() = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_software_device_destruction_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct rs2_log_callback
|
||||||
|
{
|
||||||
|
virtual void on_log( rs2_log_severity severity, rs2_log_message const & msg ) noexcept = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_log_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct rs2_calibration_change_callback
|
||||||
|
{
|
||||||
|
virtual void on_calibration_change( rs2_calibration_status ) noexcept = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_calibration_change_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct rs2_devices_changed_callback
|
||||||
|
{
|
||||||
|
virtual void on_devices_changed(rs2_device_list* removed, rs2_device_list* added) = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_devices_changed_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct rs2_playback_status_changed_callback
|
||||||
|
{
|
||||||
|
virtual void on_playback_status_changed(rs2_playback_status status) = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_playback_status_changed_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct rs2_update_progress_callback
|
||||||
|
{
|
||||||
|
virtual void on_update_progress(const float update_progress) = 0;
|
||||||
|
virtual void release() = 0;
|
||||||
|
virtual ~rs2_update_progress_callback() {}
|
||||||
|
};
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
class error : public std::runtime_error
|
||||||
|
{
|
||||||
|
std::string function, args;
|
||||||
|
rs2_exception_type type;
|
||||||
|
public:
|
||||||
|
explicit error(rs2_error* err) : runtime_error(rs2_get_error_message(err))
|
||||||
|
{
|
||||||
|
function = (nullptr != rs2_get_failed_function(err)) ? rs2_get_failed_function(err) : std::string();
|
||||||
|
args = (nullptr != rs2_get_failed_args(err)) ? rs2_get_failed_args(err) : std::string();
|
||||||
|
type = rs2_get_librealsense_exception_type(err);
|
||||||
|
rs2_free_error(err);
|
||||||
|
}
|
||||||
|
|
||||||
|
explicit error(const std::string& message) : runtime_error(message.c_str())
|
||||||
|
{
|
||||||
|
function = "";
|
||||||
|
args = "";
|
||||||
|
type = RS2_EXCEPTION_TYPE_UNKNOWN;
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::string& get_failed_function() const
|
||||||
|
{
|
||||||
|
return function;
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::string& get_failed_args() const
|
||||||
|
{
|
||||||
|
return args;
|
||||||
|
}
|
||||||
|
|
||||||
|
rs2_exception_type get_type() const { return type; }
|
||||||
|
|
||||||
|
static void handle(rs2_error* e);
|
||||||
|
};
|
||||||
|
|
||||||
|
#define RS2_ERROR_CLASS(name, base) \
|
||||||
|
class name : public base\
|
||||||
|
{\
|
||||||
|
public:\
|
||||||
|
explicit name(rs2_error* e) noexcept : base(e) {}\
|
||||||
|
}
|
||||||
|
|
||||||
|
RS2_ERROR_CLASS(recoverable_error, error);
|
||||||
|
RS2_ERROR_CLASS(unrecoverable_error, error);
|
||||||
|
RS2_ERROR_CLASS(camera_disconnected_error, unrecoverable_error);
|
||||||
|
RS2_ERROR_CLASS(backend_error, unrecoverable_error);
|
||||||
|
RS2_ERROR_CLASS(device_in_recovery_mode_error, unrecoverable_error);
|
||||||
|
RS2_ERROR_CLASS(invalid_value_error, recoverable_error);
|
||||||
|
RS2_ERROR_CLASS(wrong_api_call_sequence_error, recoverable_error);
|
||||||
|
RS2_ERROR_CLASS(not_implemented_error, recoverable_error);
|
||||||
|
#undef RS2_ERROR_CLASS
|
||||||
|
|
||||||
|
inline void error::handle(rs2_error* e)
|
||||||
|
{
|
||||||
|
if (e)
|
||||||
|
{
|
||||||
|
auto h = rs2_get_librealsense_exception_type(e);
|
||||||
|
switch (h) {
|
||||||
|
case RS2_EXCEPTION_TYPE_CAMERA_DISCONNECTED:
|
||||||
|
throw camera_disconnected_error(e);
|
||||||
|
case RS2_EXCEPTION_TYPE_BACKEND:
|
||||||
|
throw backend_error(e);
|
||||||
|
case RS2_EXCEPTION_TYPE_INVALID_VALUE:
|
||||||
|
throw invalid_value_error(e);
|
||||||
|
case RS2_EXCEPTION_TYPE_WRONG_API_CALL_SEQUENCE:
|
||||||
|
throw wrong_api_call_sequence_error(e);
|
||||||
|
case RS2_EXCEPTION_TYPE_NOT_IMPLEMENTED:
|
||||||
|
throw not_implemented_error(e);
|
||||||
|
case RS2_EXCEPTION_TYPE_DEVICE_IN_RECOVERY_MODE:
|
||||||
|
throw device_in_recovery_mode_error(e);
|
||||||
|
default:
|
||||||
|
throw error(e);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
class context;
|
||||||
|
class device;
|
||||||
|
class device_list;
|
||||||
|
class syncer;
|
||||||
|
class device_base;
|
||||||
|
class roi_sensor;
|
||||||
|
class frame;
|
||||||
|
|
||||||
|
struct option_range
|
||||||
|
{
|
||||||
|
float min;
|
||||||
|
float max;
|
||||||
|
float def;
|
||||||
|
float step;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct region_of_interest
|
||||||
|
{
|
||||||
|
int min_x;
|
||||||
|
int min_y;
|
||||||
|
int max_x;
|
||||||
|
int max_y;
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_vector v) { return o << v.x << ", " << v.y << ", " << v.z; }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_quaternion q) { return o << q.x << ", " << q.y << ", " << q.z << ", " << q.w; }
|
||||||
|
|
||||||
|
#endif // LIBREALSENSE_RS2_TYPES_HPP
|
|
@ -0,0 +1,128 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
/** \file rs.h
|
||||||
|
* \brief
|
||||||
|
* Exposes librealsense functionality for C compilers
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_H
|
||||||
|
#define LIBREALSENSE_RS2_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "rsutil.h"
|
||||||
|
#include "h/rs_types.h"
|
||||||
|
#include "h/rs_context.h"
|
||||||
|
#include "h/rs_device.h"
|
||||||
|
#include "h/rs_frame.h"
|
||||||
|
#include "h/rs_option.h"
|
||||||
|
#include "h/rs_processing.h"
|
||||||
|
#include "h/rs_record_playback.h"
|
||||||
|
#include "h/rs_sensor.h"
|
||||||
|
|
||||||
|
#define RS2_API_MAJOR_VERSION 2
|
||||||
|
#define RS2_API_MINOR_VERSION 50
|
||||||
|
#define RS2_API_PATCH_VERSION 0
|
||||||
|
#define RS2_API_BUILD_VERSION 0
|
||||||
|
|
||||||
|
#ifndef STRINGIFY
|
||||||
|
#define STRINGIFY(arg) #arg
|
||||||
|
#endif
|
||||||
|
#ifndef VAR_ARG_STRING
|
||||||
|
#define VAR_ARG_STRING(arg) STRINGIFY(arg)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Versioning rules : For each release at least one of [MJR/MNR/PTCH] triple is promoted */
|
||||||
|
/* : Versions that differ by RS2_API_PATCH_VERSION only are interface-compatible, i.e. no user-code changes required */
|
||||||
|
/* : Versions that differ by MAJOR/MINOR VERSION component can introduce API changes */
|
||||||
|
/* Version in encoded integer format (1,9,x) -> 01090x. note that each component is limited into [0-99] range by design */
|
||||||
|
#define RS2_API_VERSION (((RS2_API_MAJOR_VERSION) * 10000) + ((RS2_API_MINOR_VERSION) * 100) + (RS2_API_PATCH_VERSION))
|
||||||
|
/* Return version in "X.Y.Z" format */
|
||||||
|
#define RS2_API_VERSION_STR (VAR_ARG_STRING(RS2_API_MAJOR_VERSION.RS2_API_MINOR_VERSION.RS2_API_PATCH_VERSION))
|
||||||
|
#define RS2_API_FULL_VERSION_STR (VAR_ARG_STRING(RS2_API_MAJOR_VERSION.RS2_API_MINOR_VERSION.RS2_API_PATCH_VERSION.RS2_API_BUILD_VERSION))
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get the size of rs2_raw_data_buffer
|
||||||
|
* \param[in] buffer pointer to rs2_raw_data_buffer returned by rs2_send_and_receive_raw_data
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return size of rs2_raw_data_buffer
|
||||||
|
*/
|
||||||
|
int rs2_get_raw_data_size(const rs2_raw_data_buffer* buffer, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delete rs2_raw_data_buffer
|
||||||
|
* \param[in] buffer rs2_raw_data_buffer returned by rs2_send_and_receive_raw_data
|
||||||
|
*/
|
||||||
|
void rs2_delete_raw_data(const rs2_raw_data_buffer* buffer);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve char array from rs2_raw_data_buffer
|
||||||
|
* \param[in] buffer rs2_raw_data_buffer returned by rs2_send_and_receive_raw_data
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return raw data
|
||||||
|
*/
|
||||||
|
const unsigned char* rs2_get_raw_data(const rs2_raw_data_buffer* buffer, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Retrieve the API version from the source code. Evaluate that the value is conformant to the established policies
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the version API encoded into integer value "1.9.3" -> 10903
|
||||||
|
*/
|
||||||
|
int rs2_get_api_version(rs2_error** error);
|
||||||
|
|
||||||
|
void rs2_log_to_console(rs2_log_severity min_severity, rs2_error ** error);
|
||||||
|
|
||||||
|
void rs2_log_to_file(rs2_log_severity min_severity, const char * file_path, rs2_error ** error);
|
||||||
|
|
||||||
|
void rs2_log_to_callback_cpp( rs2_log_severity min_severity, rs2_log_callback * callback, rs2_error ** error );
|
||||||
|
|
||||||
|
void rs2_log_to_callback( rs2_log_severity min_severity, rs2_log_callback_ptr callback, void * arg, rs2_error** error );
|
||||||
|
|
||||||
|
void rs2_reset_logger( rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable rolling log file when used with rs2_log_to_file:
|
||||||
|
* Upon reaching (max_size/2) bytes, the log will be renamed with an ".old" suffix and a new log created. Any
|
||||||
|
* previous .old file will be erased.
|
||||||
|
* Must have permissions to remove/rename files in log file directory.
|
||||||
|
* \param[in] max_size max file size in megabytes
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_enable_rolling_log_file( unsigned max_size, rs2_error ** error );
|
||||||
|
|
||||||
|
|
||||||
|
unsigned rs2_get_log_message_line_number( rs2_log_message const * msg, rs2_error** error );
|
||||||
|
const char * rs2_get_log_message_filename( rs2_log_message const * msg, rs2_error** error );
|
||||||
|
const char * rs2_get_raw_log_message( rs2_log_message const * msg, rs2_error** error );
|
||||||
|
const char * rs2_get_full_log_message( rs2_log_message const * msg, rs2_error** error );
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add custom message into librealsense log
|
||||||
|
* \param[in] severity The log level for the message to be written under
|
||||||
|
* \param[in] message Message to be logged
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
void rs2_log(rs2_log_severity severity, const char * message, rs2_error ** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Given the 2D depth coordinate (x,y) provide the corresponding depth in metric units
|
||||||
|
* \param[in] frame_ref 2D depth pixel coordinates (Left-Upper corner origin)
|
||||||
|
* \param[in] x,y 2D depth pixel coordinates (Left-Upper corner origin)
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
*/
|
||||||
|
float rs2_depth_frame_get_distance(const rs2_frame* frame_ref, int x, int y, rs2_error** error);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* return the time at specific time point
|
||||||
|
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
|
||||||
|
* \return the time at specific time point, in live and record mode it will return the system time and in playback mode it will return the recorded time
|
||||||
|
*/
|
||||||
|
rs2_time_t rs2_get_time( rs2_error** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,175 @@
|
||||||
|
// License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RS2_HPP
|
||||||
|
#define LIBREALSENSE_RS2_HPP
|
||||||
|
|
||||||
|
#include "rs.h"
|
||||||
|
#include "hpp/rs_types.hpp"
|
||||||
|
#include "hpp/rs_context.hpp"
|
||||||
|
#include "hpp/rs_device.hpp"
|
||||||
|
#include "hpp/rs_frame.hpp"
|
||||||
|
#include "hpp/rs_processing.hpp"
|
||||||
|
#include "hpp/rs_record_playback.hpp"
|
||||||
|
#include "hpp/rs_sensor.hpp"
|
||||||
|
#include "hpp/rs_pipeline.hpp"
|
||||||
|
|
||||||
|
namespace rs2
|
||||||
|
{
|
||||||
|
inline void log_to_console(rs2_log_severity min_severity)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_log_to_console(min_severity, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void log_to_file(rs2_log_severity min_severity, const char * file_path = nullptr)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_log_to_file(min_severity, file_path, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void reset_logger()
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_reset_logger(&e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Enable rolling log file when used with rs2_log_to_file:
|
||||||
|
// Upon reaching (max_size/2) bytes, the log will be renamed with an ".old" suffix and a new log created. Any
|
||||||
|
// previous .old file will be erased.
|
||||||
|
// Must have permissions to remove/rename files in log file directory.
|
||||||
|
//
|
||||||
|
// @param max_size max file size in megabytes
|
||||||
|
//
|
||||||
|
inline void enable_rolling_log_file( unsigned max_size )
|
||||||
|
{
|
||||||
|
rs2_error * e = nullptr;
|
||||||
|
rs2_enable_rolling_log_file( max_size, &e );
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
Interface to the log message data we expose.
|
||||||
|
*/
|
||||||
|
class log_message
|
||||||
|
{
|
||||||
|
// Only log_callback should be creating us!
|
||||||
|
template< class T > friend class log_callback;
|
||||||
|
|
||||||
|
log_message( rs2_log_message const & msg ) : _msg( msg ) {}
|
||||||
|
|
||||||
|
public:
|
||||||
|
/* Returns the line-number in the file where the LOG() comment was issued */
|
||||||
|
size_t line_number() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
size_t ln = rs2_get_log_message_line_number( &_msg, &e );
|
||||||
|
error::handle( e );
|
||||||
|
return ln;
|
||||||
|
}
|
||||||
|
/* Returns the file in which the LOG() command was issued */
|
||||||
|
const char * filename() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
const char * path = rs2_get_log_message_filename( &_msg, &e );
|
||||||
|
error::handle( e );
|
||||||
|
return path;
|
||||||
|
}
|
||||||
|
/* Returns the raw message, as it was passed to LOG(), before any embelishments like level etc. */
|
||||||
|
const char* raw() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
const char* r = rs2_get_raw_log_message( &_msg, &e );
|
||||||
|
error::handle( e );
|
||||||
|
return r;
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
Returns a complete log message, as defined by librealsense, with level, timestamp, etc.:
|
||||||
|
11/12 13:49:40,153 INFO [10604] (rs.cpp:2271) Framebuffer size changed to 1552 x 919
|
||||||
|
*/
|
||||||
|
const char* full() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
const char* str = rs2_get_full_log_message( &_msg, &e );
|
||||||
|
error::handle( e );
|
||||||
|
return str;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
rs2_log_message const & _msg;
|
||||||
|
};
|
||||||
|
|
||||||
|
/*
|
||||||
|
Wrapper around any callback function that is given to log_to_callback.
|
||||||
|
*/
|
||||||
|
template<class T>
|
||||||
|
class log_callback : public rs2_log_callback
|
||||||
|
{
|
||||||
|
T on_log_function;
|
||||||
|
public:
|
||||||
|
explicit log_callback( T on_log ) : on_log_function( on_log ) {}
|
||||||
|
|
||||||
|
void on_log( rs2_log_severity severity, rs2_log_message const & msg ) noexcept override
|
||||||
|
{
|
||||||
|
on_log_function( severity, log_message( msg ));
|
||||||
|
}
|
||||||
|
|
||||||
|
void release() override { delete this; }
|
||||||
|
};
|
||||||
|
|
||||||
|
/*
|
||||||
|
Your callback should look like this, for example:
|
||||||
|
void callback( rs2_log_severity severity, rs2::log_message const & msg ) noexcept
|
||||||
|
{
|
||||||
|
std::cout << msg.build() << std::endl;
|
||||||
|
}
|
||||||
|
and, when initializing rs2:
|
||||||
|
rs2::log_to_callback( callback );
|
||||||
|
or:
|
||||||
|
rs2::log_to_callback(
|
||||||
|
[]( rs2_log_severity severity, rs2::log_message const & msg ) noexcept
|
||||||
|
{
|
||||||
|
std::cout << msg.build() << std::endl;
|
||||||
|
})
|
||||||
|
*/
|
||||||
|
template< typename S >
|
||||||
|
inline void log_to_callback( rs2_log_severity min_severity, S callback )
|
||||||
|
{
|
||||||
|
// We wrap the callback with an interface and pass it to librealsense, who will
|
||||||
|
// now manage its lifetime. Rather than deleting it, though, it will call its
|
||||||
|
// release() function, where (back in our context) it can be safely deleted:
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_log_to_callback_cpp( min_severity, new log_callback< S >( std::move( callback )), &e );
|
||||||
|
error::handle( e );
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void log(rs2_log_severity severity, const char* message)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_log(severity, message, &e);
|
||||||
|
error::handle(e);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_stream stream) { return o << rs2_stream_to_string(stream); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_format format) { return o << rs2_format_to_string(format); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_distortion distortion) { return o << rs2_distortion_to_string(distortion); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_option option) { return o << rs2_option_to_string(option); } // This function is being deprecated. For existing options it will return option name, but for future API additions the user should call rs2_get_option_name instead.
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_log_severity severity) { return o << rs2_log_severity_to_string(severity); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2::log_message const & msg ) { return o << msg.raw(); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_camera_info camera_info) { return o << rs2_camera_info_to_string(camera_info); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_frame_metadata_value metadata) { return o << rs2_frame_metadata_to_string(metadata); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_timestamp_domain domain) { return o << rs2_timestamp_domain_to_string(domain); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_notification_category notificaton) { return o << rs2_notification_category_to_string(notificaton); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_sr300_visual_preset preset) { return o << rs2_sr300_visual_preset_to_string(preset); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_exception_type exception_type) { return o << rs2_exception_type_to_string(exception_type); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_playback_status status) { return o << rs2_playback_status_to_string(status); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_l500_visual_preset preset) {return o << rs2_l500_visual_preset_to_string(preset);}
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_sensor_mode mode) { return o << rs2_sensor_mode_to_string(mode); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_calibration_type mode) { return o << rs2_calibration_type_to_string(mode); }
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_calibration_status mode) { return o << rs2_calibration_status_to_string(mode); }
|
||||||
|
|
||||||
|
#endif // LIBREALSENSE_RS2_HPP
|
|
@ -0,0 +1,99 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
#ifndef RS400_ADVANCED_MODE_H
|
||||||
|
#define RS400_ADVANCED_MODE_H
|
||||||
|
|
||||||
|
#define RS400_ADVANCED_MODE_HPP
|
||||||
|
#include "h/rs_advanced_mode_command.h"
|
||||||
|
#undef RS400_ADVANCED_MODE_HPP
|
||||||
|
|
||||||
|
#include "h/rs_types.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Enable/Disable Advanced-Mode */
|
||||||
|
void rs2_toggle_advanced_mode(rs2_device* dev, int enable, rs2_error** error);
|
||||||
|
|
||||||
|
/* Check if Advanced-Mode is enabled */
|
||||||
|
void rs2_is_enabled(rs2_device* dev, int* enabled, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for Depth Control Group, returns 0 if success */
|
||||||
|
void rs2_set_depth_control(rs2_device* dev, const STDepthControlGroup* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for Depth Control Group, returns 0 if success */
|
||||||
|
void rs2_get_depth_control(rs2_device* dev, STDepthControlGroup* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for RSM Group, returns 0 if success */
|
||||||
|
void rs2_set_rsm(rs2_device* dev, const STRsm* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for RSM Group, returns 0 if success */
|
||||||
|
void rs2_get_rsm(rs2_device* dev, STRsm* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STRauSupportVectorControl, returns 0 if success */
|
||||||
|
void rs2_set_rau_support_vector_control(rs2_device* dev, const STRauSupportVectorControl* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STRauSupportVectorControl, returns 0 if success */
|
||||||
|
void rs2_get_rau_support_vector_control(rs2_device* dev, STRauSupportVectorControl* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STColorControl, returns 0 if success */
|
||||||
|
void rs2_set_color_control(rs2_device* dev, const STColorControl* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STColorControl, returns 0 if success */
|
||||||
|
void rs2_get_color_control(rs2_device* dev, STColorControl* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STRauColorThresholdsControl, returns 0 if success */
|
||||||
|
void rs2_set_rau_thresholds_control(rs2_device* dev, const STRauColorThresholdsControl* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STRauColorThresholdsControl, returns 0 if success */
|
||||||
|
void rs2_get_rau_thresholds_control(rs2_device* dev, STRauColorThresholdsControl* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STSloColorThresholdsControl, returns 0 if success */
|
||||||
|
void rs2_set_slo_color_thresholds_control(rs2_device* dev, const STSloColorThresholdsControl* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STRauColorThresholdsControl, returns 0 if success */
|
||||||
|
void rs2_get_slo_color_thresholds_control(rs2_device* dev, STSloColorThresholdsControl* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STSloPenaltyControl, returns 0 if success */
|
||||||
|
void rs2_set_slo_penalty_control(rs2_device* dev, const STSloPenaltyControl* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STSloPenaltyControl, returns 0 if success */
|
||||||
|
void rs2_get_slo_penalty_control(rs2_device* dev, STSloPenaltyControl* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STHdad, returns 0 if success */
|
||||||
|
void rs2_set_hdad(rs2_device* dev, const STHdad* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STHdad, returns 0 if success */
|
||||||
|
void rs2_get_hdad(rs2_device* dev, STHdad* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STColorCorrection, returns 0 if success */
|
||||||
|
void rs2_set_color_correction(rs2_device* dev, const STColorCorrection* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STColorCorrection, returns 0 if success */
|
||||||
|
void rs2_get_color_correction(rs2_device* dev, STColorCorrection* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
/* Sets new values for STDepthTableControl, returns 0 if success */
|
||||||
|
void rs2_set_depth_table(rs2_device* dev, const STDepthTableControl* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STDepthTableControl, returns 0 if success */
|
||||||
|
void rs2_get_depth_table(rs2_device* dev, STDepthTableControl* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
void rs2_set_ae_control(rs2_device* dev, const STAEControl* group, rs2_error** error);
|
||||||
|
|
||||||
|
void rs2_get_ae_control(rs2_device* dev, STAEControl* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
void rs2_set_census(rs2_device* dev, const STCensusRadius* group, rs2_error** error);
|
||||||
|
|
||||||
|
void rs2_get_census(rs2_device* dev, STCensusRadius* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
void rs2_set_amp_factor(rs2_device* dev, const STAFactor* group, rs2_error** error);
|
||||||
|
|
||||||
|
/* Gets new values for STAFactor, returns 0 if success */
|
||||||
|
void rs2_get_amp_factor(rs2_device* dev, STAFactor* group, int mode, rs2_error** error);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -0,0 +1,386 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
#ifndef R4XX_ADVANCED_MODE_HPP
|
||||||
|
#define R4XX_ADVANCED_MODE_HPP
|
||||||
|
|
||||||
|
#include <cmath>
|
||||||
|
#include "rs.hpp"
|
||||||
|
#include "rs_advanced_mode.h"
|
||||||
|
#include "hpp/rs_serializable_device.hpp"
|
||||||
|
|
||||||
|
namespace rs400
|
||||||
|
{
|
||||||
|
class advanced_mode : public rs2::serializable_device
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
advanced_mode(rs2::device d)
|
||||||
|
: rs2::serializable_device(d)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
if(_dev && rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_ADVANCED_MODE, &e) == 0 && !e)
|
||||||
|
{
|
||||||
|
_dev = nullptr;
|
||||||
|
}
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
void toggle_advanced_mode(bool enable)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_toggle_advanced_mode(_dev.get(), enable, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool is_enabled() const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
int enabled=0;
|
||||||
|
rs2_is_enabled(_dev.get(), &enabled, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return !!enabled;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_depth_control(const STDepthControlGroup& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_depth_control(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STDepthControlGroup get_depth_control(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STDepthControlGroup group{};
|
||||||
|
rs2_get_depth_control(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_rsm(const STRsm& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_rsm(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STRsm get_rsm(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STRsm group{};
|
||||||
|
rs2_get_rsm(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_rau_support_vector_control(const STRauSupportVectorControl& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_rau_support_vector_control(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STRauSupportVectorControl get_rau_support_vector_control(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STRauSupportVectorControl group{};
|
||||||
|
rs2_get_rau_support_vector_control(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_color_control(const STColorControl& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_color_control(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STColorControl get_color_control(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STColorControl group{};
|
||||||
|
rs2_get_color_control(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_rau_thresholds_control(const STRauColorThresholdsControl& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_rau_thresholds_control(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STRauColorThresholdsControl get_rau_thresholds_control(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STRauColorThresholdsControl group{};
|
||||||
|
rs2_get_rau_thresholds_control(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_slo_color_thresholds_control(const STSloColorThresholdsControl& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_slo_color_thresholds_control(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STSloColorThresholdsControl get_slo_color_thresholds_control(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STSloColorThresholdsControl group{};
|
||||||
|
rs2_get_slo_color_thresholds_control(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_slo_penalty_control(const STSloPenaltyControl& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_slo_penalty_control(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STSloPenaltyControl get_slo_penalty_control(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STSloPenaltyControl group{};
|
||||||
|
rs2_get_slo_penalty_control(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_hdad(const STHdad& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_hdad(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STHdad get_hdad(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STHdad group{};
|
||||||
|
rs2_get_hdad(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_color_correction(const STColorCorrection& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_color_correction(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STColorCorrection get_color_correction(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STColorCorrection group{};
|
||||||
|
rs2_get_color_correction(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_depth_table(const STDepthTableControl& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_depth_table(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STDepthTableControl get_depth_table(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STDepthTableControl group{};
|
||||||
|
rs2_get_depth_table(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_ae_control(const STAEControl& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_ae_control(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STAEControl get_ae_control(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STAEControl group{};
|
||||||
|
rs2_get_ae_control(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_census(const STCensusRadius& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_census(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STCensusRadius get_census(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STCensusRadius group{};
|
||||||
|
rs2_get_census(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_amp_factor(const STAFactor& group)
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
rs2_set_amp_factor(_dev.get(), &group, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
}
|
||||||
|
|
||||||
|
STAFactor get_amp_factor(int mode = 0) const
|
||||||
|
{
|
||||||
|
rs2_error* e = nullptr;
|
||||||
|
STAFactor group{};
|
||||||
|
rs2_get_amp_factor(_dev.get(), &group, mode, &e);
|
||||||
|
rs2::error::handle(e);
|
||||||
|
|
||||||
|
return group;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
inline std::ostream & operator << (std::ostream & o, rs2_rs400_visual_preset preset) { return o << rs2_rs400_visual_preset_to_string(preset); }
|
||||||
|
|
||||||
|
inline bool operator==(const STDepthControlGroup& a, const STDepthControlGroup& b)
|
||||||
|
{
|
||||||
|
return (a.plusIncrement == b.plusIncrement &&
|
||||||
|
a.minusDecrement == b.minusDecrement &&
|
||||||
|
a.deepSeaMedianThreshold == b.deepSeaMedianThreshold &&
|
||||||
|
a.scoreThreshA == b.scoreThreshA &&
|
||||||
|
a.scoreThreshB == b.scoreThreshB &&
|
||||||
|
a.textureDifferenceThreshold == b.textureDifferenceThreshold &&
|
||||||
|
a.textureCountThreshold == b.textureCountThreshold &&
|
||||||
|
a.deepSeaSecondPeakThreshold == b.deepSeaSecondPeakThreshold &&
|
||||||
|
a.deepSeaNeighborThreshold == b.deepSeaNeighborThreshold &&
|
||||||
|
a.lrAgreeThreshold == b.lrAgreeThreshold);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STRsm& a, const STRsm& b)
|
||||||
|
{
|
||||||
|
return (a.rsmBypass == b.rsmBypass &&
|
||||||
|
a.diffThresh == b.diffThresh &&
|
||||||
|
a.sloRauDiffThresh == b.sloRauDiffThresh &&
|
||||||
|
a.removeThresh == b.removeThresh);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STRauSupportVectorControl& a, const STRauSupportVectorControl& b)
|
||||||
|
{
|
||||||
|
return (a.minWest == b.minWest &&
|
||||||
|
a.minEast == b.minEast &&
|
||||||
|
a.minWEsum == b.minWEsum &&
|
||||||
|
a.minNorth == b.minNorth &&
|
||||||
|
a.minSouth == b.minSouth &&
|
||||||
|
a.minNSsum == b.minNSsum &&
|
||||||
|
a.uShrink == b.uShrink &&
|
||||||
|
a.vShrink == b.vShrink);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STColorControl& a, const STColorControl& b)
|
||||||
|
{
|
||||||
|
return (a.disableSADColor == b.disableSADColor &&
|
||||||
|
a.disableRAUColor == b.disableRAUColor &&
|
||||||
|
a.disableSLORightColor == b.disableSLORightColor &&
|
||||||
|
a.disableSLOLeftColor == b.disableSLOLeftColor &&
|
||||||
|
a.disableSADNormalize == b.disableSADNormalize);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STRauColorThresholdsControl& a, const STRauColorThresholdsControl& b)
|
||||||
|
{
|
||||||
|
return (a.rauDiffThresholdRed == b.rauDiffThresholdRed &&
|
||||||
|
a.rauDiffThresholdGreen == b.rauDiffThresholdGreen &&
|
||||||
|
a.rauDiffThresholdBlue == b.rauDiffThresholdBlue);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STSloColorThresholdsControl& a, const STSloColorThresholdsControl& b)
|
||||||
|
{
|
||||||
|
return (a.diffThresholdRed == b.diffThresholdRed &&
|
||||||
|
a.diffThresholdGreen == b.diffThresholdGreen &&
|
||||||
|
a.diffThresholdBlue == b.diffThresholdBlue);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STSloPenaltyControl& a, const STSloPenaltyControl& b)
|
||||||
|
{
|
||||||
|
return (a.sloK1Penalty == b.sloK1Penalty &&
|
||||||
|
a.sloK2Penalty == b.sloK2Penalty &&
|
||||||
|
a.sloK1PenaltyMod1 == b.sloK1PenaltyMod1 &&
|
||||||
|
a.sloK2PenaltyMod1 == b.sloK2PenaltyMod1 &&
|
||||||
|
a.sloK1PenaltyMod2 == b.sloK1PenaltyMod2 &&
|
||||||
|
a.sloK2PenaltyMod2 == b.sloK2PenaltyMod2);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STHdad& a, const STHdad& b)
|
||||||
|
{
|
||||||
|
return (a.lambdaCensus == b.lambdaCensus &&
|
||||||
|
a.lambdaAD == b.lambdaAD &&
|
||||||
|
a.ignoreSAD == b.ignoreSAD);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STColorCorrection& a, const STColorCorrection& b)
|
||||||
|
{
|
||||||
|
return (a.colorCorrection1 == b.colorCorrection1 &&
|
||||||
|
a.colorCorrection2 == b.colorCorrection2 &&
|
||||||
|
a.colorCorrection3 == b.colorCorrection3 &&
|
||||||
|
a.colorCorrection4 == b.colorCorrection4 &&
|
||||||
|
a.colorCorrection5 == b.colorCorrection5 &&
|
||||||
|
a.colorCorrection6 == b.colorCorrection6 &&
|
||||||
|
a.colorCorrection7 == b.colorCorrection7 &&
|
||||||
|
a.colorCorrection8 == b.colorCorrection8 &&
|
||||||
|
a.colorCorrection9 == b.colorCorrection9 &&
|
||||||
|
a.colorCorrection10 == b.colorCorrection10 &&
|
||||||
|
a.colorCorrection11 == b.colorCorrection11 &&
|
||||||
|
a.colorCorrection12 == b.colorCorrection12);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STAEControl& a, const STAEControl& b)
|
||||||
|
{
|
||||||
|
return (a.meanIntensitySetPoint == b.meanIntensitySetPoint);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STDepthTableControl& a, const STDepthTableControl& b)
|
||||||
|
{
|
||||||
|
return (a.depthUnits == b.depthUnits &&
|
||||||
|
a.depthClampMin == b.depthClampMin &&
|
||||||
|
a.depthClampMax == b.depthClampMax &&
|
||||||
|
a.disparityMode == b.disparityMode &&
|
||||||
|
a.disparityShift == b.disparityShift);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STCensusRadius& a, const STCensusRadius& b)
|
||||||
|
{
|
||||||
|
return (a.uDiameter == b.uDiameter &&
|
||||||
|
a.vDiameter == b.vDiameter);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool operator==(const STAFactor& a, const STAFactor& b)
|
||||||
|
{
|
||||||
|
return (fabs(a.amplitude - b.amplitude) < std::numeric_limits<float>::epsilon());
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif // R4XX_ADVANCED_MODE_HPP
|
|
@ -0,0 +1,46 @@
|
||||||
|
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||||
|
Copyright(c) 2015 Intel Corporation. All Rights Reserved. */
|
||||||
|
|
||||||
|
#ifndef LIBREALSENSE_RSUTIL2_H
|
||||||
|
#define LIBREALSENSE_RSUTIL2_H
|
||||||
|
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <math.h>
|
||||||
|
#include <float.h>
|
||||||
|
#include "h/rs_types.h"
|
||||||
|
#include "h/rs_sensor.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Given a point in 3D space, compute the corresponding pixel coordinates in an image with no distortion or forward distortion coefficients produced by the same camera */
|
||||||
|
void rs2_project_point_to_pixel(float pixel[2], const rs2_intrinsics* intrin, const float point[3]);
|
||||||
|
|
||||||
|
/* Given pixel coordinates and depth in an image with no distortion or inverse distortion coefficients, compute the corresponding point in 3D space relative to the same camera */
|
||||||
|
void rs2_deproject_pixel_to_point(float point[3], const rs2_intrinsics* intrin, const float pixel[2], float depth);
|
||||||
|
|
||||||
|
/* Transform 3D coordinates relative to one sensor to 3D coordinates relative to another viewpoint */
|
||||||
|
void rs2_transform_point_to_point(float to_point[3], const rs2_extrinsics* extrin, const float from_point[3]);
|
||||||
|
|
||||||
|
/* Calculate horizontal and vertical feild of view, based on video intrinsics */
|
||||||
|
void rs2_fov(const rs2_intrinsics* intrin, float to_fov[2]);
|
||||||
|
|
||||||
|
/* Find projected pixel with unknown depth search along line. */
|
||||||
|
void rs2_project_color_pixel_to_depth_pixel(float to_pixel[2],
|
||||||
|
const uint16_t* data, float depth_scale,
|
||||||
|
float depth_min, float depth_max,
|
||||||
|
const struct rs2_intrinsics* depth_intrin,
|
||||||
|
const struct rs2_intrinsics* color_intrin,
|
||||||
|
const struct rs2_extrinsics* color_to_depth,
|
||||||
|
const struct rs2_extrinsics* depth_to_color,
|
||||||
|
const float from_pixel[2]);
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // LIBREALSENSE_RSUTIL2_H
|
|
@ -0,0 +1,14 @@
|
||||||
|
#ifndef __LIKELY_H_INCLUDED__
|
||||||
|
#define __LIKELY_H_INCLUDED__
|
||||||
|
|
||||||
|
#if defined __GNUC__
|
||||||
|
#define likely(x) __builtin_expect ((x), 1)
|
||||||
|
#define unlikely(x) __builtin_expect ((x), 0)
|
||||||
|
#else
|
||||||
|
#define likely(x) (x)
|
||||||
|
#define unlikely(x) (x)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -0,0 +1,204 @@
|
||||||
|
/** @file
|
||||||
|
* @brief MAVLink comm protocol generated from SysMavlink.xml
|
||||||
|
* @see http://mavlink.org
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
#ifndef MAVLINK_SYSMAVLINK_H
|
||||||
|
#define MAVLINK_SYSMAVLINK_H
|
||||||
|
|
||||||
|
#ifndef MAVLINK_H
|
||||||
|
#error Wrong include order: MAVLINK_SYSMAVLINK.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#undef MAVLINK_THIS_XML_HASH
|
||||||
|
#define MAVLINK_THIS_XML_HASH 2384190490983077020
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE LENGTHS AND CRCS
|
||||||
|
|
||||||
|
#ifndef MAVLINK_MESSAGE_LENGTHS
|
||||||
|
#define MAVLINK_MESSAGE_LENGTHS {}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_MESSAGE_CRCS
|
||||||
|
#define MAVLINK_MESSAGE_CRCS {{11, 106, 1, 1, 0, 0, 0}, {12, 204, 1, 1, 0, 0, 0}, {13, 62, 38, 38, 0, 0, 0}, {14, 84, 1, 1, 0, 0, 0}, {15, 236, 56, 56, 0, 0, 0}, {16, 74, 246, 246, 0, 0, 0}, {17, 99, 209, 209, 0, 0, 0}, {18, 12, 5, 5, 0, 0, 0}, {19, 110, 42, 42, 0, 0, 0}, {121, 228, 1, 1, 0, 0, 0}, {122, 151, 20, 20, 0, 0, 0}, {123, 10, 61, 61, 0, 0, 0}, {124, 68, 44, 44, 0, 0, 0}, {125, 149, 36, 36, 0, 0, 0}, {126, 25, 1, 1, 0, 0, 0}}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "../protocol.h"
|
||||||
|
|
||||||
|
#define MAVLINK_ENABLED_SYSMAVLINK
|
||||||
|
|
||||||
|
// ENUM DEFINITIONS
|
||||||
|
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_DEVICE_REQUEST_ANSWER_TYPE
|
||||||
|
#define HAVE_ENUM_DEVICE_REQUEST_ANSWER_TYPE
|
||||||
|
typedef enum DEVICE_REQUEST_ANSWER_TYPE
|
||||||
|
{
|
||||||
|
PC2COM_OK=1, /* PC return ok to com board | */
|
||||||
|
COM2PC_OK=2, /* Com board return ok to PC | */
|
||||||
|
COM2SYS_OK=3, /* Com board return ok to sys board | */
|
||||||
|
SYS2COM_OK=4, /* Sys board return ok to com board | */
|
||||||
|
PC2SYS_OK=5, /* PC return ok to sys board | */
|
||||||
|
SYS2PC_OK=6, /* Sys board return ok to PC | */
|
||||||
|
DEVICE_REQUEST_ANSWER_TYPE_ENUM_END=7, /* | */
|
||||||
|
} DEVICE_REQUEST_ANSWER_TYPE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_LIDAR_WORKING_MODE
|
||||||
|
#define HAVE_ENUM_LIDAR_WORKING_MODE
|
||||||
|
typedef enum LIDAR_WORKING_MODE
|
||||||
|
{
|
||||||
|
NORMAL_MODE=1, /* Configure the LiDAR to operate in normal mode. | */
|
||||||
|
STANDBY_MODE=2, /* Configure the LiDAR to enter standby mode. | */
|
||||||
|
RAW_MODE=3, /* Configure the LiDAR to operate in raw mode. | */
|
||||||
|
LIDAR_WORKING_MODE_ENUM_END=4, /* | */
|
||||||
|
} LIDAR_WORKING_MODE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_LIDAR_WORKING_INTERNAL_MODE
|
||||||
|
#define HAVE_ENUM_LIDAR_WORKING_INTERNAL_MODE
|
||||||
|
typedef enum LIDAR_WORKING_INTERNAL_MODE
|
||||||
|
{
|
||||||
|
INTERNAL_NORMAL_MODE=1, /* Configure the LiDAR to operate in normal mode. | */
|
||||||
|
INTERNAL_RAW_MODE=2, /* Configure the LiDAR to operate in raw mode. | */
|
||||||
|
INTERNAL_STANDBY_MODE=3, /* Configure the LiDAR to enter standby mode. | */
|
||||||
|
INTERNAL_COM_MOTOR_STOP_MODE=4, /* Configure the LiDAR to enter 2D mode. | */
|
||||||
|
INTERNAL_APD_DEBUG_MODE=5, /* Configure the LiDAR to enter APD test mode. | */
|
||||||
|
INTERNAL_STRENGTH_DEBUG_MODE=6, /* Configure the LiDAR to strength test mode. | */
|
||||||
|
INTERNAL_DISTANCE_DEBUG_MODE=7, /* Configure the LiDAR to distance test mode. | */
|
||||||
|
INTERNAL_POINT_DEGUB_MODE=8, /* Configure the LiDAR to point test mode. | */
|
||||||
|
INTERNAL_CONTINUE_POINT_DEGUB_MODE=9, /* Configure the LiDAR to continue point test mode. | */
|
||||||
|
INTERNAL_LASER_TEST_MODE=10, /* Configure the LiDAR to laser 100KHZ test mode. | */
|
||||||
|
INTERNAL_IMU_QUATERNION_MODE=11, /* Configure the LiDAR to IMU quaternion dispay mode. | */
|
||||||
|
INTERNAL_IMU_ACC_GYRO_MODE=12, /* Configure the LiDAR to IMU riginion data test mode. | */
|
||||||
|
LIDAR_WORKING_INTERNAL_MODE_ENUM_END=13, /* | */
|
||||||
|
} LIDAR_WORKING_INTERNAL_MODE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_LIDAR_WORKING_STATUS
|
||||||
|
#define HAVE_ENUM_LIDAR_WORKING_STATUS
|
||||||
|
typedef enum LIDAR_WORKING_STATUS
|
||||||
|
{
|
||||||
|
WORK_MODE_STA=1, /* Status of lidar work mode 0:Nomal mode 1:Raw mode | */
|
||||||
|
LED_RING_LOST_RATE_STA=2, /* Status of led ring data lost status 0: lost rate ok 1:lost rate error | */
|
||||||
|
POINT_LOST_RATE_STA=4, /* Status of point cloud lost rate 0: lost rate ok 1:lost rate error | */
|
||||||
|
LED_RING_COMMAND_STA=8, /* Status of lidar command mode 0:LED command mode 1:other function work mode | */
|
||||||
|
IMU_WORK_STA=16, /* Status of IMU 0: IMU work ok 1: IMU work error | */
|
||||||
|
SYS_ENCODER_STA=32, /* Status of SYS encoder 0:encoder ok 1:encoder error | */
|
||||||
|
COM_ENCODER_STA=64, /* Status of COM encoder 0:encoder ok 1:encoder error | */
|
||||||
|
LIDAR_DATA_AVAILABLE=128, /* Status of lidar data available 0:Available 1:Not Available | */
|
||||||
|
LIDAR_WORKING_STATUS_ENUM_END=129, /* | */
|
||||||
|
} LIDAR_WORKING_STATUS;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_DEVICE_REQUEST_INTERNAL_DATA_TYPE
|
||||||
|
#define HAVE_ENUM_DEVICE_REQUEST_INTERNAL_DATA_TYPE
|
||||||
|
typedef enum DEVICE_REQUEST_INTERNAL_DATA_TYPE
|
||||||
|
{
|
||||||
|
INTERNAL_DATA_REQUEST_CLOCK_SYNC=1, /* Request for device state | */
|
||||||
|
INTERNAL_CMD_LIDAR_VERSION=2, /* Request get firmware version | */
|
||||||
|
INTERNAL_DATA_REQUEST_COM_FLASH_PARAMETER=3, /* Request for com flash paramteter | */
|
||||||
|
INTERNAL_DATA_REQUEST_SYS_FLASH_PARAMETER=4, /* Request for sys flash paramteter | */
|
||||||
|
DEVICE_REQUEST_INTERNAL_DATA_TYPE_ENUM_END=5, /* | */
|
||||||
|
} DEVICE_REQUEST_INTERNAL_DATA_TYPE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_DEVICE_REQUEST_DATA_TYPE
|
||||||
|
#define HAVE_ENUM_DEVICE_REQUEST_DATA_TYPE
|
||||||
|
typedef enum DEVICE_REQUEST_DATA_TYPE
|
||||||
|
{
|
||||||
|
DATA_REQUEST_CLOCK_SYNC=1, /* Request for device state | */
|
||||||
|
CMD_LIDAR_VERSION=2, /* Request get firmware version | */
|
||||||
|
DEVICE_REQUEST_DATA_TYPE_ENUM_END=3, /* | */
|
||||||
|
} DEVICE_REQUEST_DATA_TYPE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_DEVICE_COMMAND_TYPE
|
||||||
|
#define HAVE_ENUM_DEVICE_COMMAND_TYPE
|
||||||
|
typedef enum DEVICE_COMMAND_TYPE
|
||||||
|
{
|
||||||
|
CMD_LIDAR_SAVE_FLASH=1, /* Save lidar configuration to Flash memory | */
|
||||||
|
CMD_LIDAR_REBOOT=2, /* Reboot lidar | */
|
||||||
|
DEVICE_COMMAND_TYPE_ENUM_END=3, /* | */
|
||||||
|
} DEVICE_COMMAND_TYPE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_SYNC_TIME_TYPE
|
||||||
|
#define HAVE_ENUM_SYNC_TIME_TYPE
|
||||||
|
typedef enum SYNC_TIME_TYPE
|
||||||
|
{
|
||||||
|
CMD_SYNC_TIME_REQUEST=1, /* Lidar sync time request start | */
|
||||||
|
CMD_SYNC_TIME_RESPONSE=2, /* Lidar sync time request response | */
|
||||||
|
SYNC_TIME_TYPE_ENUM_END=3, /* | */
|
||||||
|
} SYNC_TIME_TYPE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @brief */
|
||||||
|
#ifndef HAVE_ENUM_LED_DISPLAY_MODE_SELECT
|
||||||
|
#define HAVE_ENUM_LED_DISPLAY_MODE_SELECT
|
||||||
|
typedef enum LED_DISPLAY_MODE_SELECT
|
||||||
|
{
|
||||||
|
LED_RING_COMMAND_MODE=1, /* Command display mode. | */
|
||||||
|
LED_RING_FUN_FORWARD_SLOW_MODE=2, /* Function mode forward at slow. | */
|
||||||
|
LED_RING_FUN_FORWARD_FAST_MODE=3, /* Function mode forward at fast. | */
|
||||||
|
LED_RING_FUN_REVERSE_SLOW_MODE=4, /* Function mode reverse at slow. | */
|
||||||
|
LED_RING_FUN_REVERSE_FAST_MODE=5, /* Function mode reverse at fast. | */
|
||||||
|
LED_RING_FUN_TRIPLE_FLIP_MODE=6, /* Function mode triple flip. | */
|
||||||
|
LED_RING_FUN_TRIPLE_BREATHING_MODE=7, /* Function mode triple breathing. | */
|
||||||
|
LED_RING_FUN_SIXSTAGE_BREATHING_MODE=8, /* Function mode six-stage breathing. | */
|
||||||
|
LED_DISPLAY_MODE_SELECT_ENUM_END=9, /* | */
|
||||||
|
} LED_DISPLAY_MODE_SELECT;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MAVLINK VERSION
|
||||||
|
|
||||||
|
#ifndef MAVLINK_VERSION
|
||||||
|
#define MAVLINK_VERSION 34
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if (MAVLINK_VERSION == 0)
|
||||||
|
#undef MAVLINK_VERSION
|
||||||
|
#define MAVLINK_VERSION 34
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE DEFINITIONS
|
||||||
|
#include "./mavlink_msg_device_request_data.h"
|
||||||
|
#include "./mavlink_msg_device_command.h"
|
||||||
|
#include "./mavlink_msg_ret_lidar_version.h"
|
||||||
|
#include "./mavlink_msg_config_lidar_working_mode.h"
|
||||||
|
#include "./mavlink_msg_config_led_ring_table_packet.h"
|
||||||
|
#include "./mavlink_msg_ret_lidar_distance_data_packet.h"
|
||||||
|
#include "./mavlink_msg_ret_lidar_auxiliary_data_packet.h"
|
||||||
|
#include "./mavlink_msg_ret_lidar_time_sync_data.h"
|
||||||
|
#include "./mavlink_msg_ret_imu_attitude_data_packet.h"
|
||||||
|
|
||||||
|
// base include
|
||||||
|
|
||||||
|
|
||||||
|
#undef MAVLINK_THIS_XML_HASH
|
||||||
|
#define MAVLINK_THIS_XML_HASH 2384190490983077020
|
||||||
|
|
||||||
|
#if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
|
||||||
|
# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_DEVICE_REQUEST_DATA, MAVLINK_MESSAGE_INFO_DEVICE_COMMAND, MAVLINK_MESSAGE_INFO_RET_LIDAR_VERSION, MAVLINK_MESSAGE_INFO_CONFIG_LIDAR_WORKING_MODE, MAVLINK_MESSAGE_INFO_CONFIG_LED_RING_TABLE_PACKET, MAVLINK_MESSAGE_INFO_RET_LIDAR_DISTANCE_DATA_PACKET, MAVLINK_MESSAGE_INFO_RET_LIDAR_AUXILIARY_DATA_PACKET, MAVLINK_MESSAGE_INFO_RET_LIDAR_TIME_SYNC_DATA, MAVLINK_MESSAGE_INFO_RET_IMU_ATTITUDE_DATA_PACKET, MAVLINK_MESSAGE_INFO_DEVICE_REQUEST_ANSWER, MAVLINK_MESSAGE_INFO_DEVICE_DEBUG_MODE_PARAMS, MAVLINK_MESSAGE_INFO_SET_COM_NECESSARY_MEASURE_PARAMETER, MAVLINK_MESSAGE_INFO_SET_SYS_NECESSARY_MEASURE_PARAMETER, MAVLINK_MESSAGE_INFO_RET_TDC_POINT_DEBUG_PACKET, MAVLINK_MESSAGE_INFO_DEVICE_REQUEST_INTERNAL_DATA}
|
||||||
|
# define MAVLINK_MESSAGE_NAMES {{ "CONFIG_LED_RING_TABLE_PACKET", 15 }, { "CONFIG_LIDAR_WORKING_MODE", 14 }, { "DEVICE_COMMAND", 12 }, { "DEVICE_DEBUG_MODE_PARAMS", 122 }, { "DEVICE_REQUEST_ANSWER", 121 }, { "DEVICE_REQUEST_DATA", 11 }, { "DEVICE_REQUEST_INTERNAL_DATA", 126 }, { "RET_IMU_ATTITUDE_DATA_PACKET", 19 }, { "RET_LIDAR_AUXILIARY_DATA_PACKET", 17 }, { "RET_LIDAR_DISTANCE_DATA_PACKET", 16 }, { "RET_LIDAR_TIME_SYNC_DATA", 18 }, { "RET_LIDAR_VERSION", 13 }, { "RET_TDC_POINT_DEBUG_PACKET", 125 }, { "SET_COM_NECESSARY_MEASURE_PARAMETER", 123 }, { "SET_SYS_NECESSARY_MEASURE_PARAMETER", 124 }}
|
||||||
|
# if MAVLINK_COMMAND_24BIT
|
||||||
|
# include "../mavlink_get_info.h"
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif // __cplusplus
|
||||||
|
#endif // MAVLINK_SYSMAVLINK_H
|
|
@ -0,0 +1,34 @@
|
||||||
|
/** @file
|
||||||
|
* @brief MAVLink comm protocol built from SysMavlink.xml
|
||||||
|
* @see http://mavlink.org
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
#ifndef MAVLINK_H
|
||||||
|
#define MAVLINK_H
|
||||||
|
|
||||||
|
#define MAVLINK_PRIMARY_XML_HASH 2384190490983077020
|
||||||
|
|
||||||
|
#ifndef MAVLINK_STX
|
||||||
|
#define MAVLINK_STX 253
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_ENDIAN
|
||||||
|
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_ALIGNED_FIELDS
|
||||||
|
#define MAVLINK_ALIGNED_FIELDS 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_CRC_EXTRA
|
||||||
|
#define MAVLINK_CRC_EXTRA 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_COMMAND_24BIT 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "version.h"
|
||||||
|
#include "SysMavlink.h"
|
||||||
|
|
||||||
|
#endif // MAVLINK_H
|
|
@ -0,0 +1,305 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE CONFIG_LED_RING_TABLE_PACKET PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET 15
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_config_led_ring_table_packet_t {
|
||||||
|
uint32_t led_rotation_period; /*< Rotation period.*/
|
||||||
|
uint32_t led_zero_point_offset; /*< Zero offset unit in milliseconds.*/
|
||||||
|
uint16_t packet_id; /*< Data packet ID.*/
|
||||||
|
uint8_t led_display_mode; /*< LED display mode selection.*/
|
||||||
|
uint8_t led_table[45]; /*< LED display field data packet, 45 bytes represent the status of 360 LEDs bit by bit.*/
|
||||||
|
} mavlink_config_led_ring_table_packet_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN 56
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN 56
|
||||||
|
#define MAVLINK_MSG_ID_15_LEN 56
|
||||||
|
#define MAVLINK_MSG_ID_15_MIN_LEN 56
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC 236
|
||||||
|
#define MAVLINK_MSG_ID_15_CRC 236
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_CONFIG_LED_RING_TABLE_PACKET_FIELD_LED_TABLE_LEN 45
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_CONFIG_LED_RING_TABLE_PACKET { \
|
||||||
|
15, \
|
||||||
|
"CONFIG_LED_RING_TABLE_PACKET", \
|
||||||
|
5, \
|
||||||
|
{ { "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_config_led_ring_table_packet_t, packet_id) }, \
|
||||||
|
{ "led_rotation_period", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_config_led_ring_table_packet_t, led_rotation_period) }, \
|
||||||
|
{ "led_zero_point_offset", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_config_led_ring_table_packet_t, led_zero_point_offset) }, \
|
||||||
|
{ "led_display_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_config_led_ring_table_packet_t, led_display_mode) }, \
|
||||||
|
{ "led_table", NULL, MAVLINK_TYPE_UINT8_T, 45, 11, offsetof(mavlink_config_led_ring_table_packet_t, led_table) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_CONFIG_LED_RING_TABLE_PACKET { \
|
||||||
|
"CONFIG_LED_RING_TABLE_PACKET", \
|
||||||
|
5, \
|
||||||
|
{ { "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_config_led_ring_table_packet_t, packet_id) }, \
|
||||||
|
{ "led_rotation_period", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_config_led_ring_table_packet_t, led_rotation_period) }, \
|
||||||
|
{ "led_zero_point_offset", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_config_led_ring_table_packet_t, led_zero_point_offset) }, \
|
||||||
|
{ "led_display_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_config_led_ring_table_packet_t, led_display_mode) }, \
|
||||||
|
{ "led_table", NULL, MAVLINK_TYPE_UINT8_T, 45, 11, offsetof(mavlink_config_led_ring_table_packet_t, led_table) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a config_led_ring_table_packet message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param led_rotation_period Rotation period.
|
||||||
|
* @param led_zero_point_offset Zero offset unit in milliseconds.
|
||||||
|
* @param led_display_mode LED display mode selection.
|
||||||
|
* @param led_table LED display field data packet, 45 bytes represent the status of 360 LEDs bit by bit.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_led_ring_table_packet_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint16_t packet_id, uint32_t led_rotation_period, uint32_t led_zero_point_offset, uint8_t led_display_mode, const uint8_t *led_table)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, led_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 4, led_zero_point_offset);
|
||||||
|
_mav_put_uint16_t(buf, 8, packet_id);
|
||||||
|
_mav_put_uint8_t(buf, 10, led_display_mode);
|
||||||
|
_mav_put_uint8_t_array(buf, 11, led_table, 45);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_config_led_ring_table_packet_t packet;
|
||||||
|
packet.led_rotation_period = led_rotation_period;
|
||||||
|
packet.led_zero_point_offset = led_zero_point_offset;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.led_display_mode = led_display_mode;
|
||||||
|
mav_array_memcpy(packet.led_table, led_table, sizeof(uint8_t)*45);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a config_led_ring_table_packet message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param led_rotation_period Rotation period.
|
||||||
|
* @param led_zero_point_offset Zero offset unit in milliseconds.
|
||||||
|
* @param led_display_mode LED display mode selection.
|
||||||
|
* @param led_table LED display field data packet, 45 bytes represent the status of 360 LEDs bit by bit.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_led_ring_table_packet_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint16_t packet_id,uint32_t led_rotation_period,uint32_t led_zero_point_offset,uint8_t led_display_mode,const uint8_t *led_table)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, led_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 4, led_zero_point_offset);
|
||||||
|
_mav_put_uint16_t(buf, 8, packet_id);
|
||||||
|
_mav_put_uint8_t(buf, 10, led_display_mode);
|
||||||
|
_mav_put_uint8_t_array(buf, 11, led_table, 45);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_config_led_ring_table_packet_t packet;
|
||||||
|
packet.led_rotation_period = led_rotation_period;
|
||||||
|
packet.led_zero_point_offset = led_zero_point_offset;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.led_display_mode = led_display_mode;
|
||||||
|
mav_array_memcpy(packet.led_table, led_table, sizeof(uint8_t)*45);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a config_led_ring_table_packet struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param config_led_ring_table_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_led_ring_table_packet_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_config_led_ring_table_packet_t* config_led_ring_table_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_config_led_ring_table_packet_pack(system_id, component_id, msg, config_led_ring_table_packet->packet_id, config_led_ring_table_packet->led_rotation_period, config_led_ring_table_packet->led_zero_point_offset, config_led_ring_table_packet->led_display_mode, config_led_ring_table_packet->led_table);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a config_led_ring_table_packet struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param config_led_ring_table_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_led_ring_table_packet_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_config_led_ring_table_packet_t* config_led_ring_table_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_config_led_ring_table_packet_pack_chan(system_id, component_id, chan, msg, config_led_ring_table_packet->packet_id, config_led_ring_table_packet->led_rotation_period, config_led_ring_table_packet->led_zero_point_offset, config_led_ring_table_packet->led_display_mode, config_led_ring_table_packet->led_table);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a config_led_ring_table_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param led_rotation_period Rotation period.
|
||||||
|
* @param led_zero_point_offset Zero offset unit in milliseconds.
|
||||||
|
* @param led_display_mode LED display mode selection.
|
||||||
|
* @param led_table LED display field data packet, 45 bytes represent the status of 360 LEDs bit by bit.
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_config_led_ring_table_packet_send(mavlink_channel_t chan, uint16_t packet_id, uint32_t led_rotation_period, uint32_t led_zero_point_offset, uint8_t led_display_mode, const uint8_t *led_table)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, led_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 4, led_zero_point_offset);
|
||||||
|
_mav_put_uint16_t(buf, 8, packet_id);
|
||||||
|
_mav_put_uint8_t(buf, 10, led_display_mode);
|
||||||
|
_mav_put_uint8_t_array(buf, 11, led_table, 45);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET, buf, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_config_led_ring_table_packet_t packet;
|
||||||
|
packet.led_rotation_period = led_rotation_period;
|
||||||
|
packet.led_zero_point_offset = led_zero_point_offset;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.led_display_mode = led_display_mode;
|
||||||
|
mav_array_memcpy(packet.led_table, led_table, sizeof(uint8_t)*45);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET, (const char *)&packet, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a config_led_ring_table_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_config_led_ring_table_packet_send_struct(mavlink_channel_t chan, const mavlink_config_led_ring_table_packet_t* config_led_ring_table_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_config_led_ring_table_packet_send(chan, config_led_ring_table_packet->packet_id, config_led_ring_table_packet->led_rotation_period, config_led_ring_table_packet->led_zero_point_offset, config_led_ring_table_packet->led_display_mode, config_led_ring_table_packet->led_table);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET, (const char *)config_led_ring_table_packet, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_config_led_ring_table_packet_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t packet_id, uint32_t led_rotation_period, uint32_t led_zero_point_offset, uint8_t led_display_mode, const uint8_t *led_table)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint32_t(buf, 0, led_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 4, led_zero_point_offset);
|
||||||
|
_mav_put_uint16_t(buf, 8, packet_id);
|
||||||
|
_mav_put_uint8_t(buf, 10, led_display_mode);
|
||||||
|
_mav_put_uint8_t_array(buf, 11, led_table, 45);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET, buf, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_config_led_ring_table_packet_t *packet = (mavlink_config_led_ring_table_packet_t *)msgbuf;
|
||||||
|
packet->led_rotation_period = led_rotation_period;
|
||||||
|
packet->led_zero_point_offset = led_zero_point_offset;
|
||||||
|
packet->packet_id = packet_id;
|
||||||
|
packet->led_display_mode = led_display_mode;
|
||||||
|
mav_array_memcpy(packet->led_table, led_table, sizeof(uint8_t)*45);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET, (const char *)packet, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE CONFIG_LED_RING_TABLE_PACKET UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field packet_id from config_led_ring_table_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet ID.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_led_ring_table_packet_get_packet_id(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 8);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field led_rotation_period from config_led_ring_table_packet message
|
||||||
|
*
|
||||||
|
* @return Rotation period.
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_config_led_ring_table_packet_get_led_rotation_period(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field led_zero_point_offset from config_led_ring_table_packet message
|
||||||
|
*
|
||||||
|
* @return Zero offset unit in milliseconds.
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_config_led_ring_table_packet_get_led_zero_point_offset(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 4);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field led_display_mode from config_led_ring_table_packet message
|
||||||
|
*
|
||||||
|
* @return LED display mode selection.
|
||||||
|
*/
|
||||||
|
static inline uint8_t mavlink_msg_config_led_ring_table_packet_get_led_display_mode(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t(msg, 10);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field led_table from config_led_ring_table_packet message
|
||||||
|
*
|
||||||
|
* @return LED display field data packet, 45 bytes represent the status of 360 LEDs bit by bit.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_led_ring_table_packet_get_led_table(const mavlink_message_t* msg, uint8_t *led_table)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t_array(msg, led_table, 45, 11);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a config_led_ring_table_packet message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param config_led_ring_table_packet C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_config_led_ring_table_packet_decode(const mavlink_message_t* msg, mavlink_config_led_ring_table_packet_t* config_led_ring_table_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
config_led_ring_table_packet->led_rotation_period = mavlink_msg_config_led_ring_table_packet_get_led_rotation_period(msg);
|
||||||
|
config_led_ring_table_packet->led_zero_point_offset = mavlink_msg_config_led_ring_table_packet_get_led_zero_point_offset(msg);
|
||||||
|
config_led_ring_table_packet->packet_id = mavlink_msg_config_led_ring_table_packet_get_packet_id(msg);
|
||||||
|
config_led_ring_table_packet->led_display_mode = mavlink_msg_config_led_ring_table_packet_get_led_display_mode(msg);
|
||||||
|
mavlink_msg_config_led_ring_table_packet_get_led_table(msg, config_led_ring_table_packet->led_table);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN? msg->len : MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN;
|
||||||
|
memset(config_led_ring_table_packet, 0, MAVLINK_MSG_ID_CONFIG_LED_RING_TABLE_PACKET_LEN);
|
||||||
|
memcpy(config_led_ring_table_packet, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,213 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE CONFIG_LIDAR_WORKING_MODE PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE 14
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_config_lidar_working_mode_t {
|
||||||
|
uint8_t request_type; /*< Types of operating modes for LiDAR.*/
|
||||||
|
} mavlink_config_lidar_working_mode_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_14_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_14_MIN_LEN 1
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC 84
|
||||||
|
#define MAVLINK_MSG_ID_14_CRC 84
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_CONFIG_LIDAR_WORKING_MODE { \
|
||||||
|
14, \
|
||||||
|
"CONFIG_LIDAR_WORKING_MODE", \
|
||||||
|
1, \
|
||||||
|
{ { "request_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_config_lidar_working_mode_t, request_type) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_CONFIG_LIDAR_WORKING_MODE { \
|
||||||
|
"CONFIG_LIDAR_WORKING_MODE", \
|
||||||
|
1, \
|
||||||
|
{ { "request_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_config_lidar_working_mode_t, request_type) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a config_lidar_working_mode message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param request_type Types of operating modes for LiDAR.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_lidar_working_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_config_lidar_working_mode_t packet;
|
||||||
|
packet.request_type = request_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a config_lidar_working_mode message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param request_type Types of operating modes for LiDAR.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_lidar_working_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_config_lidar_working_mode_t packet;
|
||||||
|
packet.request_type = request_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a config_lidar_working_mode struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param config_lidar_working_mode C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_lidar_working_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_config_lidar_working_mode_t* config_lidar_working_mode)
|
||||||
|
{
|
||||||
|
return mavlink_msg_config_lidar_working_mode_pack(system_id, component_id, msg, config_lidar_working_mode->request_type);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a config_lidar_working_mode struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param config_lidar_working_mode C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_config_lidar_working_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_config_lidar_working_mode_t* config_lidar_working_mode)
|
||||||
|
{
|
||||||
|
return mavlink_msg_config_lidar_working_mode_pack_chan(system_id, component_id, chan, msg, config_lidar_working_mode->request_type);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a config_lidar_working_mode message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param request_type Types of operating modes for LiDAR.
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_config_lidar_working_mode_send(mavlink_channel_t chan, uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE, buf, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_config_lidar_working_mode_t packet;
|
||||||
|
packet.request_type = request_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE, (const char *)&packet, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a config_lidar_working_mode message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_config_lidar_working_mode_send_struct(mavlink_channel_t chan, const mavlink_config_lidar_working_mode_t* config_lidar_working_mode)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_config_lidar_working_mode_send(chan, config_lidar_working_mode->request_type);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE, (const char *)config_lidar_working_mode, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_config_lidar_working_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE, buf, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_config_lidar_working_mode_t *packet = (mavlink_config_lidar_working_mode_t *)msgbuf;
|
||||||
|
packet->request_type = request_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE, (const char *)packet, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_MIN_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE CONFIG_LIDAR_WORKING_MODE UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field request_type from config_lidar_working_mode message
|
||||||
|
*
|
||||||
|
* @return Types of operating modes for LiDAR.
|
||||||
|
*/
|
||||||
|
static inline uint8_t mavlink_msg_config_lidar_working_mode_get_request_type(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a config_lidar_working_mode message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param config_lidar_working_mode C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_config_lidar_working_mode_decode(const mavlink_message_t* msg, mavlink_config_lidar_working_mode_t* config_lidar_working_mode)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
config_lidar_working_mode->request_type = mavlink_msg_config_lidar_working_mode_get_request_type(msg);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN? msg->len : MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN;
|
||||||
|
memset(config_lidar_working_mode, 0, MAVLINK_MSG_ID_CONFIG_LIDAR_WORKING_MODE_LEN);
|
||||||
|
memcpy(config_lidar_working_mode, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,213 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE DEVICE_COMMAND PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_COMMAND 12
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_device_command_t {
|
||||||
|
uint8_t cmd_type; /*< Command*/
|
||||||
|
} mavlink_device_command_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_COMMAND_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_12_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_12_MIN_LEN 1
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_COMMAND_CRC 204
|
||||||
|
#define MAVLINK_MSG_ID_12_CRC 204
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_DEVICE_COMMAND { \
|
||||||
|
12, \
|
||||||
|
"DEVICE_COMMAND", \
|
||||||
|
1, \
|
||||||
|
{ { "cmd_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_device_command_t, cmd_type) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_DEVICE_COMMAND { \
|
||||||
|
"DEVICE_COMMAND", \
|
||||||
|
1, \
|
||||||
|
{ { "cmd_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_device_command_t, cmd_type) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a device_command message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param cmd_type Command
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint8_t cmd_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_DEVICE_COMMAND_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, cmd_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_device_command_t packet;
|
||||||
|
packet.cmd_type = cmd_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_DEVICE_COMMAND;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a device_command message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param cmd_type Command
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint8_t cmd_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_DEVICE_COMMAND_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, cmd_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_device_command_t packet;
|
||||||
|
packet.cmd_type = cmd_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_DEVICE_COMMAND;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a device_command struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param device_command C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_command_t* device_command)
|
||||||
|
{
|
||||||
|
return mavlink_msg_device_command_pack(system_id, component_id, msg, device_command->cmd_type);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a device_command struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param device_command C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_command_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_command_t* device_command)
|
||||||
|
{
|
||||||
|
return mavlink_msg_device_command_pack_chan(system_id, component_id, chan, msg, device_command->cmd_type);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a device_command message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param cmd_type Command
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_device_command_send(mavlink_channel_t chan, uint8_t cmd_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_DEVICE_COMMAND_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, cmd_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_COMMAND, buf, MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_device_command_t packet;
|
||||||
|
packet.cmd_type = cmd_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a device_command message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_device_command_send_struct(mavlink_channel_t chan, const mavlink_device_command_t* device_command)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_device_command_send(chan, device_command->cmd_type);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_COMMAND, (const char *)device_command, MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_DEVICE_COMMAND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_device_command_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint8_t(buf, 0, cmd_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_COMMAND, buf, MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_device_command_t *packet = (mavlink_device_command_t *)msgbuf;
|
||||||
|
packet->cmd_type = cmd_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_COMMAND, (const char *)packet, MAVLINK_MSG_ID_DEVICE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN, MAVLINK_MSG_ID_DEVICE_COMMAND_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE DEVICE_COMMAND UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field cmd_type from device_command message
|
||||||
|
*
|
||||||
|
* @return Command
|
||||||
|
*/
|
||||||
|
static inline uint8_t mavlink_msg_device_command_get_cmd_type(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a device_command message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param device_command C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_device_command_decode(const mavlink_message_t* msg, mavlink_device_command_t* device_command)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
device_command->cmd_type = mavlink_msg_device_command_get_cmd_type(msg);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_COMMAND_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_COMMAND_LEN;
|
||||||
|
memset(device_command, 0, MAVLINK_MSG_ID_DEVICE_COMMAND_LEN);
|
||||||
|
memcpy(device_command, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,213 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE DEVICE_REQUEST_DATA PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_REQUEST_DATA 11
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_device_request_data_t {
|
||||||
|
uint8_t request_type; /*< Type of the needed data*/
|
||||||
|
} mavlink_device_request_data_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_11_LEN 1
|
||||||
|
#define MAVLINK_MSG_ID_11_MIN_LEN 1
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC 106
|
||||||
|
#define MAVLINK_MSG_ID_11_CRC 106
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_DEVICE_REQUEST_DATA { \
|
||||||
|
11, \
|
||||||
|
"DEVICE_REQUEST_DATA", \
|
||||||
|
1, \
|
||||||
|
{ { "request_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_device_request_data_t, request_type) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_DEVICE_REQUEST_DATA { \
|
||||||
|
"DEVICE_REQUEST_DATA", \
|
||||||
|
1, \
|
||||||
|
{ { "request_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_device_request_data_t, request_type) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a device_request_data message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param request_type Type of the needed data
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_device_request_data_t packet;
|
||||||
|
packet.request_type = request_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_DEVICE_REQUEST_DATA;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a device_request_data message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param request_type Type of the needed data
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_device_request_data_t packet;
|
||||||
|
packet.request_type = request_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_DEVICE_REQUEST_DATA;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a device_request_data struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param device_request_data C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_request_data_t* device_request_data)
|
||||||
|
{
|
||||||
|
return mavlink_msg_device_request_data_pack(system_id, component_id, msg, device_request_data->request_type);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a device_request_data struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param device_request_data C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_device_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_request_data_t* device_request_data)
|
||||||
|
{
|
||||||
|
return mavlink_msg_device_request_data_pack_chan(system_id, component_id, chan, msg, device_request_data->request_type);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a device_request_data message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param request_type Type of the needed data
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_device_request_data_send(mavlink_channel_t chan, uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN];
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA, buf, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_device_request_data_t packet;
|
||||||
|
packet.request_type = request_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a device_request_data message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_device_request_data_send_struct(mavlink_channel_t chan, const mavlink_device_request_data_t* device_request_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_device_request_data_send(chan, device_request_data->request_type);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA, (const char *)device_request_data, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_device_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_type)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint8_t(buf, 0, request_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA, buf, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_device_request_data_t *packet = (mavlink_device_request_data_t *)msgbuf;
|
||||||
|
packet->request_type = request_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE DEVICE_REQUEST_DATA UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field request_type from device_request_data message
|
||||||
|
*
|
||||||
|
* @return Type of the needed data
|
||||||
|
*/
|
||||||
|
static inline uint8_t mavlink_msg_device_request_data_get_request_type(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a device_request_data message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param device_request_data C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_device_request_data_decode(const mavlink_message_t* msg, mavlink_device_request_data_t* device_request_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
device_request_data->request_type = mavlink_msg_device_request_data_get_request_type(msg);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN;
|
||||||
|
memset(device_request_data, 0, MAVLINK_MSG_ID_DEVICE_REQUEST_DATA_LEN);
|
||||||
|
memcpy(device_request_data, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,282 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE RET_IMU_ATTITUDE_DATA_PACKET PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET 19
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_ret_imu_attitude_data_packet_t {
|
||||||
|
float quaternion[4]; /*< Quaternion Array.*/
|
||||||
|
float angular_velocity[3]; /*< Three-axis angular velocity values.*/
|
||||||
|
float linear_acceleration[3]; /*< Three-axis acceleration values.*/
|
||||||
|
uint16_t packet_id; /*< Data packet ID.*/
|
||||||
|
} mavlink_ret_imu_attitude_data_packet_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN 42
|
||||||
|
#define MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN 42
|
||||||
|
#define MAVLINK_MSG_ID_19_LEN 42
|
||||||
|
#define MAVLINK_MSG_ID_19_MIN_LEN 42
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC 110
|
||||||
|
#define MAVLINK_MSG_ID_19_CRC 110
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_RET_IMU_ATTITUDE_DATA_PACKET_FIELD_QUATERNION_LEN 4
|
||||||
|
#define MAVLINK_MSG_RET_IMU_ATTITUDE_DATA_PACKET_FIELD_ANGULAR_VELOCITY_LEN 3
|
||||||
|
#define MAVLINK_MSG_RET_IMU_ATTITUDE_DATA_PACKET_FIELD_LINEAR_ACCELERATION_LEN 3
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_IMU_ATTITUDE_DATA_PACKET { \
|
||||||
|
19, \
|
||||||
|
"RET_IMU_ATTITUDE_DATA_PACKET", \
|
||||||
|
4, \
|
||||||
|
{ { "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_ret_imu_attitude_data_packet_t, packet_id) }, \
|
||||||
|
{ "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_ret_imu_attitude_data_packet_t, quaternion) }, \
|
||||||
|
{ "angular_velocity", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_ret_imu_attitude_data_packet_t, angular_velocity) }, \
|
||||||
|
{ "linear_acceleration", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_ret_imu_attitude_data_packet_t, linear_acceleration) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_IMU_ATTITUDE_DATA_PACKET { \
|
||||||
|
"RET_IMU_ATTITUDE_DATA_PACKET", \
|
||||||
|
4, \
|
||||||
|
{ { "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_ret_imu_attitude_data_packet_t, packet_id) }, \
|
||||||
|
{ "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_ret_imu_attitude_data_packet_t, quaternion) }, \
|
||||||
|
{ "angular_velocity", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_ret_imu_attitude_data_packet_t, angular_velocity) }, \
|
||||||
|
{ "linear_acceleration", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_ret_imu_attitude_data_packet_t, linear_acceleration) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_imu_attitude_data_packet message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param quaternion Quaternion Array.
|
||||||
|
* @param angular_velocity Three-axis angular velocity values.
|
||||||
|
* @param linear_acceleration Three-axis acceleration values.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint16_t packet_id, const float *quaternion, const float *angular_velocity, const float *linear_acceleration)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint16_t(buf, 40, packet_id);
|
||||||
|
_mav_put_float_array(buf, 0, quaternion, 4);
|
||||||
|
_mav_put_float_array(buf, 16, angular_velocity, 3);
|
||||||
|
_mav_put_float_array(buf, 28, linear_acceleration, 3);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_imu_attitude_data_packet_t packet;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
|
||||||
|
mav_array_memcpy(packet.angular_velocity, angular_velocity, sizeof(float)*3);
|
||||||
|
mav_array_memcpy(packet.linear_acceleration, linear_acceleration, sizeof(float)*3);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_imu_attitude_data_packet message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param quaternion Quaternion Array.
|
||||||
|
* @param angular_velocity Three-axis angular velocity values.
|
||||||
|
* @param linear_acceleration Three-axis acceleration values.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint16_t packet_id,const float *quaternion,const float *angular_velocity,const float *linear_acceleration)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint16_t(buf, 40, packet_id);
|
||||||
|
_mav_put_float_array(buf, 0, quaternion, 4);
|
||||||
|
_mav_put_float_array(buf, 16, angular_velocity, 3);
|
||||||
|
_mav_put_float_array(buf, 28, linear_acceleration, 3);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_imu_attitude_data_packet_t packet;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
|
||||||
|
mav_array_memcpy(packet.angular_velocity, angular_velocity, sizeof(float)*3);
|
||||||
|
mav_array_memcpy(packet.linear_acceleration, linear_acceleration, sizeof(float)*3);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_imu_attitude_data_packet struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_imu_attitude_data_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ret_imu_attitude_data_packet_t* ret_imu_attitude_data_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_imu_attitude_data_packet_pack(system_id, component_id, msg, ret_imu_attitude_data_packet->packet_id, ret_imu_attitude_data_packet->quaternion, ret_imu_attitude_data_packet->angular_velocity, ret_imu_attitude_data_packet->linear_acceleration);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_imu_attitude_data_packet struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_imu_attitude_data_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ret_imu_attitude_data_packet_t* ret_imu_attitude_data_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_imu_attitude_data_packet_pack_chan(system_id, component_id, chan, msg, ret_imu_attitude_data_packet->packet_id, ret_imu_attitude_data_packet->quaternion, ret_imu_attitude_data_packet->angular_velocity, ret_imu_attitude_data_packet->linear_acceleration);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_imu_attitude_data_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param quaternion Quaternion Array.
|
||||||
|
* @param angular_velocity Three-axis angular velocity values.
|
||||||
|
* @param linear_acceleration Three-axis acceleration values.
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_ret_imu_attitude_data_packet_send(mavlink_channel_t chan, uint16_t packet_id, const float *quaternion, const float *angular_velocity, const float *linear_acceleration)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint16_t(buf, 40, packet_id);
|
||||||
|
_mav_put_float_array(buf, 0, quaternion, 4);
|
||||||
|
_mav_put_float_array(buf, 16, angular_velocity, 3);
|
||||||
|
_mav_put_float_array(buf, 28, linear_acceleration, 3);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET, buf, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_imu_attitude_data_packet_t packet;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
|
||||||
|
mav_array_memcpy(packet.angular_velocity, angular_velocity, sizeof(float)*3);
|
||||||
|
mav_array_memcpy(packet.linear_acceleration, linear_acceleration, sizeof(float)*3);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET, (const char *)&packet, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_imu_attitude_data_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_imu_attitude_data_packet_send_struct(mavlink_channel_t chan, const mavlink_ret_imu_attitude_data_packet_t* ret_imu_attitude_data_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_ret_imu_attitude_data_packet_send(chan, ret_imu_attitude_data_packet->packet_id, ret_imu_attitude_data_packet->quaternion, ret_imu_attitude_data_packet->angular_velocity, ret_imu_attitude_data_packet->linear_acceleration);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET, (const char *)ret_imu_attitude_data_packet, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_imu_attitude_data_packet_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t packet_id, const float *quaternion, const float *angular_velocity, const float *linear_acceleration)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint16_t(buf, 40, packet_id);
|
||||||
|
_mav_put_float_array(buf, 0, quaternion, 4);
|
||||||
|
_mav_put_float_array(buf, 16, angular_velocity, 3);
|
||||||
|
_mav_put_float_array(buf, 28, linear_acceleration, 3);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET, buf, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_imu_attitude_data_packet_t *packet = (mavlink_ret_imu_attitude_data_packet_t *)msgbuf;
|
||||||
|
packet->packet_id = packet_id;
|
||||||
|
mav_array_memcpy(packet->quaternion, quaternion, sizeof(float)*4);
|
||||||
|
mav_array_memcpy(packet->angular_velocity, angular_velocity, sizeof(float)*3);
|
||||||
|
mav_array_memcpy(packet->linear_acceleration, linear_acceleration, sizeof(float)*3);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET, (const char *)packet, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE RET_IMU_ATTITUDE_DATA_PACKET UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field packet_id from ret_imu_attitude_data_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet ID.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_get_packet_id(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 40);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field quaternion from ret_imu_attitude_data_packet message
|
||||||
|
*
|
||||||
|
* @return Quaternion Array.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_get_quaternion(const mavlink_message_t* msg, float *quaternion)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float_array(msg, quaternion, 4, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field angular_velocity from ret_imu_attitude_data_packet message
|
||||||
|
*
|
||||||
|
* @return Three-axis angular velocity values.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_get_angular_velocity(const mavlink_message_t* msg, float *angular_velocity)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float_array(msg, angular_velocity, 3, 16);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field linear_acceleration from ret_imu_attitude_data_packet message
|
||||||
|
*
|
||||||
|
* @return Three-axis acceleration values.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_imu_attitude_data_packet_get_linear_acceleration(const mavlink_message_t* msg, float *linear_acceleration)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float_array(msg, linear_acceleration, 3, 28);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a ret_imu_attitude_data_packet message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param ret_imu_attitude_data_packet C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_imu_attitude_data_packet_decode(const mavlink_message_t* msg, mavlink_ret_imu_attitude_data_packet_t* ret_imu_attitude_data_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_ret_imu_attitude_data_packet_get_quaternion(msg, ret_imu_attitude_data_packet->quaternion);
|
||||||
|
mavlink_msg_ret_imu_attitude_data_packet_get_angular_velocity(msg, ret_imu_attitude_data_packet->angular_velocity);
|
||||||
|
mavlink_msg_ret_imu_attitude_data_packet_get_linear_acceleration(msg, ret_imu_attitude_data_packet->linear_acceleration);
|
||||||
|
ret_imu_attitude_data_packet->packet_id = mavlink_msg_ret_imu_attitude_data_packet_get_packet_id(msg);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN? msg->len : MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN;
|
||||||
|
memset(ret_imu_attitude_data_packet, 0, MAVLINK_MSG_ID_RET_IMU_ATTITUDE_DATA_PACKET_LEN);
|
||||||
|
memcpy(ret_imu_attitude_data_packet, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,805 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE RET_LIDAR_AUXILIARY_DATA_PACKET PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET 17
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_ret_lidar_auxiliary_data_packet_t {
|
||||||
|
uint32_t lidar_sync_delay_time; /*< Delay time of upper computer communication(us).*/
|
||||||
|
uint32_t time_stamp_s_step; /*< LiDAR operational timestamp in seconds.*/
|
||||||
|
uint32_t time_stamp_us_step; /*< LiDAR operational timestamp in microsecond .*/
|
||||||
|
uint32_t sys_rotation_period; /*< LiDAR low-speed motor rotation period in microsecond .*/
|
||||||
|
uint32_t com_rotation_period; /*< LiDAR high-speed motor rotation period in microsecond .*/
|
||||||
|
float com_horizontal_angle_start; /*< The first data in the current data packet is the horizontal angle,Distance data applicable to RET_LIDAR_DISTANCE_DATA_PACKET data packet and reflectivity data of RET_LIDAR_AUXILIARY_DATA_PACKET data packet.*/
|
||||||
|
float com_horizontal_angle_step; /*< Angle interval between two adjacent data in the horizontal direction.*/
|
||||||
|
float sys_vertical_angle_start; /*< The vertical angle of the first data in the current data packet.*/
|
||||||
|
float sys_vertical_angle_span; /*< The angular span between adjacent data in the vertical direction of the current data packet.*/
|
||||||
|
float apd_temperature; /*< APD temperature value*/
|
||||||
|
float dirty_index; /*< Protective cover dirt detection index*/
|
||||||
|
float imu_temperature; /*< IMU temperature value*/
|
||||||
|
float up_optical_q; /*< Up optical communication quality.*/
|
||||||
|
float down_optical_q; /*< Downlink optical communication quality.*/
|
||||||
|
float apd_voltage; /*< APD voltage value.*/
|
||||||
|
float imu_angle_x_offset; /*< IMU x-axis installation angle error.*/
|
||||||
|
float imu_angle_y_offset; /*< IMU y-axis installation angle error.*/
|
||||||
|
float imu_angle_z_offset; /*< IMU z-axis installation angle error.*/
|
||||||
|
float b_axis_dist; /*< Laser calibration b distance compensation.*/
|
||||||
|
float theta_angle; /*< Laser calibration theta angle compensation.*/
|
||||||
|
float ksi_angle; /*< Laser calibration ksi angle compensation.*/
|
||||||
|
uint16_t packet_id; /*< Data packet ID.*/
|
||||||
|
uint16_t payload_size; /*< Data packet payload size.*/
|
||||||
|
uint8_t lidar_work_status; /*< LiDAR operational state indicator.*/
|
||||||
|
uint8_t reflect_data[120]; /*< reflectivity data*/
|
||||||
|
} mavlink_ret_lidar_auxiliary_data_packet_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN 209
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN 209
|
||||||
|
#define MAVLINK_MSG_ID_17_LEN 209
|
||||||
|
#define MAVLINK_MSG_ID_17_MIN_LEN 209
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC 99
|
||||||
|
#define MAVLINK_MSG_ID_17_CRC 99
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_RET_LIDAR_AUXILIARY_DATA_PACKET_FIELD_REFLECT_DATA_LEN 120
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_AUXILIARY_DATA_PACKET { \
|
||||||
|
17, \
|
||||||
|
"RET_LIDAR_AUXILIARY_DATA_PACKET", \
|
||||||
|
25, \
|
||||||
|
{ { "lidar_work_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 88, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, lidar_work_status) }, \
|
||||||
|
{ "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, packet_id) }, \
|
||||||
|
{ "payload_size", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, payload_size) }, \
|
||||||
|
{ "lidar_sync_delay_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, lidar_sync_delay_time) }, \
|
||||||
|
{ "time_stamp_s_step", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, time_stamp_s_step) }, \
|
||||||
|
{ "time_stamp_us_step", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, time_stamp_us_step) }, \
|
||||||
|
{ "sys_rotation_period", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, sys_rotation_period) }, \
|
||||||
|
{ "com_rotation_period", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, com_rotation_period) }, \
|
||||||
|
{ "com_horizontal_angle_start", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, com_horizontal_angle_start) }, \
|
||||||
|
{ "com_horizontal_angle_step", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, com_horizontal_angle_step) }, \
|
||||||
|
{ "sys_vertical_angle_start", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, sys_vertical_angle_start) }, \
|
||||||
|
{ "sys_vertical_angle_span", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, sys_vertical_angle_span) }, \
|
||||||
|
{ "apd_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, apd_temperature) }, \
|
||||||
|
{ "dirty_index", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, dirty_index) }, \
|
||||||
|
{ "imu_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_temperature) }, \
|
||||||
|
{ "up_optical_q", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, up_optical_q) }, \
|
||||||
|
{ "down_optical_q", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, down_optical_q) }, \
|
||||||
|
{ "apd_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, apd_voltage) }, \
|
||||||
|
{ "imu_angle_x_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_angle_x_offset) }, \
|
||||||
|
{ "imu_angle_y_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_angle_y_offset) }, \
|
||||||
|
{ "imu_angle_z_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_angle_z_offset) }, \
|
||||||
|
{ "b_axis_dist", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, b_axis_dist) }, \
|
||||||
|
{ "theta_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, theta_angle) }, \
|
||||||
|
{ "ksi_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, ksi_angle) }, \
|
||||||
|
{ "reflect_data", NULL, MAVLINK_TYPE_UINT8_T, 120, 89, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, reflect_data) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_AUXILIARY_DATA_PACKET { \
|
||||||
|
"RET_LIDAR_AUXILIARY_DATA_PACKET", \
|
||||||
|
25, \
|
||||||
|
{ { "lidar_work_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 88, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, lidar_work_status) }, \
|
||||||
|
{ "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, packet_id) }, \
|
||||||
|
{ "payload_size", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, payload_size) }, \
|
||||||
|
{ "lidar_sync_delay_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, lidar_sync_delay_time) }, \
|
||||||
|
{ "time_stamp_s_step", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, time_stamp_s_step) }, \
|
||||||
|
{ "time_stamp_us_step", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, time_stamp_us_step) }, \
|
||||||
|
{ "sys_rotation_period", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, sys_rotation_period) }, \
|
||||||
|
{ "com_rotation_period", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, com_rotation_period) }, \
|
||||||
|
{ "com_horizontal_angle_start", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, com_horizontal_angle_start) }, \
|
||||||
|
{ "com_horizontal_angle_step", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, com_horizontal_angle_step) }, \
|
||||||
|
{ "sys_vertical_angle_start", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, sys_vertical_angle_start) }, \
|
||||||
|
{ "sys_vertical_angle_span", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, sys_vertical_angle_span) }, \
|
||||||
|
{ "apd_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, apd_temperature) }, \
|
||||||
|
{ "dirty_index", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, dirty_index) }, \
|
||||||
|
{ "imu_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_temperature) }, \
|
||||||
|
{ "up_optical_q", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, up_optical_q) }, \
|
||||||
|
{ "down_optical_q", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, down_optical_q) }, \
|
||||||
|
{ "apd_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, apd_voltage) }, \
|
||||||
|
{ "imu_angle_x_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_angle_x_offset) }, \
|
||||||
|
{ "imu_angle_y_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_angle_y_offset) }, \
|
||||||
|
{ "imu_angle_z_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, imu_angle_z_offset) }, \
|
||||||
|
{ "b_axis_dist", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, b_axis_dist) }, \
|
||||||
|
{ "theta_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, theta_angle) }, \
|
||||||
|
{ "ksi_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, ksi_angle) }, \
|
||||||
|
{ "reflect_data", NULL, MAVLINK_TYPE_UINT8_T, 120, 89, offsetof(mavlink_ret_lidar_auxiliary_data_packet_t, reflect_data) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_auxiliary_data_packet message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param lidar_work_status LiDAR operational state indicator.
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param payload_size Data packet payload size.
|
||||||
|
* @param lidar_sync_delay_time Delay time of upper computer communication(us).
|
||||||
|
* @param time_stamp_s_step LiDAR operational timestamp in seconds.
|
||||||
|
* @param time_stamp_us_step LiDAR operational timestamp in microsecond .
|
||||||
|
* @param sys_rotation_period LiDAR low-speed motor rotation period in microsecond .
|
||||||
|
* @param com_rotation_period LiDAR high-speed motor rotation period in microsecond .
|
||||||
|
* @param com_horizontal_angle_start The first data in the current data packet is the horizontal angle,Distance data applicable to RET_LIDAR_DISTANCE_DATA_PACKET data packet and reflectivity data of RET_LIDAR_AUXILIARY_DATA_PACKET data packet.
|
||||||
|
* @param com_horizontal_angle_step Angle interval between two adjacent data in the horizontal direction.
|
||||||
|
* @param sys_vertical_angle_start The vertical angle of the first data in the current data packet.
|
||||||
|
* @param sys_vertical_angle_span The angular span between adjacent data in the vertical direction of the current data packet.
|
||||||
|
* @param apd_temperature APD temperature value
|
||||||
|
* @param dirty_index Protective cover dirt detection index
|
||||||
|
* @param imu_temperature IMU temperature value
|
||||||
|
* @param up_optical_q Up optical communication quality.
|
||||||
|
* @param down_optical_q Downlink optical communication quality.
|
||||||
|
* @param apd_voltage APD voltage value.
|
||||||
|
* @param imu_angle_x_offset IMU x-axis installation angle error.
|
||||||
|
* @param imu_angle_y_offset IMU y-axis installation angle error.
|
||||||
|
* @param imu_angle_z_offset IMU z-axis installation angle error.
|
||||||
|
* @param b_axis_dist Laser calibration b distance compensation.
|
||||||
|
* @param theta_angle Laser calibration theta angle compensation.
|
||||||
|
* @param ksi_angle Laser calibration ksi angle compensation.
|
||||||
|
* @param reflect_data reflectivity data
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_auxiliary_data_packet_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint8_t lidar_work_status, uint16_t packet_id, uint16_t payload_size, uint32_t lidar_sync_delay_time, uint32_t time_stamp_s_step, uint32_t time_stamp_us_step, uint32_t sys_rotation_period, uint32_t com_rotation_period, float com_horizontal_angle_start, float com_horizontal_angle_step, float sys_vertical_angle_start, float sys_vertical_angle_span, float apd_temperature, float dirty_index, float imu_temperature, float up_optical_q, float down_optical_q, float apd_voltage, float imu_angle_x_offset, float imu_angle_y_offset, float imu_angle_z_offset, float b_axis_dist, float theta_angle, float ksi_angle, const uint8_t *reflect_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_delay_time);
|
||||||
|
_mav_put_uint32_t(buf, 4, time_stamp_s_step);
|
||||||
|
_mav_put_uint32_t(buf, 8, time_stamp_us_step);
|
||||||
|
_mav_put_uint32_t(buf, 12, sys_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 16, com_rotation_period);
|
||||||
|
_mav_put_float(buf, 20, com_horizontal_angle_start);
|
||||||
|
_mav_put_float(buf, 24, com_horizontal_angle_step);
|
||||||
|
_mav_put_float(buf, 28, sys_vertical_angle_start);
|
||||||
|
_mav_put_float(buf, 32, sys_vertical_angle_span);
|
||||||
|
_mav_put_float(buf, 36, apd_temperature);
|
||||||
|
_mav_put_float(buf, 40, dirty_index);
|
||||||
|
_mav_put_float(buf, 44, imu_temperature);
|
||||||
|
_mav_put_float(buf, 48, up_optical_q);
|
||||||
|
_mav_put_float(buf, 52, down_optical_q);
|
||||||
|
_mav_put_float(buf, 56, apd_voltage);
|
||||||
|
_mav_put_float(buf, 60, imu_angle_x_offset);
|
||||||
|
_mav_put_float(buf, 64, imu_angle_y_offset);
|
||||||
|
_mav_put_float(buf, 68, imu_angle_z_offset);
|
||||||
|
_mav_put_float(buf, 72, b_axis_dist);
|
||||||
|
_mav_put_float(buf, 76, theta_angle);
|
||||||
|
_mav_put_float(buf, 80, ksi_angle);
|
||||||
|
_mav_put_uint16_t(buf, 84, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 86, payload_size);
|
||||||
|
_mav_put_uint8_t(buf, 88, lidar_work_status);
|
||||||
|
_mav_put_uint8_t_array(buf, 89, reflect_data, 120);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_auxiliary_data_packet_t packet;
|
||||||
|
packet.lidar_sync_delay_time = lidar_sync_delay_time;
|
||||||
|
packet.time_stamp_s_step = time_stamp_s_step;
|
||||||
|
packet.time_stamp_us_step = time_stamp_us_step;
|
||||||
|
packet.sys_rotation_period = sys_rotation_period;
|
||||||
|
packet.com_rotation_period = com_rotation_period;
|
||||||
|
packet.com_horizontal_angle_start = com_horizontal_angle_start;
|
||||||
|
packet.com_horizontal_angle_step = com_horizontal_angle_step;
|
||||||
|
packet.sys_vertical_angle_start = sys_vertical_angle_start;
|
||||||
|
packet.sys_vertical_angle_span = sys_vertical_angle_span;
|
||||||
|
packet.apd_temperature = apd_temperature;
|
||||||
|
packet.dirty_index = dirty_index;
|
||||||
|
packet.imu_temperature = imu_temperature;
|
||||||
|
packet.up_optical_q = up_optical_q;
|
||||||
|
packet.down_optical_q = down_optical_q;
|
||||||
|
packet.apd_voltage = apd_voltage;
|
||||||
|
packet.imu_angle_x_offset = imu_angle_x_offset;
|
||||||
|
packet.imu_angle_y_offset = imu_angle_y_offset;
|
||||||
|
packet.imu_angle_z_offset = imu_angle_z_offset;
|
||||||
|
packet.b_axis_dist = b_axis_dist;
|
||||||
|
packet.theta_angle = theta_angle;
|
||||||
|
packet.ksi_angle = ksi_angle;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.payload_size = payload_size;
|
||||||
|
packet.lidar_work_status = lidar_work_status;
|
||||||
|
mav_array_memcpy(packet.reflect_data, reflect_data, sizeof(uint8_t)*120);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_auxiliary_data_packet message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param lidar_work_status LiDAR operational state indicator.
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param payload_size Data packet payload size.
|
||||||
|
* @param lidar_sync_delay_time Delay time of upper computer communication(us).
|
||||||
|
* @param time_stamp_s_step LiDAR operational timestamp in seconds.
|
||||||
|
* @param time_stamp_us_step LiDAR operational timestamp in microsecond .
|
||||||
|
* @param sys_rotation_period LiDAR low-speed motor rotation period in microsecond .
|
||||||
|
* @param com_rotation_period LiDAR high-speed motor rotation period in microsecond .
|
||||||
|
* @param com_horizontal_angle_start The first data in the current data packet is the horizontal angle,Distance data applicable to RET_LIDAR_DISTANCE_DATA_PACKET data packet and reflectivity data of RET_LIDAR_AUXILIARY_DATA_PACKET data packet.
|
||||||
|
* @param com_horizontal_angle_step Angle interval between two adjacent data in the horizontal direction.
|
||||||
|
* @param sys_vertical_angle_start The vertical angle of the first data in the current data packet.
|
||||||
|
* @param sys_vertical_angle_span The angular span between adjacent data in the vertical direction of the current data packet.
|
||||||
|
* @param apd_temperature APD temperature value
|
||||||
|
* @param dirty_index Protective cover dirt detection index
|
||||||
|
* @param imu_temperature IMU temperature value
|
||||||
|
* @param up_optical_q Up optical communication quality.
|
||||||
|
* @param down_optical_q Downlink optical communication quality.
|
||||||
|
* @param apd_voltage APD voltage value.
|
||||||
|
* @param imu_angle_x_offset IMU x-axis installation angle error.
|
||||||
|
* @param imu_angle_y_offset IMU y-axis installation angle error.
|
||||||
|
* @param imu_angle_z_offset IMU z-axis installation angle error.
|
||||||
|
* @param b_axis_dist Laser calibration b distance compensation.
|
||||||
|
* @param theta_angle Laser calibration theta angle compensation.
|
||||||
|
* @param ksi_angle Laser calibration ksi angle compensation.
|
||||||
|
* @param reflect_data reflectivity data
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_auxiliary_data_packet_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint8_t lidar_work_status,uint16_t packet_id,uint16_t payload_size,uint32_t lidar_sync_delay_time,uint32_t time_stamp_s_step,uint32_t time_stamp_us_step,uint32_t sys_rotation_period,uint32_t com_rotation_period,float com_horizontal_angle_start,float com_horizontal_angle_step,float sys_vertical_angle_start,float sys_vertical_angle_span,float apd_temperature,float dirty_index,float imu_temperature,float up_optical_q,float down_optical_q,float apd_voltage,float imu_angle_x_offset,float imu_angle_y_offset,float imu_angle_z_offset,float b_axis_dist,float theta_angle,float ksi_angle,const uint8_t *reflect_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_delay_time);
|
||||||
|
_mav_put_uint32_t(buf, 4, time_stamp_s_step);
|
||||||
|
_mav_put_uint32_t(buf, 8, time_stamp_us_step);
|
||||||
|
_mav_put_uint32_t(buf, 12, sys_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 16, com_rotation_period);
|
||||||
|
_mav_put_float(buf, 20, com_horizontal_angle_start);
|
||||||
|
_mav_put_float(buf, 24, com_horizontal_angle_step);
|
||||||
|
_mav_put_float(buf, 28, sys_vertical_angle_start);
|
||||||
|
_mav_put_float(buf, 32, sys_vertical_angle_span);
|
||||||
|
_mav_put_float(buf, 36, apd_temperature);
|
||||||
|
_mav_put_float(buf, 40, dirty_index);
|
||||||
|
_mav_put_float(buf, 44, imu_temperature);
|
||||||
|
_mav_put_float(buf, 48, up_optical_q);
|
||||||
|
_mav_put_float(buf, 52, down_optical_q);
|
||||||
|
_mav_put_float(buf, 56, apd_voltage);
|
||||||
|
_mav_put_float(buf, 60, imu_angle_x_offset);
|
||||||
|
_mav_put_float(buf, 64, imu_angle_y_offset);
|
||||||
|
_mav_put_float(buf, 68, imu_angle_z_offset);
|
||||||
|
_mav_put_float(buf, 72, b_axis_dist);
|
||||||
|
_mav_put_float(buf, 76, theta_angle);
|
||||||
|
_mav_put_float(buf, 80, ksi_angle);
|
||||||
|
_mav_put_uint16_t(buf, 84, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 86, payload_size);
|
||||||
|
_mav_put_uint8_t(buf, 88, lidar_work_status);
|
||||||
|
_mav_put_uint8_t_array(buf, 89, reflect_data, 120);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_auxiliary_data_packet_t packet;
|
||||||
|
packet.lidar_sync_delay_time = lidar_sync_delay_time;
|
||||||
|
packet.time_stamp_s_step = time_stamp_s_step;
|
||||||
|
packet.time_stamp_us_step = time_stamp_us_step;
|
||||||
|
packet.sys_rotation_period = sys_rotation_period;
|
||||||
|
packet.com_rotation_period = com_rotation_period;
|
||||||
|
packet.com_horizontal_angle_start = com_horizontal_angle_start;
|
||||||
|
packet.com_horizontal_angle_step = com_horizontal_angle_step;
|
||||||
|
packet.sys_vertical_angle_start = sys_vertical_angle_start;
|
||||||
|
packet.sys_vertical_angle_span = sys_vertical_angle_span;
|
||||||
|
packet.apd_temperature = apd_temperature;
|
||||||
|
packet.dirty_index = dirty_index;
|
||||||
|
packet.imu_temperature = imu_temperature;
|
||||||
|
packet.up_optical_q = up_optical_q;
|
||||||
|
packet.down_optical_q = down_optical_q;
|
||||||
|
packet.apd_voltage = apd_voltage;
|
||||||
|
packet.imu_angle_x_offset = imu_angle_x_offset;
|
||||||
|
packet.imu_angle_y_offset = imu_angle_y_offset;
|
||||||
|
packet.imu_angle_z_offset = imu_angle_z_offset;
|
||||||
|
packet.b_axis_dist = b_axis_dist;
|
||||||
|
packet.theta_angle = theta_angle;
|
||||||
|
packet.ksi_angle = ksi_angle;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.payload_size = payload_size;
|
||||||
|
packet.lidar_work_status = lidar_work_status;
|
||||||
|
mav_array_memcpy(packet.reflect_data, reflect_data, sizeof(uint8_t)*120);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_auxiliary_data_packet struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_auxiliary_data_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_auxiliary_data_packet_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ret_lidar_auxiliary_data_packet_t* ret_lidar_auxiliary_data_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_auxiliary_data_packet_pack(system_id, component_id, msg, ret_lidar_auxiliary_data_packet->lidar_work_status, ret_lidar_auxiliary_data_packet->packet_id, ret_lidar_auxiliary_data_packet->payload_size, ret_lidar_auxiliary_data_packet->lidar_sync_delay_time, ret_lidar_auxiliary_data_packet->time_stamp_s_step, ret_lidar_auxiliary_data_packet->time_stamp_us_step, ret_lidar_auxiliary_data_packet->sys_rotation_period, ret_lidar_auxiliary_data_packet->com_rotation_period, ret_lidar_auxiliary_data_packet->com_horizontal_angle_start, ret_lidar_auxiliary_data_packet->com_horizontal_angle_step, ret_lidar_auxiliary_data_packet->sys_vertical_angle_start, ret_lidar_auxiliary_data_packet->sys_vertical_angle_span, ret_lidar_auxiliary_data_packet->apd_temperature, ret_lidar_auxiliary_data_packet->dirty_index, ret_lidar_auxiliary_data_packet->imu_temperature, ret_lidar_auxiliary_data_packet->up_optical_q, ret_lidar_auxiliary_data_packet->down_optical_q, ret_lidar_auxiliary_data_packet->apd_voltage, ret_lidar_auxiliary_data_packet->imu_angle_x_offset, ret_lidar_auxiliary_data_packet->imu_angle_y_offset, ret_lidar_auxiliary_data_packet->imu_angle_z_offset, ret_lidar_auxiliary_data_packet->b_axis_dist, ret_lidar_auxiliary_data_packet->theta_angle, ret_lidar_auxiliary_data_packet->ksi_angle, ret_lidar_auxiliary_data_packet->reflect_data);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_auxiliary_data_packet struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_auxiliary_data_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_auxiliary_data_packet_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ret_lidar_auxiliary_data_packet_t* ret_lidar_auxiliary_data_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_auxiliary_data_packet_pack_chan(system_id, component_id, chan, msg, ret_lidar_auxiliary_data_packet->lidar_work_status, ret_lidar_auxiliary_data_packet->packet_id, ret_lidar_auxiliary_data_packet->payload_size, ret_lidar_auxiliary_data_packet->lidar_sync_delay_time, ret_lidar_auxiliary_data_packet->time_stamp_s_step, ret_lidar_auxiliary_data_packet->time_stamp_us_step, ret_lidar_auxiliary_data_packet->sys_rotation_period, ret_lidar_auxiliary_data_packet->com_rotation_period, ret_lidar_auxiliary_data_packet->com_horizontal_angle_start, ret_lidar_auxiliary_data_packet->com_horizontal_angle_step, ret_lidar_auxiliary_data_packet->sys_vertical_angle_start, ret_lidar_auxiliary_data_packet->sys_vertical_angle_span, ret_lidar_auxiliary_data_packet->apd_temperature, ret_lidar_auxiliary_data_packet->dirty_index, ret_lidar_auxiliary_data_packet->imu_temperature, ret_lidar_auxiliary_data_packet->up_optical_q, ret_lidar_auxiliary_data_packet->down_optical_q, ret_lidar_auxiliary_data_packet->apd_voltage, ret_lidar_auxiliary_data_packet->imu_angle_x_offset, ret_lidar_auxiliary_data_packet->imu_angle_y_offset, ret_lidar_auxiliary_data_packet->imu_angle_z_offset, ret_lidar_auxiliary_data_packet->b_axis_dist, ret_lidar_auxiliary_data_packet->theta_angle, ret_lidar_auxiliary_data_packet->ksi_angle, ret_lidar_auxiliary_data_packet->reflect_data);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_auxiliary_data_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param lidar_work_status LiDAR operational state indicator.
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param payload_size Data packet payload size.
|
||||||
|
* @param lidar_sync_delay_time Delay time of upper computer communication(us).
|
||||||
|
* @param time_stamp_s_step LiDAR operational timestamp in seconds.
|
||||||
|
* @param time_stamp_us_step LiDAR operational timestamp in microsecond .
|
||||||
|
* @param sys_rotation_period LiDAR low-speed motor rotation period in microsecond .
|
||||||
|
* @param com_rotation_period LiDAR high-speed motor rotation period in microsecond .
|
||||||
|
* @param com_horizontal_angle_start The first data in the current data packet is the horizontal angle,Distance data applicable to RET_LIDAR_DISTANCE_DATA_PACKET data packet and reflectivity data of RET_LIDAR_AUXILIARY_DATA_PACKET data packet.
|
||||||
|
* @param com_horizontal_angle_step Angle interval between two adjacent data in the horizontal direction.
|
||||||
|
* @param sys_vertical_angle_start The vertical angle of the first data in the current data packet.
|
||||||
|
* @param sys_vertical_angle_span The angular span between adjacent data in the vertical direction of the current data packet.
|
||||||
|
* @param apd_temperature APD temperature value
|
||||||
|
* @param dirty_index Protective cover dirt detection index
|
||||||
|
* @param imu_temperature IMU temperature value
|
||||||
|
* @param up_optical_q Up optical communication quality.
|
||||||
|
* @param down_optical_q Downlink optical communication quality.
|
||||||
|
* @param apd_voltage APD voltage value.
|
||||||
|
* @param imu_angle_x_offset IMU x-axis installation angle error.
|
||||||
|
* @param imu_angle_y_offset IMU y-axis installation angle error.
|
||||||
|
* @param imu_angle_z_offset IMU z-axis installation angle error.
|
||||||
|
* @param b_axis_dist Laser calibration b distance compensation.
|
||||||
|
* @param theta_angle Laser calibration theta angle compensation.
|
||||||
|
* @param ksi_angle Laser calibration ksi angle compensation.
|
||||||
|
* @param reflect_data reflectivity data
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_ret_lidar_auxiliary_data_packet_send(mavlink_channel_t chan, uint8_t lidar_work_status, uint16_t packet_id, uint16_t payload_size, uint32_t lidar_sync_delay_time, uint32_t time_stamp_s_step, uint32_t time_stamp_us_step, uint32_t sys_rotation_period, uint32_t com_rotation_period, float com_horizontal_angle_start, float com_horizontal_angle_step, float sys_vertical_angle_start, float sys_vertical_angle_span, float apd_temperature, float dirty_index, float imu_temperature, float up_optical_q, float down_optical_q, float apd_voltage, float imu_angle_x_offset, float imu_angle_y_offset, float imu_angle_z_offset, float b_axis_dist, float theta_angle, float ksi_angle, const uint8_t *reflect_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_delay_time);
|
||||||
|
_mav_put_uint32_t(buf, 4, time_stamp_s_step);
|
||||||
|
_mav_put_uint32_t(buf, 8, time_stamp_us_step);
|
||||||
|
_mav_put_uint32_t(buf, 12, sys_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 16, com_rotation_period);
|
||||||
|
_mav_put_float(buf, 20, com_horizontal_angle_start);
|
||||||
|
_mav_put_float(buf, 24, com_horizontal_angle_step);
|
||||||
|
_mav_put_float(buf, 28, sys_vertical_angle_start);
|
||||||
|
_mav_put_float(buf, 32, sys_vertical_angle_span);
|
||||||
|
_mav_put_float(buf, 36, apd_temperature);
|
||||||
|
_mav_put_float(buf, 40, dirty_index);
|
||||||
|
_mav_put_float(buf, 44, imu_temperature);
|
||||||
|
_mav_put_float(buf, 48, up_optical_q);
|
||||||
|
_mav_put_float(buf, 52, down_optical_q);
|
||||||
|
_mav_put_float(buf, 56, apd_voltage);
|
||||||
|
_mav_put_float(buf, 60, imu_angle_x_offset);
|
||||||
|
_mav_put_float(buf, 64, imu_angle_y_offset);
|
||||||
|
_mav_put_float(buf, 68, imu_angle_z_offset);
|
||||||
|
_mav_put_float(buf, 72, b_axis_dist);
|
||||||
|
_mav_put_float(buf, 76, theta_angle);
|
||||||
|
_mav_put_float(buf, 80, ksi_angle);
|
||||||
|
_mav_put_uint16_t(buf, 84, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 86, payload_size);
|
||||||
|
_mav_put_uint8_t(buf, 88, lidar_work_status);
|
||||||
|
_mav_put_uint8_t_array(buf, 89, reflect_data, 120);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET, buf, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_auxiliary_data_packet_t packet;
|
||||||
|
packet.lidar_sync_delay_time = lidar_sync_delay_time;
|
||||||
|
packet.time_stamp_s_step = time_stamp_s_step;
|
||||||
|
packet.time_stamp_us_step = time_stamp_us_step;
|
||||||
|
packet.sys_rotation_period = sys_rotation_period;
|
||||||
|
packet.com_rotation_period = com_rotation_period;
|
||||||
|
packet.com_horizontal_angle_start = com_horizontal_angle_start;
|
||||||
|
packet.com_horizontal_angle_step = com_horizontal_angle_step;
|
||||||
|
packet.sys_vertical_angle_start = sys_vertical_angle_start;
|
||||||
|
packet.sys_vertical_angle_span = sys_vertical_angle_span;
|
||||||
|
packet.apd_temperature = apd_temperature;
|
||||||
|
packet.dirty_index = dirty_index;
|
||||||
|
packet.imu_temperature = imu_temperature;
|
||||||
|
packet.up_optical_q = up_optical_q;
|
||||||
|
packet.down_optical_q = down_optical_q;
|
||||||
|
packet.apd_voltage = apd_voltage;
|
||||||
|
packet.imu_angle_x_offset = imu_angle_x_offset;
|
||||||
|
packet.imu_angle_y_offset = imu_angle_y_offset;
|
||||||
|
packet.imu_angle_z_offset = imu_angle_z_offset;
|
||||||
|
packet.b_axis_dist = b_axis_dist;
|
||||||
|
packet.theta_angle = theta_angle;
|
||||||
|
packet.ksi_angle = ksi_angle;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.payload_size = payload_size;
|
||||||
|
packet.lidar_work_status = lidar_work_status;
|
||||||
|
mav_array_memcpy(packet.reflect_data, reflect_data, sizeof(uint8_t)*120);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET, (const char *)&packet, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_auxiliary_data_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_auxiliary_data_packet_send_struct(mavlink_channel_t chan, const mavlink_ret_lidar_auxiliary_data_packet_t* ret_lidar_auxiliary_data_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_ret_lidar_auxiliary_data_packet_send(chan, ret_lidar_auxiliary_data_packet->lidar_work_status, ret_lidar_auxiliary_data_packet->packet_id, ret_lidar_auxiliary_data_packet->payload_size, ret_lidar_auxiliary_data_packet->lidar_sync_delay_time, ret_lidar_auxiliary_data_packet->time_stamp_s_step, ret_lidar_auxiliary_data_packet->time_stamp_us_step, ret_lidar_auxiliary_data_packet->sys_rotation_period, ret_lidar_auxiliary_data_packet->com_rotation_period, ret_lidar_auxiliary_data_packet->com_horizontal_angle_start, ret_lidar_auxiliary_data_packet->com_horizontal_angle_step, ret_lidar_auxiliary_data_packet->sys_vertical_angle_start, ret_lidar_auxiliary_data_packet->sys_vertical_angle_span, ret_lidar_auxiliary_data_packet->apd_temperature, ret_lidar_auxiliary_data_packet->dirty_index, ret_lidar_auxiliary_data_packet->imu_temperature, ret_lidar_auxiliary_data_packet->up_optical_q, ret_lidar_auxiliary_data_packet->down_optical_q, ret_lidar_auxiliary_data_packet->apd_voltage, ret_lidar_auxiliary_data_packet->imu_angle_x_offset, ret_lidar_auxiliary_data_packet->imu_angle_y_offset, ret_lidar_auxiliary_data_packet->imu_angle_z_offset, ret_lidar_auxiliary_data_packet->b_axis_dist, ret_lidar_auxiliary_data_packet->theta_angle, ret_lidar_auxiliary_data_packet->ksi_angle, ret_lidar_auxiliary_data_packet->reflect_data);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET, (const char *)ret_lidar_auxiliary_data_packet, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_auxiliary_data_packet_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t lidar_work_status, uint16_t packet_id, uint16_t payload_size, uint32_t lidar_sync_delay_time, uint32_t time_stamp_s_step, uint32_t time_stamp_us_step, uint32_t sys_rotation_period, uint32_t com_rotation_period, float com_horizontal_angle_start, float com_horizontal_angle_step, float sys_vertical_angle_start, float sys_vertical_angle_span, float apd_temperature, float dirty_index, float imu_temperature, float up_optical_q, float down_optical_q, float apd_voltage, float imu_angle_x_offset, float imu_angle_y_offset, float imu_angle_z_offset, float b_axis_dist, float theta_angle, float ksi_angle, const uint8_t *reflect_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_delay_time);
|
||||||
|
_mav_put_uint32_t(buf, 4, time_stamp_s_step);
|
||||||
|
_mav_put_uint32_t(buf, 8, time_stamp_us_step);
|
||||||
|
_mav_put_uint32_t(buf, 12, sys_rotation_period);
|
||||||
|
_mav_put_uint32_t(buf, 16, com_rotation_period);
|
||||||
|
_mav_put_float(buf, 20, com_horizontal_angle_start);
|
||||||
|
_mav_put_float(buf, 24, com_horizontal_angle_step);
|
||||||
|
_mav_put_float(buf, 28, sys_vertical_angle_start);
|
||||||
|
_mav_put_float(buf, 32, sys_vertical_angle_span);
|
||||||
|
_mav_put_float(buf, 36, apd_temperature);
|
||||||
|
_mav_put_float(buf, 40, dirty_index);
|
||||||
|
_mav_put_float(buf, 44, imu_temperature);
|
||||||
|
_mav_put_float(buf, 48, up_optical_q);
|
||||||
|
_mav_put_float(buf, 52, down_optical_q);
|
||||||
|
_mav_put_float(buf, 56, apd_voltage);
|
||||||
|
_mav_put_float(buf, 60, imu_angle_x_offset);
|
||||||
|
_mav_put_float(buf, 64, imu_angle_y_offset);
|
||||||
|
_mav_put_float(buf, 68, imu_angle_z_offset);
|
||||||
|
_mav_put_float(buf, 72, b_axis_dist);
|
||||||
|
_mav_put_float(buf, 76, theta_angle);
|
||||||
|
_mav_put_float(buf, 80, ksi_angle);
|
||||||
|
_mav_put_uint16_t(buf, 84, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 86, payload_size);
|
||||||
|
_mav_put_uint8_t(buf, 88, lidar_work_status);
|
||||||
|
_mav_put_uint8_t_array(buf, 89, reflect_data, 120);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET, buf, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_auxiliary_data_packet_t *packet = (mavlink_ret_lidar_auxiliary_data_packet_t *)msgbuf;
|
||||||
|
packet->lidar_sync_delay_time = lidar_sync_delay_time;
|
||||||
|
packet->time_stamp_s_step = time_stamp_s_step;
|
||||||
|
packet->time_stamp_us_step = time_stamp_us_step;
|
||||||
|
packet->sys_rotation_period = sys_rotation_period;
|
||||||
|
packet->com_rotation_period = com_rotation_period;
|
||||||
|
packet->com_horizontal_angle_start = com_horizontal_angle_start;
|
||||||
|
packet->com_horizontal_angle_step = com_horizontal_angle_step;
|
||||||
|
packet->sys_vertical_angle_start = sys_vertical_angle_start;
|
||||||
|
packet->sys_vertical_angle_span = sys_vertical_angle_span;
|
||||||
|
packet->apd_temperature = apd_temperature;
|
||||||
|
packet->dirty_index = dirty_index;
|
||||||
|
packet->imu_temperature = imu_temperature;
|
||||||
|
packet->up_optical_q = up_optical_q;
|
||||||
|
packet->down_optical_q = down_optical_q;
|
||||||
|
packet->apd_voltage = apd_voltage;
|
||||||
|
packet->imu_angle_x_offset = imu_angle_x_offset;
|
||||||
|
packet->imu_angle_y_offset = imu_angle_y_offset;
|
||||||
|
packet->imu_angle_z_offset = imu_angle_z_offset;
|
||||||
|
packet->b_axis_dist = b_axis_dist;
|
||||||
|
packet->theta_angle = theta_angle;
|
||||||
|
packet->ksi_angle = ksi_angle;
|
||||||
|
packet->packet_id = packet_id;
|
||||||
|
packet->payload_size = payload_size;
|
||||||
|
packet->lidar_work_status = lidar_work_status;
|
||||||
|
mav_array_memcpy(packet->reflect_data, reflect_data, sizeof(uint8_t)*120);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET, (const char *)packet, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE RET_LIDAR_AUXILIARY_DATA_PACKET UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field lidar_work_status from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return LiDAR operational state indicator.
|
||||||
|
*/
|
||||||
|
static inline uint8_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_lidar_work_status(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t(msg, 88);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field packet_id from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet ID.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_packet_id(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 84);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field payload_size from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet payload size.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_payload_size(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 86);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field lidar_sync_delay_time from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Delay time of upper computer communication(us).
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_lidar_sync_delay_time(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field time_stamp_s_step from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return LiDAR operational timestamp in seconds.
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_time_stamp_s_step(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 4);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field time_stamp_us_step from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return LiDAR operational timestamp in microsecond .
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_time_stamp_us_step(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 8);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field sys_rotation_period from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return LiDAR low-speed motor rotation period in microsecond .
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_sys_rotation_period(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 12);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field com_rotation_period from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return LiDAR high-speed motor rotation period in microsecond .
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_com_rotation_period(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 16);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field com_horizontal_angle_start from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return The first data in the current data packet is the horizontal angle,Distance data applicable to RET_LIDAR_DISTANCE_DATA_PACKET data packet and reflectivity data of RET_LIDAR_AUXILIARY_DATA_PACKET data packet.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_com_horizontal_angle_start(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 20);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field com_horizontal_angle_step from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Angle interval between two adjacent data in the horizontal direction.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_com_horizontal_angle_step(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 24);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field sys_vertical_angle_start from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return The vertical angle of the first data in the current data packet.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_sys_vertical_angle_start(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 28);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field sys_vertical_angle_span from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return The angular span between adjacent data in the vertical direction of the current data packet.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_sys_vertical_angle_span(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 32);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field apd_temperature from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return APD temperature value
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_apd_temperature(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 36);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field dirty_index from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Protective cover dirt detection index
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_dirty_index(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 40);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field imu_temperature from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return IMU temperature value
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_temperature(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 44);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field up_optical_q from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Up optical communication quality.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_up_optical_q(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 48);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field down_optical_q from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Downlink optical communication quality.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_down_optical_q(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 52);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field apd_voltage from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return APD voltage value.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_apd_voltage(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 56);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field imu_angle_x_offset from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return IMU x-axis installation angle error.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_angle_x_offset(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 60);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field imu_angle_y_offset from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return IMU y-axis installation angle error.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_angle_y_offset(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 64);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field imu_angle_z_offset from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return IMU z-axis installation angle error.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_angle_z_offset(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 68);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field b_axis_dist from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Laser calibration b distance compensation.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_b_axis_dist(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 72);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field theta_angle from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Laser calibration theta angle compensation.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_theta_angle(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 76);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field ksi_angle from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return Laser calibration ksi angle compensation.
|
||||||
|
*/
|
||||||
|
static inline float mavlink_msg_ret_lidar_auxiliary_data_packet_get_ksi_angle(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_float(msg, 80);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field reflect_data from ret_lidar_auxiliary_data_packet message
|
||||||
|
*
|
||||||
|
* @return reflectivity data
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_auxiliary_data_packet_get_reflect_data(const mavlink_message_t* msg, uint8_t *reflect_data)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t_array(msg, reflect_data, 120, 89);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a ret_lidar_auxiliary_data_packet message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param ret_lidar_auxiliary_data_packet C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_auxiliary_data_packet_decode(const mavlink_message_t* msg, mavlink_ret_lidar_auxiliary_data_packet_t* ret_lidar_auxiliary_data_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
ret_lidar_auxiliary_data_packet->lidar_sync_delay_time = mavlink_msg_ret_lidar_auxiliary_data_packet_get_lidar_sync_delay_time(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->time_stamp_s_step = mavlink_msg_ret_lidar_auxiliary_data_packet_get_time_stamp_s_step(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->time_stamp_us_step = mavlink_msg_ret_lidar_auxiliary_data_packet_get_time_stamp_us_step(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->sys_rotation_period = mavlink_msg_ret_lidar_auxiliary_data_packet_get_sys_rotation_period(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->com_rotation_period = mavlink_msg_ret_lidar_auxiliary_data_packet_get_com_rotation_period(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->com_horizontal_angle_start = mavlink_msg_ret_lidar_auxiliary_data_packet_get_com_horizontal_angle_start(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->com_horizontal_angle_step = mavlink_msg_ret_lidar_auxiliary_data_packet_get_com_horizontal_angle_step(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->sys_vertical_angle_start = mavlink_msg_ret_lidar_auxiliary_data_packet_get_sys_vertical_angle_start(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->sys_vertical_angle_span = mavlink_msg_ret_lidar_auxiliary_data_packet_get_sys_vertical_angle_span(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->apd_temperature = mavlink_msg_ret_lidar_auxiliary_data_packet_get_apd_temperature(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->dirty_index = mavlink_msg_ret_lidar_auxiliary_data_packet_get_dirty_index(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->imu_temperature = mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_temperature(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->up_optical_q = mavlink_msg_ret_lidar_auxiliary_data_packet_get_up_optical_q(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->down_optical_q = mavlink_msg_ret_lidar_auxiliary_data_packet_get_down_optical_q(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->apd_voltage = mavlink_msg_ret_lidar_auxiliary_data_packet_get_apd_voltage(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->imu_angle_x_offset = mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_angle_x_offset(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->imu_angle_y_offset = mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_angle_y_offset(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->imu_angle_z_offset = mavlink_msg_ret_lidar_auxiliary_data_packet_get_imu_angle_z_offset(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->b_axis_dist = mavlink_msg_ret_lidar_auxiliary_data_packet_get_b_axis_dist(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->theta_angle = mavlink_msg_ret_lidar_auxiliary_data_packet_get_theta_angle(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->ksi_angle = mavlink_msg_ret_lidar_auxiliary_data_packet_get_ksi_angle(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->packet_id = mavlink_msg_ret_lidar_auxiliary_data_packet_get_packet_id(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->payload_size = mavlink_msg_ret_lidar_auxiliary_data_packet_get_payload_size(msg);
|
||||||
|
ret_lidar_auxiliary_data_packet->lidar_work_status = mavlink_msg_ret_lidar_auxiliary_data_packet_get_lidar_work_status(msg);
|
||||||
|
mavlink_msg_ret_lidar_auxiliary_data_packet_get_reflect_data(msg, ret_lidar_auxiliary_data_packet->reflect_data);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN? msg->len : MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN;
|
||||||
|
memset(ret_lidar_auxiliary_data_packet, 0, MAVLINK_MSG_ID_RET_LIDAR_AUXILIARY_DATA_PACKET_LEN);
|
||||||
|
memcpy(ret_lidar_auxiliary_data_packet, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,280 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE RET_LIDAR_DISTANCE_DATA_PACKET PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET 16
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_ret_lidar_distance_data_packet_t {
|
||||||
|
uint16_t packet_id; /*< Data packet ID.*/
|
||||||
|
uint16_t packet_cnt; /*< Data packet count.*/
|
||||||
|
uint16_t payload_size; /*< Data packet payload size.*/
|
||||||
|
uint8_t point_data[240]; /*< Data packet distance data.*/
|
||||||
|
} mavlink_ret_lidar_distance_data_packet_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN 246
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN 246
|
||||||
|
#define MAVLINK_MSG_ID_16_LEN 246
|
||||||
|
#define MAVLINK_MSG_ID_16_MIN_LEN 246
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC 74
|
||||||
|
#define MAVLINK_MSG_ID_16_CRC 74
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_RET_LIDAR_DISTANCE_DATA_PACKET_FIELD_POINT_DATA_LEN 240
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_DISTANCE_DATA_PACKET { \
|
||||||
|
16, \
|
||||||
|
"RET_LIDAR_DISTANCE_DATA_PACKET", \
|
||||||
|
4, \
|
||||||
|
{ { "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ret_lidar_distance_data_packet_t, packet_id) }, \
|
||||||
|
{ "packet_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ret_lidar_distance_data_packet_t, packet_cnt) }, \
|
||||||
|
{ "payload_size", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ret_lidar_distance_data_packet_t, payload_size) }, \
|
||||||
|
{ "point_data", NULL, MAVLINK_TYPE_UINT8_T, 240, 6, offsetof(mavlink_ret_lidar_distance_data_packet_t, point_data) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_DISTANCE_DATA_PACKET { \
|
||||||
|
"RET_LIDAR_DISTANCE_DATA_PACKET", \
|
||||||
|
4, \
|
||||||
|
{ { "packet_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ret_lidar_distance_data_packet_t, packet_id) }, \
|
||||||
|
{ "packet_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ret_lidar_distance_data_packet_t, packet_cnt) }, \
|
||||||
|
{ "payload_size", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ret_lidar_distance_data_packet_t, payload_size) }, \
|
||||||
|
{ "point_data", NULL, MAVLINK_TYPE_UINT8_T, 240, 6, offsetof(mavlink_ret_lidar_distance_data_packet_t, point_data) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_distance_data_packet message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param packet_cnt Data packet count.
|
||||||
|
* @param payload_size Data packet payload size.
|
||||||
|
* @param point_data Data packet distance data.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint16_t packet_id, uint16_t packet_cnt, uint16_t payload_size, const uint8_t *point_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint16_t(buf, 0, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 2, packet_cnt);
|
||||||
|
_mav_put_uint16_t(buf, 4, payload_size);
|
||||||
|
_mav_put_uint8_t_array(buf, 6, point_data, 240);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_distance_data_packet_t packet;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.packet_cnt = packet_cnt;
|
||||||
|
packet.payload_size = payload_size;
|
||||||
|
mav_array_memcpy(packet.point_data, point_data, sizeof(uint8_t)*240);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_distance_data_packet message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param packet_cnt Data packet count.
|
||||||
|
* @param payload_size Data packet payload size.
|
||||||
|
* @param point_data Data packet distance data.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint16_t packet_id,uint16_t packet_cnt,uint16_t payload_size,const uint8_t *point_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint16_t(buf, 0, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 2, packet_cnt);
|
||||||
|
_mav_put_uint16_t(buf, 4, payload_size);
|
||||||
|
_mav_put_uint8_t_array(buf, 6, point_data, 240);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_distance_data_packet_t packet;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.packet_cnt = packet_cnt;
|
||||||
|
packet.payload_size = payload_size;
|
||||||
|
mav_array_memcpy(packet.point_data, point_data, sizeof(uint8_t)*240);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_distance_data_packet struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_distance_data_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ret_lidar_distance_data_packet_t* ret_lidar_distance_data_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_distance_data_packet_pack(system_id, component_id, msg, ret_lidar_distance_data_packet->packet_id, ret_lidar_distance_data_packet->packet_cnt, ret_lidar_distance_data_packet->payload_size, ret_lidar_distance_data_packet->point_data);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_distance_data_packet struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_distance_data_packet C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ret_lidar_distance_data_packet_t* ret_lidar_distance_data_packet)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_distance_data_packet_pack_chan(system_id, component_id, chan, msg, ret_lidar_distance_data_packet->packet_id, ret_lidar_distance_data_packet->packet_cnt, ret_lidar_distance_data_packet->payload_size, ret_lidar_distance_data_packet->point_data);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_distance_data_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param packet_id Data packet ID.
|
||||||
|
* @param packet_cnt Data packet count.
|
||||||
|
* @param payload_size Data packet payload size.
|
||||||
|
* @param point_data Data packet distance data.
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_ret_lidar_distance_data_packet_send(mavlink_channel_t chan, uint16_t packet_id, uint16_t packet_cnt, uint16_t payload_size, const uint8_t *point_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN];
|
||||||
|
_mav_put_uint16_t(buf, 0, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 2, packet_cnt);
|
||||||
|
_mav_put_uint16_t(buf, 4, payload_size);
|
||||||
|
_mav_put_uint8_t_array(buf, 6, point_data, 240);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET, buf, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_distance_data_packet_t packet;
|
||||||
|
packet.packet_id = packet_id;
|
||||||
|
packet.packet_cnt = packet_cnt;
|
||||||
|
packet.payload_size = payload_size;
|
||||||
|
mav_array_memcpy(packet.point_data, point_data, sizeof(uint8_t)*240);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET, (const char *)&packet, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_distance_data_packet message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_distance_data_packet_send_struct(mavlink_channel_t chan, const mavlink_ret_lidar_distance_data_packet_t* ret_lidar_distance_data_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_ret_lidar_distance_data_packet_send(chan, ret_lidar_distance_data_packet->packet_id, ret_lidar_distance_data_packet->packet_cnt, ret_lidar_distance_data_packet->payload_size, ret_lidar_distance_data_packet->point_data);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET, (const char *)ret_lidar_distance_data_packet, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_distance_data_packet_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t packet_id, uint16_t packet_cnt, uint16_t payload_size, const uint8_t *point_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint16_t(buf, 0, packet_id);
|
||||||
|
_mav_put_uint16_t(buf, 2, packet_cnt);
|
||||||
|
_mav_put_uint16_t(buf, 4, payload_size);
|
||||||
|
_mav_put_uint8_t_array(buf, 6, point_data, 240);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET, buf, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_distance_data_packet_t *packet = (mavlink_ret_lidar_distance_data_packet_t *)msgbuf;
|
||||||
|
packet->packet_id = packet_id;
|
||||||
|
packet->packet_cnt = packet_cnt;
|
||||||
|
packet->payload_size = payload_size;
|
||||||
|
mav_array_memcpy(packet->point_data, point_data, sizeof(uint8_t)*240);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET, (const char *)packet, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE RET_LIDAR_DISTANCE_DATA_PACKET UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field packet_id from ret_lidar_distance_data_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet ID.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_get_packet_id(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field packet_cnt from ret_lidar_distance_data_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet count.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_get_packet_cnt(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 2);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field payload_size from ret_lidar_distance_data_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet payload size.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_get_payload_size(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 4);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field point_data from ret_lidar_distance_data_packet message
|
||||||
|
*
|
||||||
|
* @return Data packet distance data.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_distance_data_packet_get_point_data(const mavlink_message_t* msg, uint8_t *point_data)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t_array(msg, point_data, 240, 6);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a ret_lidar_distance_data_packet message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param ret_lidar_distance_data_packet C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_distance_data_packet_decode(const mavlink_message_t* msg, mavlink_ret_lidar_distance_data_packet_t* ret_lidar_distance_data_packet)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
ret_lidar_distance_data_packet->packet_id = mavlink_msg_ret_lidar_distance_data_packet_get_packet_id(msg);
|
||||||
|
ret_lidar_distance_data_packet->packet_cnt = mavlink_msg_ret_lidar_distance_data_packet_get_packet_cnt(msg);
|
||||||
|
ret_lidar_distance_data_packet->payload_size = mavlink_msg_ret_lidar_distance_data_packet_get_payload_size(msg);
|
||||||
|
mavlink_msg_ret_lidar_distance_data_packet_get_point_data(msg, ret_lidar_distance_data_packet->point_data);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN? msg->len : MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN;
|
||||||
|
memset(ret_lidar_distance_data_packet, 0, MAVLINK_MSG_ID_RET_LIDAR_DISTANCE_DATA_PACKET_LEN);
|
||||||
|
memcpy(ret_lidar_distance_data_packet, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,238 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE RET_LIDAR_TIME_SYNC_DATA PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA 18
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_ret_lidar_time_sync_data_t {
|
||||||
|
uint32_t lidar_sync_count; /*< Time synchronization packet count.*/
|
||||||
|
uint8_t lidar_sync_type; /*< Time synchronization packet type.*/
|
||||||
|
} mavlink_ret_lidar_time_sync_data_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN 5
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN 5
|
||||||
|
#define MAVLINK_MSG_ID_18_LEN 5
|
||||||
|
#define MAVLINK_MSG_ID_18_MIN_LEN 5
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC 12
|
||||||
|
#define MAVLINK_MSG_ID_18_CRC 12
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_TIME_SYNC_DATA { \
|
||||||
|
18, \
|
||||||
|
"RET_LIDAR_TIME_SYNC_DATA", \
|
||||||
|
2, \
|
||||||
|
{ { "lidar_sync_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_ret_lidar_time_sync_data_t, lidar_sync_type) }, \
|
||||||
|
{ "lidar_sync_count", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ret_lidar_time_sync_data_t, lidar_sync_count) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_TIME_SYNC_DATA { \
|
||||||
|
"RET_LIDAR_TIME_SYNC_DATA", \
|
||||||
|
2, \
|
||||||
|
{ { "lidar_sync_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_ret_lidar_time_sync_data_t, lidar_sync_type) }, \
|
||||||
|
{ "lidar_sync_count", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ret_lidar_time_sync_data_t, lidar_sync_count) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_time_sync_data message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param lidar_sync_type Time synchronization packet type.
|
||||||
|
* @param lidar_sync_count Time synchronization packet count.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_time_sync_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint8_t lidar_sync_type, uint32_t lidar_sync_count)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_count);
|
||||||
|
_mav_put_uint8_t(buf, 4, lidar_sync_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_time_sync_data_t packet;
|
||||||
|
packet.lidar_sync_count = lidar_sync_count;
|
||||||
|
packet.lidar_sync_type = lidar_sync_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_time_sync_data message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param lidar_sync_type Time synchronization packet type.
|
||||||
|
* @param lidar_sync_count Time synchronization packet count.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_time_sync_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint8_t lidar_sync_type,uint32_t lidar_sync_count)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_count);
|
||||||
|
_mav_put_uint8_t(buf, 4, lidar_sync_type);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_time_sync_data_t packet;
|
||||||
|
packet.lidar_sync_count = lidar_sync_count;
|
||||||
|
packet.lidar_sync_type = lidar_sync_type;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_time_sync_data struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_time_sync_data C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_time_sync_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ret_lidar_time_sync_data_t* ret_lidar_time_sync_data)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_time_sync_data_pack(system_id, component_id, msg, ret_lidar_time_sync_data->lidar_sync_type, ret_lidar_time_sync_data->lidar_sync_count);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_time_sync_data struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_time_sync_data C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_time_sync_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ret_lidar_time_sync_data_t* ret_lidar_time_sync_data)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_time_sync_data_pack_chan(system_id, component_id, chan, msg, ret_lidar_time_sync_data->lidar_sync_type, ret_lidar_time_sync_data->lidar_sync_count);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_time_sync_data message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param lidar_sync_type Time synchronization packet type.
|
||||||
|
* @param lidar_sync_count Time synchronization packet count.
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_ret_lidar_time_sync_data_send(mavlink_channel_t chan, uint8_t lidar_sync_type, uint32_t lidar_sync_count)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN];
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_count);
|
||||||
|
_mav_put_uint8_t(buf, 4, lidar_sync_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA, buf, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_time_sync_data_t packet;
|
||||||
|
packet.lidar_sync_count = lidar_sync_count;
|
||||||
|
packet.lidar_sync_type = lidar_sync_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA, (const char *)&packet, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_time_sync_data message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_time_sync_data_send_struct(mavlink_channel_t chan, const mavlink_ret_lidar_time_sync_data_t* ret_lidar_time_sync_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_ret_lidar_time_sync_data_send(chan, ret_lidar_time_sync_data->lidar_sync_type, ret_lidar_time_sync_data->lidar_sync_count);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA, (const char *)ret_lidar_time_sync_data, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_time_sync_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t lidar_sync_type, uint32_t lidar_sync_count)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
_mav_put_uint32_t(buf, 0, lidar_sync_count);
|
||||||
|
_mav_put_uint8_t(buf, 4, lidar_sync_type);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA, buf, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_time_sync_data_t *packet = (mavlink_ret_lidar_time_sync_data_t *)msgbuf;
|
||||||
|
packet->lidar_sync_count = lidar_sync_count;
|
||||||
|
packet->lidar_sync_type = lidar_sync_type;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA, (const char *)packet, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE RET_LIDAR_TIME_SYNC_DATA UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field lidar_sync_type from ret_lidar_time_sync_data message
|
||||||
|
*
|
||||||
|
* @return Time synchronization packet type.
|
||||||
|
*/
|
||||||
|
static inline uint8_t mavlink_msg_ret_lidar_time_sync_data_get_lidar_sync_type(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t(msg, 4);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field lidar_sync_count from ret_lidar_time_sync_data message
|
||||||
|
*
|
||||||
|
* @return Time synchronization packet count.
|
||||||
|
*/
|
||||||
|
static inline uint32_t mavlink_msg_ret_lidar_time_sync_data_get_lidar_sync_count(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint32_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a ret_lidar_time_sync_data message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param ret_lidar_time_sync_data C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_time_sync_data_decode(const mavlink_message_t* msg, mavlink_ret_lidar_time_sync_data_t* ret_lidar_time_sync_data)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
ret_lidar_time_sync_data->lidar_sync_count = mavlink_msg_ret_lidar_time_sync_data_get_lidar_sync_count(msg);
|
||||||
|
ret_lidar_time_sync_data->lidar_sync_type = mavlink_msg_ret_lidar_time_sync_data_get_lidar_sync_type(msg);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN? msg->len : MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN;
|
||||||
|
memset(ret_lidar_time_sync_data, 0, MAVLINK_MSG_ID_RET_LIDAR_TIME_SYNC_DATA_LEN);
|
||||||
|
memcpy(ret_lidar_time_sync_data, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -0,0 +1,291 @@
|
||||||
|
#pragma once
|
||||||
|
// MESSAGE RET_LIDAR_VERSION PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_VERSION 13
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct __mavlink_ret_lidar_version_t {
|
||||||
|
uint8_t sys_soft_version[13]; /*< SYS board soft version.*/
|
||||||
|
uint8_t com_soft_version[13]; /*< COM board soft version.*/
|
||||||
|
uint8_t sys_hard_version[6]; /*< SYS board hard version.*/
|
||||||
|
uint8_t com_hard_version[6]; /*< COM board hard version.*/
|
||||||
|
} mavlink_ret_lidar_version_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN 38
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN 38
|
||||||
|
#define MAVLINK_MSG_ID_13_LEN 38
|
||||||
|
#define MAVLINK_MSG_ID_13_MIN_LEN 38
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC 62
|
||||||
|
#define MAVLINK_MSG_ID_13_CRC 62
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_RET_LIDAR_VERSION_FIELD_SYS_SOFT_VERSION_LEN 13
|
||||||
|
#define MAVLINK_MSG_RET_LIDAR_VERSION_FIELD_COM_SOFT_VERSION_LEN 13
|
||||||
|
#define MAVLINK_MSG_RET_LIDAR_VERSION_FIELD_SYS_HARD_VERSION_LEN 6
|
||||||
|
#define MAVLINK_MSG_RET_LIDAR_VERSION_FIELD_COM_HARD_VERSION_LEN 6
|
||||||
|
|
||||||
|
#if MAVLINK_COMMAND_24BIT
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_VERSION { \
|
||||||
|
13, \
|
||||||
|
"RET_LIDAR_VERSION", \
|
||||||
|
4, \
|
||||||
|
{ { "sys_soft_version", NULL, MAVLINK_TYPE_UINT8_T, 13, 0, offsetof(mavlink_ret_lidar_version_t, sys_soft_version) }, \
|
||||||
|
{ "com_soft_version", NULL, MAVLINK_TYPE_UINT8_T, 13, 13, offsetof(mavlink_ret_lidar_version_t, com_soft_version) }, \
|
||||||
|
{ "sys_hard_version", NULL, MAVLINK_TYPE_UINT8_T, 6, 26, offsetof(mavlink_ret_lidar_version_t, sys_hard_version) }, \
|
||||||
|
{ "com_hard_version", NULL, MAVLINK_TYPE_UINT8_T, 6, 32, offsetof(mavlink_ret_lidar_version_t, com_hard_version) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define MAVLINK_MESSAGE_INFO_RET_LIDAR_VERSION { \
|
||||||
|
"RET_LIDAR_VERSION", \
|
||||||
|
4, \
|
||||||
|
{ { "sys_soft_version", NULL, MAVLINK_TYPE_UINT8_T, 13, 0, offsetof(mavlink_ret_lidar_version_t, sys_soft_version) }, \
|
||||||
|
{ "com_soft_version", NULL, MAVLINK_TYPE_UINT8_T, 13, 13, offsetof(mavlink_ret_lidar_version_t, com_soft_version) }, \
|
||||||
|
{ "sys_hard_version", NULL, MAVLINK_TYPE_UINT8_T, 6, 26, offsetof(mavlink_ret_lidar_version_t, sys_hard_version) }, \
|
||||||
|
{ "com_hard_version", NULL, MAVLINK_TYPE_UINT8_T, 6, 32, offsetof(mavlink_ret_lidar_version_t, com_hard_version) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_version message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param sys_soft_version SYS board soft version.
|
||||||
|
* @param com_soft_version COM board soft version.
|
||||||
|
* @param sys_hard_version SYS board hard version.
|
||||||
|
* @param com_hard_version COM board hard version.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
const uint8_t *sys_soft_version, const uint8_t *com_soft_version, const uint8_t *sys_hard_version, const uint8_t *com_hard_version)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN];
|
||||||
|
|
||||||
|
_mav_put_uint8_t_array(buf, 0, sys_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 13, com_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 26, sys_hard_version, 6);
|
||||||
|
_mav_put_uint8_t_array(buf, 32, com_hard_version, 6);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_version_t packet;
|
||||||
|
|
||||||
|
mav_array_memcpy(packet.sys_soft_version, sys_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet.com_soft_version, com_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet.sys_hard_version, sys_hard_version, sizeof(uint8_t)*6);
|
||||||
|
mav_array_memcpy(packet.com_hard_version, com_hard_version, sizeof(uint8_t)*6);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_VERSION;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ret_lidar_version message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param sys_soft_version SYS board soft version.
|
||||||
|
* @param com_soft_version COM board soft version.
|
||||||
|
* @param sys_hard_version SYS board hard version.
|
||||||
|
* @param com_hard_version COM board hard version.
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
const uint8_t *sys_soft_version,const uint8_t *com_soft_version,const uint8_t *sys_hard_version,const uint8_t *com_hard_version)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN];
|
||||||
|
|
||||||
|
_mav_put_uint8_t_array(buf, 0, sys_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 13, com_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 26, sys_hard_version, 6);
|
||||||
|
_mav_put_uint8_t_array(buf, 32, com_hard_version, 6);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_version_t packet;
|
||||||
|
|
||||||
|
mav_array_memcpy(packet.sys_soft_version, sys_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet.com_soft_version, com_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet.sys_hard_version, sys_hard_version, sizeof(uint8_t)*6);
|
||||||
|
mav_array_memcpy(packet.com_hard_version, com_hard_version, sizeof(uint8_t)*6);
|
||||||
|
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_RET_LIDAR_VERSION;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_version struct
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_version C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ret_lidar_version_t* ret_lidar_version)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_version_pack(system_id, component_id, msg, ret_lidar_version->sys_soft_version, ret_lidar_version->com_soft_version, ret_lidar_version->sys_hard_version, ret_lidar_version->com_hard_version);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ret_lidar_version struct on a channel
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message will be sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ret_lidar_version C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ret_lidar_version_t* ret_lidar_version)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ret_lidar_version_pack_chan(system_id, component_id, chan, msg, ret_lidar_version->sys_soft_version, ret_lidar_version->com_soft_version, ret_lidar_version->sys_hard_version, ret_lidar_version->com_hard_version);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_version message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param sys_soft_version SYS board soft version.
|
||||||
|
* @param com_soft_version COM board soft version.
|
||||||
|
* @param sys_hard_version SYS board hard version.
|
||||||
|
* @param com_hard_version COM board hard version.
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_ret_lidar_version_send(mavlink_channel_t chan, const uint8_t *sys_soft_version, const uint8_t *com_soft_version, const uint8_t *sys_hard_version, const uint8_t *com_hard_version)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN];
|
||||||
|
|
||||||
|
_mav_put_uint8_t_array(buf, 0, sys_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 13, com_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 26, sys_hard_version, 6);
|
||||||
|
_mav_put_uint8_t_array(buf, 32, com_hard_version, 6);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_VERSION, buf, MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_version_t packet;
|
||||||
|
|
||||||
|
mav_array_memcpy(packet.sys_soft_version, sys_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet.com_soft_version, com_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet.sys_hard_version, sys_hard_version, sizeof(uint8_t)*6);
|
||||||
|
mav_array_memcpy(packet.com_hard_version, com_hard_version, sizeof(uint8_t)*6);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_VERSION, (const char *)&packet, MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ret_lidar_version message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
* @param struct The MAVLink struct to serialize
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_version_send_struct(mavlink_channel_t chan, const mavlink_ret_lidar_version_t* ret_lidar_version)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_ret_lidar_version_send(chan, ret_lidar_version->sys_soft_version, ret_lidar_version->com_soft_version, ret_lidar_version->sys_hard_version, ret_lidar_version->com_hard_version);
|
||||||
|
#else
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_VERSION, (const char *)ret_lidar_version, MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
/*
|
||||||
|
This variant of _send() can be used to save stack space by re-using
|
||||||
|
memory from the receive buffer. The caller provides a
|
||||||
|
mavlink_message_t which is the size of a full mavlink message. This
|
||||||
|
is usually the receive buffer for the channel, and allows a reply to an
|
||||||
|
incoming message with minimum stack space usage.
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *sys_soft_version, const uint8_t *com_soft_version, const uint8_t *sys_hard_version, const uint8_t *com_hard_version)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char *buf = (char *)msgbuf;
|
||||||
|
|
||||||
|
_mav_put_uint8_t_array(buf, 0, sys_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 13, com_soft_version, 13);
|
||||||
|
_mav_put_uint8_t_array(buf, 26, sys_hard_version, 6);
|
||||||
|
_mav_put_uint8_t_array(buf, 32, com_hard_version, 6);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_VERSION, buf, MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC);
|
||||||
|
#else
|
||||||
|
mavlink_ret_lidar_version_t *packet = (mavlink_ret_lidar_version_t *)msgbuf;
|
||||||
|
|
||||||
|
mav_array_memcpy(packet->sys_soft_version, sys_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet->com_soft_version, com_soft_version, sizeof(uint8_t)*13);
|
||||||
|
mav_array_memcpy(packet->sys_hard_version, sys_hard_version, sizeof(uint8_t)*6);
|
||||||
|
mav_array_memcpy(packet->com_hard_version, com_hard_version, sizeof(uint8_t)*6);
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RET_LIDAR_VERSION, (const char *)packet, MAVLINK_MSG_ID_RET_LIDAR_VERSION_MIN_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN, MAVLINK_MSG_ID_RET_LIDAR_VERSION_CRC);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE RET_LIDAR_VERSION UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field sys_soft_version from ret_lidar_version message
|
||||||
|
*
|
||||||
|
* @return SYS board soft version.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_get_sys_soft_version(const mavlink_message_t* msg, uint8_t *sys_soft_version)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t_array(msg, sys_soft_version, 13, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field com_soft_version from ret_lidar_version message
|
||||||
|
*
|
||||||
|
* @return COM board soft version.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_get_com_soft_version(const mavlink_message_t* msg, uint8_t *com_soft_version)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t_array(msg, com_soft_version, 13, 13);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field sys_hard_version from ret_lidar_version message
|
||||||
|
*
|
||||||
|
* @return SYS board hard version.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_get_sys_hard_version(const mavlink_message_t* msg, uint8_t *sys_hard_version)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t_array(msg, sys_hard_version, 6, 26);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field com_hard_version from ret_lidar_version message
|
||||||
|
*
|
||||||
|
* @return COM board hard version.
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ret_lidar_version_get_com_hard_version(const mavlink_message_t* msg, uint8_t *com_hard_version)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t_array(msg, com_hard_version, 6, 32);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a ret_lidar_version message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param ret_lidar_version C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ret_lidar_version_decode(const mavlink_message_t* msg, mavlink_ret_lidar_version_t* ret_lidar_version)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
mavlink_msg_ret_lidar_version_get_sys_soft_version(msg, ret_lidar_version->sys_soft_version);
|
||||||
|
mavlink_msg_ret_lidar_version_get_com_soft_version(msg, ret_lidar_version->com_soft_version);
|
||||||
|
mavlink_msg_ret_lidar_version_get_sys_hard_version(msg, ret_lidar_version->sys_hard_version);
|
||||||
|
mavlink_msg_ret_lidar_version_get_com_hard_version(msg, ret_lidar_version->com_hard_version);
|
||||||
|
#else
|
||||||
|
uint8_t len = msg->len < MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN? msg->len : MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN;
|
||||||
|
memset(ret_lidar_version, 0, MAVLINK_MSG_ID_RET_LIDAR_VERSION_LEN);
|
||||||
|
memcpy(ret_lidar_version, _MAV_PAYLOAD(msg), len);
|
||||||
|
#endif
|
||||||
|
}
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,14 @@
|
||||||
|
/** @file
|
||||||
|
* @brief MAVLink comm protocol built from SysMavlink.xml
|
||||||
|
* @see http://mavlink.org
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef MAVLINK_VERSION_H
|
||||||
|
#define MAVLINK_VERSION_H
|
||||||
|
|
||||||
|
#define MAVLINK_BUILD_DATE "Wed May 31 2023"
|
||||||
|
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
|
||||||
|
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 246
|
||||||
|
|
||||||
|
#endif // MAVLINK_VERSION_H
|
|
@ -0,0 +1,95 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#if defined(MAVLINK_USE_CXX_NAMESPACE)
|
||||||
|
namespace mavlink {
|
||||||
|
#elif defined(__cplusplus)
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
|
||||||
|
#if (defined _MSC_VER) && (_MSC_VER < 1600)
|
||||||
|
#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* CALCULATE THE CHECKSUM
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define X25_INIT_CRC 0xffff
|
||||||
|
#define X25_VALIDATE_CRC 0xf0b8
|
||||||
|
|
||||||
|
#ifndef HAVE_CRC_ACCUMULATE
|
||||||
|
/**
|
||||||
|
* @brief Accumulate the CRC16_MCRF4XX checksum by adding one char at a time.
|
||||||
|
*
|
||||||
|
* The checksum function adds the hash of one char at a time to the
|
||||||
|
* 16 bit checksum (uint16_t).
|
||||||
|
*
|
||||||
|
* @param data new char to hash
|
||||||
|
* @param crcAccum the already accumulated checksum
|
||||||
|
**/
|
||||||
|
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
|
||||||
|
{
|
||||||
|
/*Accumulate one byte of data into the CRC*/
|
||||||
|
uint8_t tmp;
|
||||||
|
|
||||||
|
tmp = data ^ (uint8_t)(*crcAccum &0xff);
|
||||||
|
tmp ^= (tmp<<4);
|
||||||
|
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Initialize the buffer for the MCRF4XX CRC16
|
||||||
|
*
|
||||||
|
* @param crcAccum the 16 bit MCRF4XX CRC16
|
||||||
|
*/
|
||||||
|
static inline void crc_init(uint16_t* crcAccum)
|
||||||
|
{
|
||||||
|
*crcAccum = X25_INIT_CRC;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Calculates the CRC16_MCRF4XX checksum on a byte buffer
|
||||||
|
*
|
||||||
|
* @param pBuffer buffer containing the byte array to hash
|
||||||
|
* @param length length of the byte array
|
||||||
|
* @return the checksum over the buffer bytes
|
||||||
|
**/
|
||||||
|
static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
|
||||||
|
{
|
||||||
|
uint16_t crcTmp;
|
||||||
|
crc_init(&crcTmp);
|
||||||
|
while (length--) {
|
||||||
|
crc_accumulate(*pBuffer++, &crcTmp);
|
||||||
|
}
|
||||||
|
return crcTmp;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Accumulate the MCRF4XX CRC16 by adding an array of bytes
|
||||||
|
*
|
||||||
|
* The checksum function adds the hash of one char at a time to the
|
||||||
|
* 16 bit checksum (uint16_t).
|
||||||
|
*
|
||||||
|
* @param data new bytes to hash
|
||||||
|
* @param crcAccum the already accumulated checksum
|
||||||
|
**/
|
||||||
|
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
|
||||||
|
{
|
||||||
|
const uint8_t *p = (const uint8_t *)pBuffer;
|
||||||
|
while (length--) {
|
||||||
|
crc_accumulate(*p++, crcAccum);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -0,0 +1,212 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef MAVLINK_NO_CONVERSION_HELPERS
|
||||||
|
|
||||||
|
/* enable math defines on Windows */
|
||||||
|
#ifdef _MSC_VER
|
||||||
|
#ifndef _USE_MATH_DEFINES
|
||||||
|
#define _USE_MATH_DEFINES
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
#ifndef M_PI_2
|
||||||
|
#define M_PI_2 ((float)asin(1))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file mavlink_conversions.h
|
||||||
|
*
|
||||||
|
* These conversion functions follow the NASA rotation standards definition file
|
||||||
|
* available online.
|
||||||
|
*
|
||||||
|
* Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free
|
||||||
|
* (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free)
|
||||||
|
* rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the
|
||||||
|
* protocol as widely as possible.
|
||||||
|
*
|
||||||
|
* @author James Goppert
|
||||||
|
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Converts a quaternion to a rotation matrix
|
||||||
|
*
|
||||||
|
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
|
||||||
|
* @param dcm a 3x3 rotation matrix
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
|
||||||
|
{
|
||||||
|
double a = (double)quaternion[0];
|
||||||
|
double b = (double)quaternion[1];
|
||||||
|
double c = (double)quaternion[2];
|
||||||
|
double d = (double)quaternion[3];
|
||||||
|
double aSq = a * a;
|
||||||
|
double bSq = b * b;
|
||||||
|
double cSq = c * c;
|
||||||
|
double dSq = d * d;
|
||||||
|
dcm[0][0] = aSq + bSq - cSq - dSq;
|
||||||
|
dcm[0][1] = 2 * (b * c - a * d);
|
||||||
|
dcm[0][2] = 2 * (a * c + b * d);
|
||||||
|
dcm[1][0] = 2 * (b * c + a * d);
|
||||||
|
dcm[1][1] = aSq - bSq + cSq - dSq;
|
||||||
|
dcm[1][2] = 2 * (c * d - a * b);
|
||||||
|
dcm[2][0] = 2 * (b * d - a * c);
|
||||||
|
dcm[2][1] = 2 * (a * b + c * d);
|
||||||
|
dcm[2][2] = aSq - bSq - cSq + dSq;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Converts a rotation matrix to euler angles
|
||||||
|
*
|
||||||
|
* @param dcm a 3x3 rotation matrix
|
||||||
|
* @param roll the roll angle in radians
|
||||||
|
* @param pitch the pitch angle in radians
|
||||||
|
* @param yaw the yaw angle in radians
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
|
||||||
|
{
|
||||||
|
float phi, theta, psi;
|
||||||
|
theta = asinf(-dcm[2][0]);
|
||||||
|
|
||||||
|
if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
|
||||||
|
phi = 0.0f;
|
||||||
|
psi = (atan2f(dcm[1][2] - dcm[0][1],
|
||||||
|
dcm[0][2] + dcm[1][1]) + phi);
|
||||||
|
|
||||||
|
} else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
|
||||||
|
phi = 0.0f;
|
||||||
|
psi = atan2f(dcm[1][2] - dcm[0][1],
|
||||||
|
dcm[0][2] + dcm[1][1] - phi);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
phi = atan2f(dcm[2][1], dcm[2][2]);
|
||||||
|
psi = atan2f(dcm[1][0], dcm[0][0]);
|
||||||
|
}
|
||||||
|
|
||||||
|
*roll = phi;
|
||||||
|
*pitch = theta;
|
||||||
|
*yaw = psi;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Converts a quaternion to euler angles
|
||||||
|
*
|
||||||
|
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
|
||||||
|
* @param roll the roll angle in radians
|
||||||
|
* @param pitch the pitch angle in radians
|
||||||
|
* @param yaw the yaw angle in radians
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw)
|
||||||
|
{
|
||||||
|
float dcm[3][3];
|
||||||
|
mavlink_quaternion_to_dcm(quaternion, dcm);
|
||||||
|
mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Converts euler angles to a quaternion
|
||||||
|
*
|
||||||
|
* @param roll the roll angle in radians
|
||||||
|
* @param pitch the pitch angle in radians
|
||||||
|
* @param yaw the yaw angle in radians
|
||||||
|
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
|
||||||
|
{
|
||||||
|
float cosPhi_2 = cosf(roll / 2);
|
||||||
|
float sinPhi_2 = sinf(roll / 2);
|
||||||
|
float cosTheta_2 = cosf(pitch / 2);
|
||||||
|
float sinTheta_2 = sinf(pitch / 2);
|
||||||
|
float cosPsi_2 = cosf(yaw / 2);
|
||||||
|
float sinPsi_2 = sinf(yaw / 2);
|
||||||
|
quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
|
||||||
|
sinPhi_2 * sinTheta_2 * sinPsi_2);
|
||||||
|
quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
|
||||||
|
cosPhi_2 * sinTheta_2 * sinPsi_2);
|
||||||
|
quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
|
||||||
|
sinPhi_2 * cosTheta_2 * sinPsi_2);
|
||||||
|
quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
|
||||||
|
sinPhi_2 * sinTheta_2 * cosPsi_2);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Converts a rotation matrix to a quaternion
|
||||||
|
* Reference:
|
||||||
|
* - Shoemake, Quaternions,
|
||||||
|
* http://www.cs.ucr.edu/~vbz/resources/quatut.pdf
|
||||||
|
*
|
||||||
|
* @param dcm a 3x3 rotation matrix
|
||||||
|
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
|
||||||
|
{
|
||||||
|
float tr = dcm[0][0] + dcm[1][1] + dcm[2][2];
|
||||||
|
if (tr > 0.0f) {
|
||||||
|
float s = sqrtf(tr + 1.0f);
|
||||||
|
quaternion[0] = s * 0.5f;
|
||||||
|
s = 0.5f / s;
|
||||||
|
quaternion[1] = (dcm[2][1] - dcm[1][2]) * s;
|
||||||
|
quaternion[2] = (dcm[0][2] - dcm[2][0]) * s;
|
||||||
|
quaternion[3] = (dcm[1][0] - dcm[0][1]) * s;
|
||||||
|
} else {
|
||||||
|
/* Find maximum diagonal element in dcm
|
||||||
|
* store index in dcm_i */
|
||||||
|
int dcm_i = 0;
|
||||||
|
int i;
|
||||||
|
for (i = 1; i < 3; i++) {
|
||||||
|
if (dcm[i][i] > dcm[dcm_i][dcm_i]) {
|
||||||
|
dcm_i = i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int dcm_j = (dcm_i + 1) % 3;
|
||||||
|
int dcm_k = (dcm_i + 2) % 3;
|
||||||
|
|
||||||
|
float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] -
|
||||||
|
dcm[dcm_k][dcm_k]) + 1.0f);
|
||||||
|
quaternion[dcm_i + 1] = s * 0.5f;
|
||||||
|
s = 0.5f / s;
|
||||||
|
quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s;
|
||||||
|
quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s;
|
||||||
|
quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Converts euler angles to a rotation matrix
|
||||||
|
*
|
||||||
|
* @param roll the roll angle in radians
|
||||||
|
* @param pitch the pitch angle in radians
|
||||||
|
* @param yaw the yaw angle in radians
|
||||||
|
* @param dcm a 3x3 rotation matrix
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
|
||||||
|
{
|
||||||
|
float cosPhi = cosf(roll);
|
||||||
|
float sinPhi = sinf(roll);
|
||||||
|
float cosThe = cosf(pitch);
|
||||||
|
float sinThe = sinf(pitch);
|
||||||
|
float cosPsi = cosf(yaw);
|
||||||
|
float sinPsi = sinf(yaw);
|
||||||
|
|
||||||
|
dcm[0][0] = cosThe * cosPsi;
|
||||||
|
dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
|
||||||
|
dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
|
||||||
|
|
||||||
|
dcm[1][0] = cosThe * sinPsi;
|
||||||
|
dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
|
||||||
|
dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
|
||||||
|
|
||||||
|
dcm[2][0] = -sinThe;
|
||||||
|
dcm[2][1] = sinPhi * cosThe;
|
||||||
|
dcm[2][2] = cosPhi * cosThe;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // MAVLINK_NO_CONVERSION_HELPERS
|
|
@ -0,0 +1,83 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef MAVLINK_USE_MESSAGE_INFO
|
||||||
|
#define MAVLINK_HAVE_GET_MESSAGE_INFO
|
||||||
|
|
||||||
|
/*
|
||||||
|
return the message_info struct for a message
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_id(uint32_t msgid)
|
||||||
|
{
|
||||||
|
static const mavlink_message_info_t mavlink_message_info[] = MAVLINK_MESSAGE_INFO;
|
||||||
|
/*
|
||||||
|
use a bisection search to find the right entry. A perfect hash may be better
|
||||||
|
Note that this assumes the table is sorted with primary key msgid
|
||||||
|
*/
|
||||||
|
const uint32_t count = sizeof(mavlink_message_info)/sizeof(mavlink_message_info[0]);
|
||||||
|
if (count == 0) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
uint32_t low=0, high=count-1;
|
||||||
|
while (low < high) {
|
||||||
|
uint32_t mid = (low+high)/2;
|
||||||
|
if (msgid < mavlink_message_info[mid].msgid) {
|
||||||
|
high = mid;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (msgid > mavlink_message_info[mid].msgid) {
|
||||||
|
low = mid+1;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
return &mavlink_message_info[mid];
|
||||||
|
}
|
||||||
|
if (mavlink_message_info[low].msgid == msgid) {
|
||||||
|
return &mavlink_message_info[low];
|
||||||
|
}
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return the message_info struct for a message
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info(const mavlink_message_t *msg)
|
||||||
|
{
|
||||||
|
return mavlink_get_message_info_by_id(msg->msgid);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return the message_info struct for a message
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_name(const char *name)
|
||||||
|
{
|
||||||
|
static const struct { const char *name; uint32_t msgid; } mavlink_message_names[] = MAVLINK_MESSAGE_NAMES;
|
||||||
|
/*
|
||||||
|
use a bisection search to find the right entry. A perfect hash may be better
|
||||||
|
Note that this assumes the table is sorted with primary key name
|
||||||
|
*/
|
||||||
|
const uint32_t count = sizeof(mavlink_message_names)/sizeof(mavlink_message_names[0]);
|
||||||
|
if (count == 0) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
uint32_t low=0, high=count-1;
|
||||||
|
while (low < high) {
|
||||||
|
uint32_t mid = (low+high)/2;
|
||||||
|
int cmp = strcmp(mavlink_message_names[mid].name, name);
|
||||||
|
if (cmp > 0) {
|
||||||
|
high = mid;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (cmp < 0) {
|
||||||
|
low = mid+1;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
low = mid;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (strcmp(mavlink_message_names[low].name, name) == 0) {
|
||||||
|
return mavlink_get_message_info_by_id(mavlink_message_names[low].msgid);
|
||||||
|
}
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
#endif // MAVLINK_USE_MESSAGE_INFO
|
||||||
|
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,235 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
/*
|
||||||
|
sha-256 implementation for MAVLink based on Heimdal sources, with
|
||||||
|
modifications to suit mavlink headers
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* Copyright (c) 1995 - 2001 Kungliga Tekniska Högskolan
|
||||||
|
* (Royal Institute of Technology, Stockholm, Sweden).
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in the
|
||||||
|
* documentation and/or other materials provided with the distribution.
|
||||||
|
*
|
||||||
|
* 3. Neither the name of the Institute nor the names of its contributors
|
||||||
|
* may be used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
|
||||||
|
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||||
|
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
|
||||||
|
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||||
|
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||||
|
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
|
||||||
|
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
|
||||||
|
* SUCH DAMAGE.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
allow implementation to provide their own sha256 with the same API
|
||||||
|
*/
|
||||||
|
#ifndef HAVE_MAVLINK_SHA256
|
||||||
|
|
||||||
|
#ifdef MAVLINK_USE_CXX_NAMESPACE
|
||||||
|
namespace mavlink {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_HELPER
|
||||||
|
#define MAVLINK_HELPER
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint32_t sz[2];
|
||||||
|
uint32_t counter[8];
|
||||||
|
union {
|
||||||
|
unsigned char save_bytes[64];
|
||||||
|
uint32_t save_u32[16];
|
||||||
|
} u;
|
||||||
|
} mavlink_sha256_ctx;
|
||||||
|
|
||||||
|
#define Ch(x,y,z) (((x) & (y)) ^ ((~(x)) & (z)))
|
||||||
|
#define Maj(x,y,z) (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z)))
|
||||||
|
|
||||||
|
#define ROTR(x,n) (((x)>>(n)) | ((x) << (32 - (n))))
|
||||||
|
|
||||||
|
#define Sigma0(x) (ROTR(x,2) ^ ROTR(x,13) ^ ROTR(x,22))
|
||||||
|
#define Sigma1(x) (ROTR(x,6) ^ ROTR(x,11) ^ ROTR(x,25))
|
||||||
|
#define sigma0(x) (ROTR(x,7) ^ ROTR(x,18) ^ ((x)>>3))
|
||||||
|
#define sigma1(x) (ROTR(x,17) ^ ROTR(x,19) ^ ((x)>>10))
|
||||||
|
|
||||||
|
static const uint32_t mavlink_sha256_constant_256[64] = {
|
||||||
|
0x428a2f98, 0x71374491, 0xb5c0fbcf, 0xe9b5dba5,
|
||||||
|
0x3956c25b, 0x59f111f1, 0x923f82a4, 0xab1c5ed5,
|
||||||
|
0xd807aa98, 0x12835b01, 0x243185be, 0x550c7dc3,
|
||||||
|
0x72be5d74, 0x80deb1fe, 0x9bdc06a7, 0xc19bf174,
|
||||||
|
0xe49b69c1, 0xefbe4786, 0x0fc19dc6, 0x240ca1cc,
|
||||||
|
0x2de92c6f, 0x4a7484aa, 0x5cb0a9dc, 0x76f988da,
|
||||||
|
0x983e5152, 0xa831c66d, 0xb00327c8, 0xbf597fc7,
|
||||||
|
0xc6e00bf3, 0xd5a79147, 0x06ca6351, 0x14292967,
|
||||||
|
0x27b70a85, 0x2e1b2138, 0x4d2c6dfc, 0x53380d13,
|
||||||
|
0x650a7354, 0x766a0abb, 0x81c2c92e, 0x92722c85,
|
||||||
|
0xa2bfe8a1, 0xa81a664b, 0xc24b8b70, 0xc76c51a3,
|
||||||
|
0xd192e819, 0xd6990624, 0xf40e3585, 0x106aa070,
|
||||||
|
0x19a4c116, 0x1e376c08, 0x2748774c, 0x34b0bcb5,
|
||||||
|
0x391c0cb3, 0x4ed8aa4a, 0x5b9cca4f, 0x682e6ff3,
|
||||||
|
0x748f82ee, 0x78a5636f, 0x84c87814, 0x8cc70208,
|
||||||
|
0x90befffa, 0xa4506ceb, 0xbef9a3f7, 0xc67178f2
|
||||||
|
};
|
||||||
|
|
||||||
|
MAVLINK_HELPER void mavlink_sha256_init(mavlink_sha256_ctx *m)
|
||||||
|
{
|
||||||
|
m->sz[0] = 0;
|
||||||
|
m->sz[1] = 0;
|
||||||
|
m->counter[0] = 0x6a09e667;
|
||||||
|
m->counter[1] = 0xbb67ae85;
|
||||||
|
m->counter[2] = 0x3c6ef372;
|
||||||
|
m->counter[3] = 0xa54ff53a;
|
||||||
|
m->counter[4] = 0x510e527f;
|
||||||
|
m->counter[5] = 0x9b05688c;
|
||||||
|
m->counter[6] = 0x1f83d9ab;
|
||||||
|
m->counter[7] = 0x5be0cd19;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline void mavlink_sha256_calc(mavlink_sha256_ctx *m, uint32_t *in)
|
||||||
|
{
|
||||||
|
uint32_t AA, BB, CC, DD, EE, FF, GG, HH;
|
||||||
|
uint32_t data[64];
|
||||||
|
int i;
|
||||||
|
|
||||||
|
AA = m->counter[0];
|
||||||
|
BB = m->counter[1];
|
||||||
|
CC = m->counter[2];
|
||||||
|
DD = m->counter[3];
|
||||||
|
EE = m->counter[4];
|
||||||
|
FF = m->counter[5];
|
||||||
|
GG = m->counter[6];
|
||||||
|
HH = m->counter[7];
|
||||||
|
|
||||||
|
for (i = 0; i < 16; ++i)
|
||||||
|
data[i] = in[i];
|
||||||
|
for (i = 16; i < 64; ++i)
|
||||||
|
data[i] = sigma1(data[i-2]) + data[i-7] +
|
||||||
|
sigma0(data[i-15]) + data[i - 16];
|
||||||
|
|
||||||
|
for (i = 0; i < 64; i++) {
|
||||||
|
uint32_t T1, T2;
|
||||||
|
|
||||||
|
T1 = HH + Sigma1(EE) + Ch(EE, FF, GG) + mavlink_sha256_constant_256[i] + data[i];
|
||||||
|
T2 = Sigma0(AA) + Maj(AA,BB,CC);
|
||||||
|
|
||||||
|
HH = GG;
|
||||||
|
GG = FF;
|
||||||
|
FF = EE;
|
||||||
|
EE = DD + T1;
|
||||||
|
DD = CC;
|
||||||
|
CC = BB;
|
||||||
|
BB = AA;
|
||||||
|
AA = T1 + T2;
|
||||||
|
}
|
||||||
|
|
||||||
|
m->counter[0] += AA;
|
||||||
|
m->counter[1] += BB;
|
||||||
|
m->counter[2] += CC;
|
||||||
|
m->counter[3] += DD;
|
||||||
|
m->counter[4] += EE;
|
||||||
|
m->counter[5] += FF;
|
||||||
|
m->counter[6] += GG;
|
||||||
|
m->counter[7] += HH;
|
||||||
|
}
|
||||||
|
|
||||||
|
MAVLINK_HELPER void mavlink_sha256_update(mavlink_sha256_ctx *m, const void *v, uint32_t len)
|
||||||
|
{
|
||||||
|
const unsigned char *p = (const unsigned char *)v;
|
||||||
|
uint32_t old_sz = m->sz[0];
|
||||||
|
uint32_t offset;
|
||||||
|
|
||||||
|
m->sz[0] += len * 8;
|
||||||
|
if (m->sz[0] < old_sz)
|
||||||
|
++m->sz[1];
|
||||||
|
offset = (old_sz / 8) % 64;
|
||||||
|
while(len > 0){
|
||||||
|
uint32_t l = 64 - offset;
|
||||||
|
if (len < l) {
|
||||||
|
l = len;
|
||||||
|
}
|
||||||
|
memcpy(m->u.save_bytes + offset, p, l);
|
||||||
|
offset += l;
|
||||||
|
p += l;
|
||||||
|
len -= l;
|
||||||
|
if(offset == 64){
|
||||||
|
int i;
|
||||||
|
uint32_t current[16];
|
||||||
|
const uint32_t *u = m->u.save_u32;
|
||||||
|
for (i = 0; i < 16; i++){
|
||||||
|
const uint8_t *p1 = (const uint8_t *)&u[i];
|
||||||
|
uint8_t *p2 = (uint8_t *)¤t[i];
|
||||||
|
p2[0] = p1[3];
|
||||||
|
p2[1] = p1[2];
|
||||||
|
p2[2] = p1[1];
|
||||||
|
p2[3] = p1[0];
|
||||||
|
}
|
||||||
|
mavlink_sha256_calc(m, current);
|
||||||
|
offset = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
get first 48 bits of final sha256 hash
|
||||||
|
*/
|
||||||
|
MAVLINK_HELPER void mavlink_sha256_final_48(mavlink_sha256_ctx *m, uint8_t result[6])
|
||||||
|
{
|
||||||
|
unsigned char zeros[72];
|
||||||
|
unsigned offset = (m->sz[0] / 8) % 64;
|
||||||
|
unsigned int dstart = (120 - offset - 1) % 64 + 1;
|
||||||
|
uint8_t *p = (uint8_t *)&m->counter[0];
|
||||||
|
|
||||||
|
*zeros = 0x80;
|
||||||
|
memset (zeros + 1, 0, sizeof(zeros) - 1);
|
||||||
|
zeros[dstart+7] = (m->sz[0] >> 0) & 0xff;
|
||||||
|
zeros[dstart+6] = (m->sz[0] >> 8) & 0xff;
|
||||||
|
zeros[dstart+5] = (m->sz[0] >> 16) & 0xff;
|
||||||
|
zeros[dstart+4] = (m->sz[0] >> 24) & 0xff;
|
||||||
|
zeros[dstart+3] = (m->sz[1] >> 0) & 0xff;
|
||||||
|
zeros[dstart+2] = (m->sz[1] >> 8) & 0xff;
|
||||||
|
zeros[dstart+1] = (m->sz[1] >> 16) & 0xff;
|
||||||
|
zeros[dstart+0] = (m->sz[1] >> 24) & 0xff;
|
||||||
|
|
||||||
|
mavlink_sha256_update(m, zeros, dstart + 8);
|
||||||
|
|
||||||
|
// this ordering makes the result consistent with taking the first
|
||||||
|
// 6 bytes of more conventional sha256 functions. It assumes
|
||||||
|
// little-endian ordering of m->counter
|
||||||
|
result[0] = p[3];
|
||||||
|
result[1] = p[2];
|
||||||
|
result[2] = p[1];
|
||||||
|
result[3] = p[0];
|
||||||
|
result[4] = p[7];
|
||||||
|
result[5] = p[6];
|
||||||
|
}
|
||||||
|
|
||||||
|
// prevent conflicts with users of the header
|
||||||
|
#undef Ch
|
||||||
|
#undef ROTR
|
||||||
|
#undef Sigma0
|
||||||
|
#undef Sigma1
|
||||||
|
#undef sigma0
|
||||||
|
#undef sigma1
|
||||||
|
|
||||||
|
#ifdef MAVLINK_USE_CXX_NAMESPACE
|
||||||
|
} // namespace mavlink
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // HAVE_MAVLINK_SHA256
|
|
@ -0,0 +1,301 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
|
||||||
|
#if (defined _MSC_VER) && (_MSC_VER < 1600)
|
||||||
|
#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#ifdef MAVLINK_USE_CXX_NAMESPACE
|
||||||
|
namespace mavlink {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Macro to define packed structures
|
||||||
|
#ifdef __GNUC__
|
||||||
|
#define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
|
||||||
|
#else
|
||||||
|
#define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_MAX_PAYLOAD_LEN
|
||||||
|
// it is possible to override this, but be careful!
|
||||||
|
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define MAVLINK_CORE_HEADER_LEN 9 ///< Length of core header (of the comm. layer)
|
||||||
|
#define MAVLINK_CORE_HEADER_MAVLINK1_LEN 5 ///< Length of MAVLink1 core header (of the comm. layer)
|
||||||
|
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and stx
|
||||||
|
#define MAVLINK_NUM_CHECKSUM_BYTES 2
|
||||||
|
#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
|
||||||
|
|
||||||
|
#define MAVLINK_SIGNATURE_BLOCK_LEN 13
|
||||||
|
|
||||||
|
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN) ///< Maximum packet length
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Old-style 4 byte param union
|
||||||
|
*
|
||||||
|
* This struct is the data format to be used when sending
|
||||||
|
* parameters. The parameter should be copied to the native
|
||||||
|
* type (without type conversion)
|
||||||
|
* and re-instanted on the receiving side using the
|
||||||
|
* native type as well.
|
||||||
|
*/
|
||||||
|
MAVPACKED(
|
||||||
|
typedef struct param_union {
|
||||||
|
union {
|
||||||
|
float param_float;
|
||||||
|
int32_t param_int32;
|
||||||
|
uint32_t param_uint32;
|
||||||
|
int16_t param_int16;
|
||||||
|
uint16_t param_uint16;
|
||||||
|
int8_t param_int8;
|
||||||
|
uint8_t param_uint8;
|
||||||
|
uint8_t bytes[4];
|
||||||
|
};
|
||||||
|
uint8_t type;
|
||||||
|
}) mavlink_param_union_t;
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* New-style 8 byte param union
|
||||||
|
* mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering.
|
||||||
|
* The mavlink_param_union_double_t will be treated as a little-endian structure.
|
||||||
|
*
|
||||||
|
* If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero.
|
||||||
|
* The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the
|
||||||
|
* lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union.
|
||||||
|
* The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above,
|
||||||
|
* as bitfield ordering isn't consistent between platforms. The above is intended to be for gcc on x86,
|
||||||
|
* which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number,
|
||||||
|
* and the bits pulled out using the shifts/masks.
|
||||||
|
*/
|
||||||
|
MAVPACKED(
|
||||||
|
typedef struct param_union_extended {
|
||||||
|
union {
|
||||||
|
struct {
|
||||||
|
uint8_t is_double:1;
|
||||||
|
uint8_t mavlink_type:7;
|
||||||
|
union {
|
||||||
|
char c;
|
||||||
|
uint8_t uint8;
|
||||||
|
int8_t int8;
|
||||||
|
uint16_t uint16;
|
||||||
|
int16_t int16;
|
||||||
|
uint32_t uint32;
|
||||||
|
int32_t int32;
|
||||||
|
float f;
|
||||||
|
uint8_t align[7];
|
||||||
|
};
|
||||||
|
};
|
||||||
|
uint8_t data[8];
|
||||||
|
};
|
||||||
|
}) mavlink_param_union_double_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This structure is required to make the mavlink_send_xxx convenience functions
|
||||||
|
* work, as it tells the library what the current system and component ID are.
|
||||||
|
*/
|
||||||
|
MAVPACKED(
|
||||||
|
typedef struct __mavlink_system {
|
||||||
|
uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
|
||||||
|
uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
|
||||||
|
}) mavlink_system_t;
|
||||||
|
|
||||||
|
MAVPACKED(
|
||||||
|
typedef struct __mavlink_message {
|
||||||
|
uint16_t checksum; ///< sent at end of packet
|
||||||
|
uint8_t magic; ///< protocol magic marker
|
||||||
|
uint8_t len; ///< Length of payload
|
||||||
|
uint8_t incompat_flags; ///< flags that must be understood
|
||||||
|
uint8_t compat_flags; ///< flags that can be ignored if not understood
|
||||||
|
uint8_t seq; ///< Sequence of packet
|
||||||
|
uint8_t sysid; ///< ID of message sender system/aircraft
|
||||||
|
uint8_t compid; ///< ID of the message sender component
|
||||||
|
uint32_t msgid:24; ///< ID of message in payload
|
||||||
|
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
|
||||||
|
uint8_t ck[2]; ///< incoming checksum bytes
|
||||||
|
uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
|
||||||
|
}) mavlink_message_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
MAVLINK_TYPE_CHAR = 0,
|
||||||
|
MAVLINK_TYPE_UINT8_T = 1,
|
||||||
|
MAVLINK_TYPE_INT8_T = 2,
|
||||||
|
MAVLINK_TYPE_UINT16_T = 3,
|
||||||
|
MAVLINK_TYPE_INT16_T = 4,
|
||||||
|
MAVLINK_TYPE_UINT32_T = 5,
|
||||||
|
MAVLINK_TYPE_INT32_T = 6,
|
||||||
|
MAVLINK_TYPE_UINT64_T = 7,
|
||||||
|
MAVLINK_TYPE_INT64_T = 8,
|
||||||
|
MAVLINK_TYPE_FLOAT = 9,
|
||||||
|
MAVLINK_TYPE_DOUBLE = 10
|
||||||
|
} mavlink_message_type_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MAX_FIELDS 64
|
||||||
|
|
||||||
|
typedef struct __mavlink_field_info {
|
||||||
|
const char *name; // name of this field
|
||||||
|
const char *print_format; // printing format hint, or NULL
|
||||||
|
mavlink_message_type_t type; // type of this field
|
||||||
|
unsigned int array_length; // if non-zero, field is an array
|
||||||
|
unsigned int wire_offset; // offset of each field in the payload
|
||||||
|
unsigned int structure_offset; // offset in a C structure
|
||||||
|
} mavlink_field_info_t;
|
||||||
|
|
||||||
|
// note that in this structure the order of fields is the order
|
||||||
|
// in the XML file, not necessary the wire order
|
||||||
|
typedef struct __mavlink_message_info {
|
||||||
|
uint32_t msgid; // message ID
|
||||||
|
const char *name; // name of the message
|
||||||
|
unsigned num_fields; // how many fields in this message
|
||||||
|
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
|
||||||
|
} mavlink_message_info_t;
|
||||||
|
|
||||||
|
#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
|
||||||
|
#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
|
||||||
|
|
||||||
|
// checksum is immediately after the payload bytes
|
||||||
|
#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
|
||||||
|
#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
|
||||||
|
|
||||||
|
#ifndef HAVE_MAVLINK_CHANNEL_T
|
||||||
|
typedef enum {
|
||||||
|
MAVLINK_COMM_0,
|
||||||
|
MAVLINK_COMM_1,
|
||||||
|
MAVLINK_COMM_2,
|
||||||
|
MAVLINK_COMM_3
|
||||||
|
} mavlink_channel_t;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
* applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
|
||||||
|
* of buffers they will use. If more are used, then the result will be
|
||||||
|
* a stack overrun
|
||||||
|
*/
|
||||||
|
#ifndef MAVLINK_COMM_NUM_BUFFERS
|
||||||
|
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
|
||||||
|
# define MAVLINK_COMM_NUM_BUFFERS 16
|
||||||
|
#else
|
||||||
|
# define MAVLINK_COMM_NUM_BUFFERS 4
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
MAVLINK_PARSE_STATE_UNINIT=0,
|
||||||
|
MAVLINK_PARSE_STATE_IDLE,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_STX,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_LENGTH,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_SEQ,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_SYSID,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_COMPID,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_MSGID1,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_MSGID2,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_MSGID3,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_PAYLOAD,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_CRC1,
|
||||||
|
MAVLINK_PARSE_STATE_GOT_BAD_CRC1,
|
||||||
|
MAVLINK_PARSE_STATE_SIGNATURE_WAIT
|
||||||
|
} mavlink_parse_state_t; ///< The state machine for the comm parser
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
MAVLINK_FRAMING_INCOMPLETE=0,
|
||||||
|
MAVLINK_FRAMING_OK=1,
|
||||||
|
MAVLINK_FRAMING_BAD_CRC=2,
|
||||||
|
MAVLINK_FRAMING_BAD_SIGNATURE=3
|
||||||
|
} mavlink_framing_t;
|
||||||
|
|
||||||
|
#define MAVLINK_STATUS_FLAG_IN_MAVLINK1 1 // last incoming packet was MAVLink1
|
||||||
|
#define MAVLINK_STATUS_FLAG_OUT_MAVLINK1 2 // generate MAVLink1 by default
|
||||||
|
#define MAVLINK_STATUS_FLAG_IN_SIGNED 4 // last incoming packet was signed and validated
|
||||||
|
#define MAVLINK_STATUS_FLAG_IN_BADSIG 8 // last incoming packet had a bad signature
|
||||||
|
|
||||||
|
#define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol
|
||||||
|
|
||||||
|
typedef struct __mavlink_status {
|
||||||
|
uint8_t msg_received; ///< Number of received messages
|
||||||
|
uint8_t buffer_overrun; ///< Number of buffer overruns
|
||||||
|
uint8_t parse_error; ///< Number of parse errors
|
||||||
|
mavlink_parse_state_t parse_state; ///< Parsing state machine
|
||||||
|
uint8_t packet_idx; ///< Index in current packet
|
||||||
|
uint8_t current_rx_seq; ///< Sequence number of last packet received
|
||||||
|
uint8_t current_tx_seq; ///< Sequence number of last packet sent
|
||||||
|
uint16_t packet_rx_success_count; ///< Received packets
|
||||||
|
uint16_t packet_rx_drop_count; ///< Number of packet drops
|
||||||
|
uint8_t flags; ///< MAVLINK_STATUS_FLAG_*
|
||||||
|
uint8_t signature_wait; ///< number of signature bytes left to receive
|
||||||
|
struct __mavlink_signing *signing; ///< optional signing state
|
||||||
|
struct __mavlink_signing_streams *signing_streams; ///< global record of stream timestamps
|
||||||
|
} mavlink_status_t;
|
||||||
|
|
||||||
|
/*
|
||||||
|
a callback function to allow for accepting unsigned packets
|
||||||
|
*/
|
||||||
|
typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32_t msgid);
|
||||||
|
|
||||||
|
/*
|
||||||
|
flags controlling signing
|
||||||
|
*/
|
||||||
|
#define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1 ///< Enable outgoing signing
|
||||||
|
|
||||||
|
/*
|
||||||
|
state of MAVLink signing for this channel
|
||||||
|
*/
|
||||||
|
typedef struct __mavlink_signing {
|
||||||
|
uint8_t flags; ///< MAVLINK_SIGNING_FLAG_*
|
||||||
|
uint8_t link_id; ///< Same as MAVLINK_CHANNEL
|
||||||
|
uint64_t timestamp; ///< Timestamp, in microseconds since UNIX epoch GMT
|
||||||
|
uint8_t secret_key[32];
|
||||||
|
mavlink_accept_unsigned_t accept_unsigned_callback;
|
||||||
|
} mavlink_signing_t;
|
||||||
|
|
||||||
|
/*
|
||||||
|
timestamp state of each logical signing stream. This needs to be the same structure for all
|
||||||
|
connections in order to be secure
|
||||||
|
*/
|
||||||
|
#ifndef MAVLINK_MAX_SIGNING_STREAMS
|
||||||
|
#define MAVLINK_MAX_SIGNING_STREAMS 16
|
||||||
|
#endif
|
||||||
|
typedef struct __mavlink_signing_streams {
|
||||||
|
uint16_t num_signing_streams;
|
||||||
|
struct __mavlink_signing_stream {
|
||||||
|
uint8_t link_id; ///< ID of the link (MAVLINK_CHANNEL)
|
||||||
|
uint8_t sysid; ///< Remote system ID
|
||||||
|
uint8_t compid; ///< Remote component ID
|
||||||
|
uint8_t timestamp_bytes[6]; ///< Timestamp, in microseconds since UNIX epoch GMT
|
||||||
|
} stream[MAVLINK_MAX_SIGNING_STREAMS];
|
||||||
|
} mavlink_signing_streams_t;
|
||||||
|
|
||||||
|
|
||||||
|
#define MAVLINK_BIG_ENDIAN 0
|
||||||
|
#define MAVLINK_LITTLE_ENDIAN 1
|
||||||
|
|
||||||
|
#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM 1
|
||||||
|
#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT 2
|
||||||
|
|
||||||
|
/*
|
||||||
|
entry in table of information about each message type
|
||||||
|
*/
|
||||||
|
typedef struct __mavlink_msg_entry {
|
||||||
|
uint32_t msgid;
|
||||||
|
uint8_t crc_extra;
|
||||||
|
uint8_t min_msg_len; // minimum message length
|
||||||
|
uint8_t max_msg_len; // maximum message length (e.g. including mavlink2 extensions)
|
||||||
|
uint8_t flags; // MAV_MSG_ENTRY_FLAG_*
|
||||||
|
uint8_t target_system_ofs; // payload offset to target_system, or 0
|
||||||
|
uint8_t target_component_ofs; // payload offset to target_component, or 0
|
||||||
|
} mavlink_msg_entry_t;
|
||||||
|
|
||||||
|
/*
|
||||||
|
incompat_flags bits
|
||||||
|
*/
|
||||||
|
#define MAVLINK_IFLAG_SIGNED 0x01
|
||||||
|
#define MAVLINK_IFLAG_MASK 0x01 // mask of all understood bits
|
||||||
|
|
||||||
|
#ifdef MAVLINK_USE_CXX_NAMESPACE
|
||||||
|
} // namespace mavlink
|
||||||
|
#endif
|
|
@ -0,0 +1,334 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "string.h"
|
||||||
|
#include "mavlink_types.h"
|
||||||
|
|
||||||
|
/*
|
||||||
|
If you want MAVLink on a system that is native big-endian,
|
||||||
|
you need to define NATIVE_BIG_ENDIAN
|
||||||
|
*/
|
||||||
|
#ifdef NATIVE_BIG_ENDIAN
|
||||||
|
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
|
||||||
|
#else
|
||||||
|
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_STACK_BUFFER
|
||||||
|
#define MAVLINK_STACK_BUFFER 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_AVOID_GCC_STACK_BUG
|
||||||
|
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_ASSERT
|
||||||
|
#define MAVLINK_ASSERT(x)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_START_UART_SEND
|
||||||
|
#define MAVLINK_START_UART_SEND(chan, length)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef MAVLINK_END_UART_SEND
|
||||||
|
#define MAVLINK_END_UART_SEND(chan, length)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* option to provide alternative implementation of mavlink_helpers.h */
|
||||||
|
#ifdef MAVLINK_SEPARATE_HELPERS
|
||||||
|
|
||||||
|
#define MAVLINK_HELPER
|
||||||
|
|
||||||
|
/* decls in sync with those in mavlink_helpers.h */
|
||||||
|
#ifndef MAVLINK_GET_CHANNEL_STATUS
|
||||||
|
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
|
||||||
|
#endif
|
||||||
|
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
|
||||||
|
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||||
|
uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra);
|
||||||
|
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
|
||||||
|
uint8_t min_length, uint8_t length, uint8_t crc_extra);
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid, const char *packet,
|
||||||
|
uint8_t min_length, uint8_t length, uint8_t crc_extra);
|
||||||
|
#endif
|
||||||
|
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
|
||||||
|
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
|
||||||
|
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
|
||||||
|
MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
|
||||||
|
mavlink_status_t* status,
|
||||||
|
uint8_t c,
|
||||||
|
mavlink_message_t* r_message,
|
||||||
|
mavlink_status_t* r_mavlink_status);
|
||||||
|
MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
|
||||||
|
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
|
||||||
|
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
|
||||||
|
uint8_t* r_bit_index, uint8_t* buffer);
|
||||||
|
MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid);
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
|
||||||
|
MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define MAVLINK_HELPER static inline
|
||||||
|
#include "mavlink_helpers.h"
|
||||||
|
|
||||||
|
#endif // MAVLINK_SEPARATE_HELPERS
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get the required buffer size for this message
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
if (msg->magic == MAVLINK_STX_MAVLINK1) {
|
||||||
|
return msg->len + MAVLINK_CORE_HEADER_MAVLINK1_LEN+1 + 2;
|
||||||
|
}
|
||||||
|
uint16_t signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
|
||||||
|
return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES + signature_len;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP
|
||||||
|
static inline void byte_swap_2(char *dst, const char *src)
|
||||||
|
{
|
||||||
|
dst[0] = src[1];
|
||||||
|
dst[1] = src[0];
|
||||||
|
}
|
||||||
|
static inline void byte_swap_4(char *dst, const char *src)
|
||||||
|
{
|
||||||
|
dst[0] = src[3];
|
||||||
|
dst[1] = src[2];
|
||||||
|
dst[2] = src[1];
|
||||||
|
dst[3] = src[0];
|
||||||
|
}
|
||||||
|
static inline void byte_swap_8(char *dst, const char *src)
|
||||||
|
{
|
||||||
|
dst[0] = src[7];
|
||||||
|
dst[1] = src[6];
|
||||||
|
dst[2] = src[5];
|
||||||
|
dst[3] = src[4];
|
||||||
|
dst[4] = src[3];
|
||||||
|
dst[5] = src[2];
|
||||||
|
dst[6] = src[1];
|
||||||
|
dst[7] = src[0];
|
||||||
|
}
|
||||||
|
#elif !MAVLINK_ALIGNED_FIELDS
|
||||||
|
static inline void byte_copy_2(char *dst, const char *src)
|
||||||
|
{
|
||||||
|
dst[0] = src[0];
|
||||||
|
dst[1] = src[1];
|
||||||
|
}
|
||||||
|
static inline void byte_copy_4(char *dst, const char *src)
|
||||||
|
{
|
||||||
|
dst[0] = src[0];
|
||||||
|
dst[1] = src[1];
|
||||||
|
dst[2] = src[2];
|
||||||
|
dst[3] = src[3];
|
||||||
|
}
|
||||||
|
static inline void byte_copy_8(char *dst, const char *src)
|
||||||
|
{
|
||||||
|
memcpy(dst, src, 8);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
|
||||||
|
#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b
|
||||||
|
#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b
|
||||||
|
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP
|
||||||
|
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
|
||||||
|
#elif !MAVLINK_ALIGNED_FIELDS
|
||||||
|
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
|
||||||
|
#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
|
||||||
|
#else
|
||||||
|
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
|
||||||
|
#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b
|
||||||
|
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
|
||||||
|
#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b
|
||||||
|
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
|
||||||
|
#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b
|
||||||
|
#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b
|
||||||
|
#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
like memcpy(), but if src is NULL, do a memset to zero
|
||||||
|
*/
|
||||||
|
static inline void mav_array_memcpy(void *dest, const void *src, size_t n)
|
||||||
|
{
|
||||||
|
if (src == NULL) {
|
||||||
|
memset(dest, 0, n);
|
||||||
|
} else {
|
||||||
|
memcpy(dest, src, n);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Place a char array into a buffer
|
||||||
|
*/
|
||||||
|
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
|
||||||
|
{
|
||||||
|
mav_array_memcpy(&buf[wire_offset], b, array_length);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Place a uint8_t array into a buffer
|
||||||
|
*/
|
||||||
|
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
|
||||||
|
{
|
||||||
|
mav_array_memcpy(&buf[wire_offset], b, array_length);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Place a int8_t array into a buffer
|
||||||
|
*/
|
||||||
|
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
|
||||||
|
{
|
||||||
|
mav_array_memcpy(&buf[wire_offset], b, array_length);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP
|
||||||
|
#define _MAV_PUT_ARRAY(TYPE, V) \
|
||||||
|
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
|
||||||
|
{ \
|
||||||
|
if (b == NULL) { \
|
||||||
|
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
|
||||||
|
} else { \
|
||||||
|
uint16_t i; \
|
||||||
|
for (i=0; i<array_length; i++) { \
|
||||||
|
_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
|
||||||
|
} \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define _MAV_PUT_ARRAY(TYPE, V) \
|
||||||
|
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
|
||||||
|
{ \
|
||||||
|
mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
_MAV_PUT_ARRAY(uint16_t, u16)
|
||||||
|
_MAV_PUT_ARRAY(uint32_t, u32)
|
||||||
|
_MAV_PUT_ARRAY(uint64_t, u64)
|
||||||
|
_MAV_PUT_ARRAY(int16_t, i16)
|
||||||
|
_MAV_PUT_ARRAY(int32_t, i32)
|
||||||
|
_MAV_PUT_ARRAY(int64_t, i64)
|
||||||
|
_MAV_PUT_ARRAY(float, f)
|
||||||
|
_MAV_PUT_ARRAY(double, d)
|
||||||
|
|
||||||
|
#define _MAV_RETURN_char(msg, wire_offset) (char)_MAV_PAYLOAD(msg)[wire_offset]
|
||||||
|
#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
|
||||||
|
#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
|
||||||
|
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP
|
||||||
|
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
|
||||||
|
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||||
|
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
|
||||||
|
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int16_t, 2)
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int32_t, 4)
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int64_t, 8)
|
||||||
|
_MAV_MSG_RETURN_TYPE(float, 4)
|
||||||
|
_MAV_MSG_RETURN_TYPE(double, 8)
|
||||||
|
|
||||||
|
#elif !MAVLINK_ALIGNED_FIELDS
|
||||||
|
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
|
||||||
|
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||||
|
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
|
||||||
|
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int16_t, 2)
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int32_t, 4)
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int64_t, 8)
|
||||||
|
_MAV_MSG_RETURN_TYPE(float, 4)
|
||||||
|
_MAV_MSG_RETURN_TYPE(double, 8)
|
||||||
|
#else // nicely aligned, no swap
|
||||||
|
#define _MAV_MSG_RETURN_TYPE(TYPE) \
|
||||||
|
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
|
||||||
|
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
|
||||||
|
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint16_t)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int16_t)
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint32_t)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int32_t)
|
||||||
|
_MAV_MSG_RETURN_TYPE(uint64_t)
|
||||||
|
_MAV_MSG_RETURN_TYPE(int64_t)
|
||||||
|
_MAV_MSG_RETURN_TYPE(float)
|
||||||
|
_MAV_MSG_RETURN_TYPE(double)
|
||||||
|
#endif // MAVLINK_NEED_BYTE_SWAP
|
||||||
|
|
||||||
|
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
|
||||||
|
uint8_t array_length, uint8_t wire_offset)
|
||||||
|
{
|
||||||
|
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
|
||||||
|
return array_length;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
|
||||||
|
uint8_t array_length, uint8_t wire_offset)
|
||||||
|
{
|
||||||
|
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
|
||||||
|
return array_length;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
|
||||||
|
uint8_t array_length, uint8_t wire_offset)
|
||||||
|
{
|
||||||
|
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
|
||||||
|
return array_length;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP
|
||||||
|
#define _MAV_RETURN_ARRAY(TYPE, V) \
|
||||||
|
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
|
||||||
|
uint8_t array_length, uint8_t wire_offset) \
|
||||||
|
{ \
|
||||||
|
uint16_t i; \
|
||||||
|
for (i=0; i<array_length; i++) { \
|
||||||
|
value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
|
||||||
|
} \
|
||||||
|
return array_length*sizeof(value[0]); \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define _MAV_RETURN_ARRAY(TYPE, V) \
|
||||||
|
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
|
||||||
|
uint8_t array_length, uint8_t wire_offset) \
|
||||||
|
{ \
|
||||||
|
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
|
||||||
|
return array_length*sizeof(TYPE); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
_MAV_RETURN_ARRAY(uint16_t, u16)
|
||||||
|
_MAV_RETURN_ARRAY(uint32_t, u32)
|
||||||
|
_MAV_RETURN_ARRAY(uint64_t, u64)
|
||||||
|
_MAV_RETURN_ARRAY(int16_t, i16)
|
||||||
|
_MAV_RETURN_ARRAY(int32_t, i32)
|
||||||
|
_MAV_RETURN_ARRAY(int64_t, i64)
|
||||||
|
_MAV_RETURN_ARRAY(float, f)
|
||||||
|
_MAV_RETURN_ARRAY(double, d)
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,81 @@
|
||||||
|
/**
|
||||||
|
* @file parse_range_auxiliary_data_to_cloud.h
|
||||||
|
* @date 2023-07-27
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
#include "mavlink/SysMavlink/mavlink.h"
|
||||||
|
#include <vector>
|
||||||
|
#include <array>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Parse A Range And An Auxiliary Data To A Point Cloud
|
||||||
|
*
|
||||||
|
* @param auxiliaryData
|
||||||
|
* @param rangeData
|
||||||
|
* @param scanCloud Array elements are x, y, z, intensity respectively
|
||||||
|
* @return true
|
||||||
|
* @return false
|
||||||
|
*/
|
||||||
|
bool parseRangeAuxiliaryDataToCloud(
|
||||||
|
const mavlink_ret_lidar_auxiliary_data_packet_t &auxiliaryData,
|
||||||
|
const mavlink_ret_lidar_distance_data_packet_t &rangeData,
|
||||||
|
std::vector<std::array<float, 4>> &scanCloud
|
||||||
|
){
|
||||||
|
|
||||||
|
// check packet id match
|
||||||
|
if (auxiliaryData.packet_id != rangeData.packet_id){
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// parse data
|
||||||
|
float rotate_yaw_bias = 0;
|
||||||
|
float range_scale = 0.001;
|
||||||
|
float z_bias = 0.0445;
|
||||||
|
int points_num_of_scan = 120;
|
||||||
|
float bias_laser_beam_ = auxiliaryData.b_axis_dist / 1000;
|
||||||
|
|
||||||
|
float sin_theta = sin(auxiliaryData.theta_angle);
|
||||||
|
float cos_theta = cos(auxiliaryData.theta_angle);
|
||||||
|
float sin_ksi = sin(auxiliaryData.ksi_angle);
|
||||||
|
float cos_ksi = cos(auxiliaryData.ksi_angle);
|
||||||
|
|
||||||
|
float pitch_cur = auxiliaryData.sys_vertical_angle_start * M_PI / 180.0;
|
||||||
|
float pitch_step = auxiliaryData.sys_vertical_angle_span * M_PI / 180.0;
|
||||||
|
float yaw_cur = (auxiliaryData.com_horizontal_angle_start + rotate_yaw_bias) * M_PI / 180.0;
|
||||||
|
float yaw_step = auxiliaryData.com_horizontal_angle_step / points_num_of_scan * M_PI / 180.0;
|
||||||
|
|
||||||
|
uint16_t range;
|
||||||
|
float range_float;
|
||||||
|
|
||||||
|
std::array<float, 4> point;
|
||||||
|
for (int i = 0, j = 0; j < points_num_of_scan;
|
||||||
|
i += 2, j += 1,
|
||||||
|
pitch_cur += pitch_step, yaw_cur += yaw_step)
|
||||||
|
{
|
||||||
|
// Calculate point range in float type
|
||||||
|
range = (rangeData.point_data[i + 1] << 8);
|
||||||
|
range = range | rangeData.point_data[i];
|
||||||
|
if (range == 0){
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
range_float = range_scale * range;
|
||||||
|
|
||||||
|
// Transform this point to XYZ coordinate
|
||||||
|
float&& sin_alpha = sin(pitch_cur);
|
||||||
|
float&& cos_alpha = cos(pitch_cur);
|
||||||
|
float&& sin_beta = sin(yaw_cur);
|
||||||
|
float&& cos_beta = cos(yaw_cur);
|
||||||
|
|
||||||
|
float&& A = (-cos_theta * sin_ksi + sin_theta * sin_alpha * cos_ksi) * range_float + bias_laser_beam_;
|
||||||
|
float&& B = cos_alpha * cos_ksi * range_float;
|
||||||
|
|
||||||
|
point[0] = cos_beta * A - sin_beta * B; // x
|
||||||
|
point[1] = sin_beta * A + cos_beta * B; // y
|
||||||
|
point[2] = (sin_theta * sin_ksi + cos_theta * sin_alpha * cos_ksi) * range_float + z_bias; // z
|
||||||
|
point[3] = auxiliaryData.reflect_data[j];
|
||||||
|
scanCloud.push_back(point);
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
|
@ -0,0 +1,46 @@
|
||||||
|
#ifndef __SERIALPORT_H__
|
||||||
|
#define __SERIALPORT_H__
|
||||||
|
|
||||||
|
#include <termios.h>
|
||||||
|
|
||||||
|
#define flag 1
|
||||||
|
#define noflag 0
|
||||||
|
|
||||||
|
//ComPort config
|
||||||
|
#define COM_PORT 0
|
||||||
|
#define COM_BUFFER_SIZE 256
|
||||||
|
#define PORT_SPEED 9600
|
||||||
|
#define PORT_DATABITS 8
|
||||||
|
#define PORT_PARITY 'N'
|
||||||
|
#define PORT_STOPBITS 1
|
||||||
|
|
||||||
|
class SerialPort {
|
||||||
|
public:
|
||||||
|
typedef struct Port_info_t
|
||||||
|
{
|
||||||
|
int fd;
|
||||||
|
pthread_mutex_t mt;
|
||||||
|
char name[24];
|
||||||
|
struct termios ntm;
|
||||||
|
} Port_INFO;
|
||||||
|
|
||||||
|
public:
|
||||||
|
int InitPort(Port_INFO *pPort, int);
|
||||||
|
int cleanPort(Port_INFO *pPort);
|
||||||
|
|
||||||
|
int sendnPort(Port_INFO *ptty,char *pbuf,int size);
|
||||||
|
int signal_recvnPort(Port_INFO *pPort,char *pbuf,int size);
|
||||||
|
|
||||||
|
private:
|
||||||
|
Port_INFO *readyPort(int id, Port_INFO *pPort);
|
||||||
|
int setPortSpeed(Port_INFO *pPort, int port_speed);
|
||||||
|
int setPortParity(Port_INFO *pPort,int databits,int parity,int stopbits);
|
||||||
|
|
||||||
|
int recvnPort(Port_INFO *ptty,char *pbuf,int size);
|
||||||
|
|
||||||
|
int lockPort(Port_INFO *pPort);
|
||||||
|
int unlockPort(Port_INFO *pPort);
|
||||||
|
};
|
||||||
|
#endif // __SERIALPORT_H__
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,51 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
#include <windows.h>
|
||||||
|
#define socklen_t int
|
||||||
|
typedef unsigned int uint32_t;
|
||||||
|
#else
|
||||||
|
#include <arpa/inet.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
# define closesocket close
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
#include <cstring>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief UDP Handler
|
||||||
|
*/
|
||||||
|
class UDPHandler
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
UDPHandler(unsigned short port = 9000);
|
||||||
|
virtual ~UDPHandler();
|
||||||
|
|
||||||
|
int CreateSocket();
|
||||||
|
void Close();
|
||||||
|
bool Bind();
|
||||||
|
|
||||||
|
int Send(const char *buf, int size, char *ip, unsigned short port);
|
||||||
|
int Recv(char *buf, int bufsize, sockaddr_in *from);
|
||||||
|
|
||||||
|
int SetRecvTimeout(int sec);
|
||||||
|
int SetSendTimeout(int sec);
|
||||||
|
|
||||||
|
private:
|
||||||
|
int usock = 0;
|
||||||
|
unsigned short uport = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Transform a Data Struct to UDP buffer
|
||||||
|
*
|
||||||
|
* @tparam DataStruct an IMUUnitree or ScanUnitree
|
||||||
|
* @param data
|
||||||
|
* @param buffer
|
||||||
|
* @param msgType
|
||||||
|
* @return uint32_t the total bytes sent through udp
|
||||||
|
*/
|
||||||
|
template <typename DataStruct>
|
||||||
|
uint32_t dataStructToUDPBuffer(const DataStruct &data, uint32_t msgType, char *buffer);
|
|
@ -0,0 +1,8 @@
|
||||||
|
sxai/opencv4.2
|
||||||
|
cuda/x86trt
|
||||||
|
@model/yolov8n.transd.onnx -save=workspace
|
||||||
|
@model/yolov8n-seg.b1.transd.onnx -save=workspace
|
||||||
|
@cuda/ocvtrtmk -save=.
|
||||||
|
templ/cumk
|
||||||
|
>Step1: You can execute "<yellow>bash workspace/build.sh</yellow>" to build trtmodel
|
||||||
|
>Step2: You can execute "<yellow>make run -j</yellow>", have a nice day.🤗
|
|
@ -0,0 +1,65 @@
|
||||||
|
{
|
||||||
|
"files.associations": {
|
||||||
|
"cctype": "cpp",
|
||||||
|
"clocale": "cpp",
|
||||||
|
"cmath": "cpp",
|
||||||
|
"csignal": "cpp",
|
||||||
|
"cstdarg": "cpp",
|
||||||
|
"cstddef": "cpp",
|
||||||
|
"cstdio": "cpp",
|
||||||
|
"cstdlib": "cpp",
|
||||||
|
"cstring": "cpp",
|
||||||
|
"ctime": "cpp",
|
||||||
|
"cwchar": "cpp",
|
||||||
|
"cwctype": "cpp",
|
||||||
|
"array": "cpp",
|
||||||
|
"atomic": "cpp",
|
||||||
|
"strstream": "cpp",
|
||||||
|
"*.tcc": "cpp",
|
||||||
|
"bitset": "cpp",
|
||||||
|
"chrono": "cpp",
|
||||||
|
"complex": "cpp",
|
||||||
|
"condition_variable": "cpp",
|
||||||
|
"cstdint": "cpp",
|
||||||
|
"deque": "cpp",
|
||||||
|
"list": "cpp",
|
||||||
|
"unordered_map": "cpp",
|
||||||
|
"vector": "cpp",
|
||||||
|
"exception": "cpp",
|
||||||
|
"algorithm": "cpp",
|
||||||
|
"functional": "cpp",
|
||||||
|
"iterator": "cpp",
|
||||||
|
"map": "cpp",
|
||||||
|
"memory": "cpp",
|
||||||
|
"memory_resource": "cpp",
|
||||||
|
"numeric": "cpp",
|
||||||
|
"optional": "cpp",
|
||||||
|
"random": "cpp",
|
||||||
|
"ratio": "cpp",
|
||||||
|
"set": "cpp",
|
||||||
|
"string": "cpp",
|
||||||
|
"string_view": "cpp",
|
||||||
|
"system_error": "cpp",
|
||||||
|
"tuple": "cpp",
|
||||||
|
"type_traits": "cpp",
|
||||||
|
"utility": "cpp",
|
||||||
|
"fstream": "cpp",
|
||||||
|
"initializer_list": "cpp",
|
||||||
|
"iomanip": "cpp",
|
||||||
|
"iosfwd": "cpp",
|
||||||
|
"iostream": "cpp",
|
||||||
|
"istream": "cpp",
|
||||||
|
"limits": "cpp",
|
||||||
|
"mutex": "cpp",
|
||||||
|
"new": "cpp",
|
||||||
|
"ostream": "cpp",
|
||||||
|
"sstream": "cpp",
|
||||||
|
"stdexcept": "cpp",
|
||||||
|
"streambuf": "cpp",
|
||||||
|
"thread": "cpp",
|
||||||
|
"cfenv": "cpp",
|
||||||
|
"cinttypes": "cpp",
|
||||||
|
"typeindex": "cpp",
|
||||||
|
"typeinfo": "cpp"
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,672 @@
|
||||||
|
#include <iostream>
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
// opencv 用于图像数据读取与处理
|
||||||
|
#include <opencv2/core/core.hpp>
|
||||||
|
#include <opencv2/imgproc/imgproc.hpp>
|
||||||
|
#include <opencv2/highgui/highgui.hpp>
|
||||||
|
// #include <opencv2/core/eigen.hpp>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// 使用Eigen的Geometry模块处理3d运动
|
||||||
|
#include <Eigen/Core>
|
||||||
|
#include <Eigen/Geometry>
|
||||||
|
#include <Eigen/Dense>
|
||||||
|
|
||||||
|
#include <opencv2/core/eigen.hpp>
|
||||||
|
|
||||||
|
// pcl
|
||||||
|
#include <pcl/common/transforms.h>
|
||||||
|
#include <pcl/point_types.h>
|
||||||
|
#include <pcl/io/pcd_io.h>
|
||||||
|
#include <pcl/filters/conditional_removal.h> //条件滤波器头文件
|
||||||
|
#include <pcl/filters/passthrough.h> //直通滤波器头文件
|
||||||
|
#include <pcl/filters/radius_outlier_removal.h> //半径滤波器头文件
|
||||||
|
#include <pcl/filters/statistical_outlier_removal.h> //统计滤波器头文件
|
||||||
|
#include <pcl/filters/voxel_grid.h> //体素滤波器头文件
|
||||||
|
#include <pcl/segmentation/extract_clusters.h>
|
||||||
|
#include <pcl/point_cloud.h>
|
||||||
|
#include <pcl/kdtree/kdtree_flann.h>
|
||||||
|
#include <pcl/io/pcd_io.h>
|
||||||
|
#include <pcl/PointIndices.h>
|
||||||
|
#include <pcl/filters/extract_indices.h>
|
||||||
|
#include <pcl/filters/filter.h>
|
||||||
|
// boost.format 字符串处理
|
||||||
|
#include <boost/format.hpp>
|
||||||
|
|
||||||
|
#include "../include/DepthProcessor.hpp"
|
||||||
|
#include "DepthProcessor.hpp"
|
||||||
|
#include <chrono>
|
||||||
|
#include <thread>
|
||||||
|
#include <future>
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
|
//排序用
|
||||||
|
bool point_cmp(PointXYZ a, PointXYZ b){
|
||||||
|
return a.z<b.z;
|
||||||
|
}
|
||||||
|
|
||||||
|
//将深度图转换为点云
|
||||||
|
PointCloudXYZ::Ptr DepthProcessor::depth2Cloud(PointCloudXYZ::Ptr oriCloud, const cv::Mat depthMat, int startRow, int endRow){
|
||||||
|
int height = depthMat.rows;
|
||||||
|
endRow = std::min(height, endRow);
|
||||||
|
|
||||||
|
for (int y = startRow; y < endRow; ++y) {
|
||||||
|
for (int x = 0; x < imgDepth.cols; ++x)
|
||||||
|
{
|
||||||
|
// 获取深度值
|
||||||
|
float depth = imgDepth.at<float>(y, x);
|
||||||
|
// 忽略深度值小于320mm的点
|
||||||
|
if (depth <= 320)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
// 计算三维坐标
|
||||||
|
double X = (x - cx) * depth / fx / 1000;
|
||||||
|
if(X > 0.5 || X < -0.5)
|
||||||
|
continue;
|
||||||
|
double Y = (y - cy) * depth / fy / 1000;
|
||||||
|
double Z = depth / 1000;
|
||||||
|
|
||||||
|
// 创建点云点并设置坐标
|
||||||
|
PointXYZ point;
|
||||||
|
point.x = X;
|
||||||
|
point.y = Y;
|
||||||
|
point.z = Z;
|
||||||
|
|
||||||
|
// 将点添加到点云中
|
||||||
|
oriCloud->push_back(point);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return oriCloud;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 先统计Y轴的直方图,初筛出可能包含地面的点(若Y轴坐标太小或点数太少则可能未观测到地面)
|
||||||
|
// 在这些点中进行平面拟合,精筛出属于地面的点
|
||||||
|
// 在原点云中剔除属于地面的点
|
||||||
|
PointCloudXYZ::Ptr DepthProcessor::delGround(const PointCloudXYZ::Ptr& pointCloud){
|
||||||
|
float maxY;
|
||||||
|
std::vector<std::vector<int>> histogram;
|
||||||
|
|
||||||
|
if(pointCloud->points.size() <= 10){
|
||||||
|
PointCloudXYZ::Ptr nopoint(new PointCloudXYZ);
|
||||||
|
return nopoint;
|
||||||
|
}
|
||||||
|
calHistogram(pointCloud, maxY, histogram);
|
||||||
|
|
||||||
|
// 地面上的点数必须大于20,是否应该要求maxY大于阈值?是否考虑最低点不是地面?
|
||||||
|
int n = histogram.size() - 1;
|
||||||
|
while(histogram[n].size() < 20 ) n--;
|
||||||
|
float lowY = maxY - 0.1 * (histogram.size() - n + 1);
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr objCloud = axisFilter(pointCloud, lowY, maxY, "y", true);
|
||||||
|
// 若最低点有足够多的点,则认为最低点就是地面
|
||||||
|
// if(n == histogram.size() - 1) return objCloud;
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr groundCloud = axisFilter(pointCloud, lowY, maxY, "y", false);
|
||||||
|
// 地面点太少就不拟合平面
|
||||||
|
if(groundCloud->size()<10) return axisFilter(pointCloud, maxY-0.1, maxY, "y", true);
|
||||||
|
|
||||||
|
// 创建分割器对象
|
||||||
|
SACSegmentation<PointXYZ> seg;
|
||||||
|
seg.setOptimizeCoefficients(true);
|
||||||
|
|
||||||
|
// 设置分割模型类型(平面模型)
|
||||||
|
seg.setModelType(SACMODEL_PLANE);
|
||||||
|
// 设置方法类型(RANSAC)
|
||||||
|
seg.setMethodType(SAC_RANSAC);
|
||||||
|
// 设置最大迭代次数和拟合阈值(点到平面的垂直距离)
|
||||||
|
seg.setMaxIterations(300);
|
||||||
|
seg.setDistanceThreshold(0.02);
|
||||||
|
// 输入点云
|
||||||
|
seg.setInputCloud(groundCloud);
|
||||||
|
// 创建存储模型系数的对象
|
||||||
|
ModelCoefficients::Ptr coefficients(new ModelCoefficients);
|
||||||
|
|
||||||
|
// 创建存储内点索引的对象
|
||||||
|
PointIndices::Ptr inliers(new PointIndices);
|
||||||
|
|
||||||
|
// 分割点云
|
||||||
|
seg.segment(*inliers, *coefficients);
|
||||||
|
|
||||||
|
//std::cout << "coefficients" << std::endl;
|
||||||
|
// 创建提取器对象
|
||||||
|
ExtractIndices<PointXYZ> extract;
|
||||||
|
|
||||||
|
// 设置提取器输入点云
|
||||||
|
extract.setInputCloud(groundCloud);
|
||||||
|
|
||||||
|
// 设置提取器的内点索引
|
||||||
|
extract.setIndices(inliers);
|
||||||
|
|
||||||
|
// 设置提取器的标志,为 true 表示提取非内点,即删除地面
|
||||||
|
extract.setNegative(true);
|
||||||
|
|
||||||
|
// 提取非地面点
|
||||||
|
PointCloudXYZ::Ptr no_ground_cloud(new PointCloudXYZ);
|
||||||
|
|
||||||
|
extract.filter(*no_ground_cloud);
|
||||||
|
*objCloud += *no_ground_cloud;
|
||||||
|
|
||||||
|
return objCloud;
|
||||||
|
}
|
||||||
|
|
||||||
|
//创建直方图
|
||||||
|
void DepthProcessor::calHistogram(const PointCloudXYZ::Ptr &pointCloud, float& maxY, std::vector<std::vector<int>>& histogram){
|
||||||
|
//求y的最小和最大值
|
||||||
|
float minY = 2;
|
||||||
|
maxY = -2;
|
||||||
|
for(int i = 0; i < pointCloud->points.size(); i++){
|
||||||
|
if(pointCloud->points[i].y > maxY)
|
||||||
|
maxY = pointCloud->points[i].y;
|
||||||
|
if(pointCloud->points[i].y < minY)
|
||||||
|
minY = pointCloud->points[i].y;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 创建直方图统计数组
|
||||||
|
int num_bins = (maxY - minY) / 0.05;
|
||||||
|
if (num_bins == 0)
|
||||||
|
num_bins = 1;
|
||||||
|
|
||||||
|
histogram.resize(num_bins);
|
||||||
|
|
||||||
|
// 遍历点云,统计 Y 轴坐标
|
||||||
|
for(int i = 0; i < pointCloud->points.size(); i ++){
|
||||||
|
float y_value = pointCloud->points[i].y;
|
||||||
|
int bin_index = static_cast<int>((y_value - minY) / (maxY - minY) * num_bins);
|
||||||
|
bin_index = std::max(0, std::min(num_bins - 1, bin_index));
|
||||||
|
histogram[bin_index].push_back(i);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//半径滤波,排除噪声点、坏点
|
||||||
|
void DepthProcessor::RadiusOutlierFilter(const PointCloudXYZ::Ptr &pcd_cloud0){
|
||||||
|
//创建滤波器
|
||||||
|
RadiusOutlierRemoval<PointXYZ> radiusoutlier;
|
||||||
|
//设置输入点云
|
||||||
|
radiusoutlier.setInputCloud(pcd_cloud0);
|
||||||
|
//设置半径,在该范围内找临近点
|
||||||
|
double radius = 0.1;
|
||||||
|
radiusoutlier.setRadiusSearch(radius);
|
||||||
|
//设置查询点的邻域点集数,小于该阈值的删除
|
||||||
|
int thre_count = 10;
|
||||||
|
radiusoutlier.setMinNeighborsInRadius(thre_count);
|
||||||
|
PointCloudXYZ::Ptr cloud_after_Radius ( new PointCloudXYZ );
|
||||||
|
radiusoutlier.filter(*cloud_after_Radius);
|
||||||
|
std::cout << "cloud_after_Radius:" << cloud->points.size() <<std::endl;
|
||||||
|
cloud = cloud_after_Radius;
|
||||||
|
}
|
||||||
|
|
||||||
|
//直通滤波,过滤指定轴方向的点
|
||||||
|
PointCloudXYZ::Ptr DepthProcessor::axisFilter(const PointCloudXYZ::Ptr& pointCloud, const double &thre_low, const double &thre_high, const string& field, const bool &flag_in){
|
||||||
|
// 创建滤波器对象
|
||||||
|
PassThrough<PointXYZ> passthrough;
|
||||||
|
//输入点云
|
||||||
|
passthrough.setInputCloud(pointCloud);
|
||||||
|
//设置对z轴进行操作
|
||||||
|
passthrough.setFilterFieldName(field);
|
||||||
|
//设置滤波范围
|
||||||
|
passthrough.setFilterLimits(thre_low, thre_high);
|
||||||
|
// true表示保留滤波范围外,false表示保留范围内
|
||||||
|
passthrough.setFilterLimitsNegative(flag_in);
|
||||||
|
//执行滤波并存储
|
||||||
|
PointCloudXYZ::Ptr cloud_after_PassThrough ( new PointCloudXYZ );
|
||||||
|
passthrough.filter(*cloud_after_PassThrough);
|
||||||
|
|
||||||
|
return cloud_after_PassThrough;
|
||||||
|
}
|
||||||
|
|
||||||
|
//条件滤波
|
||||||
|
void DepthProcessor::ConditionFilter(const double &ground){
|
||||||
|
// 创建条件滤波器对象
|
||||||
|
ConditionAnd<PointXYZ>::Ptr range_cond(new ConditionAnd<PointXYZ>());
|
||||||
|
|
||||||
|
// 添加条件,例如:删除 x 坐标在某个范围内的点
|
||||||
|
range_cond->addComparison(FieldComparison<PointXYZ>::ConstPtr(new FieldComparison<PointXYZ>("y", ComparisonOps::GT, ground - thre_ground)));
|
||||||
|
range_cond->addComparison(FieldComparison<PointXYZ>::ConstPtr(new FieldComparison<PointXYZ>("y", ComparisonOps::LT, ground)));
|
||||||
|
|
||||||
|
// 创建条件滤波器
|
||||||
|
ConditionalRemoval<PointXYZ> condrem;
|
||||||
|
condrem.setCondition(range_cond);
|
||||||
|
condrem.setInputCloud(cloud);
|
||||||
|
condrem.setKeepOrganized(false); // 设置为 false 表示保持点云的结构
|
||||||
|
condrem.filter(*cloud);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//最近邻搜索或半径搜索,返回的是点云的索引
|
||||||
|
void DepthProcessor::radiusSearch(const PointCloudXYZ::Ptr& pointCloud, const PointXYZ& queryPoint, const float& radius, std::vector<int>& indResults){
|
||||||
|
// 创建最近邻搜索对象
|
||||||
|
KdTreeFLANN<PointXYZ> kdtree;
|
||||||
|
kdtree.setInputCloud(pointCloud);
|
||||||
|
//结果点的距离
|
||||||
|
std::vector<float> pointDistances;
|
||||||
|
kdtree.radiusSearch(queryPoint, radius, indResults, pointDistances);
|
||||||
|
}
|
||||||
|
|
||||||
|
//加载配置文件
|
||||||
|
void DepthProcessor::load_config(const string filepath){
|
||||||
|
cv::FileStorage fsSettings(filepath, cv::FileStorage::READ);
|
||||||
|
|
||||||
|
if(!fsSettings.isOpened())
|
||||||
|
{
|
||||||
|
cerr << "Failed to open settings file at: " << filepath << endl;
|
||||||
|
exit(-1);
|
||||||
|
}
|
||||||
|
|
||||||
|
fx = fsSettings["fx"];
|
||||||
|
fy = fsSettings["fy"];
|
||||||
|
cx = fsSettings["cx"];
|
||||||
|
cy = fsSettings["cy"];
|
||||||
|
minDepth = fsSettings["minDepth"];
|
||||||
|
maxDepth = fsSettings["maxDepth"];
|
||||||
|
thre_count = fsSettings["thre_count"];
|
||||||
|
radius = fsSettings["radius"];
|
||||||
|
thre_low_x = fsSettings["thre_low_x"];
|
||||||
|
thre_high_x = fsSettings["thre_high_x"];
|
||||||
|
thre_low_y = fsSettings["thre_low_y"];
|
||||||
|
thre_high_y = fsSettings["thre_high_y"];
|
||||||
|
thre_ponit_count = fsSettings["thre_ponit_count"];
|
||||||
|
thre_point_radius = fsSettings["thre_point_radius"];
|
||||||
|
}
|
||||||
|
|
||||||
|
//检测物体的类别,返回是否有检测的标签
|
||||||
|
bool DepthProcessor::obstacleRecognize(cv::Mat boxes){
|
||||||
|
if (boxes.cols < 4)
|
||||||
|
{
|
||||||
|
std::cout << "boxes col nums error" << std::endl;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
for(int i = 0; i < boxes.rows; i++){
|
||||||
|
double rate = IOU(max_x,min_x,max_y,min_y,boxes.at<int>(i,0),boxes.at<int>(i,1),boxes.at<int>(i,2),boxes.at<int>(i,3));
|
||||||
|
if(rate >= 0.8){
|
||||||
|
label = "";
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
cv::Mat DepthProcessor::getObstacle(){
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//相机初始化
|
||||||
|
bool DepthProcessor::camHighInit(const cv::Mat depthMat, const Eigen::Affine3f& transform){
|
||||||
|
//深度图转点云
|
||||||
|
imgDepth = depthMat.clone();
|
||||||
|
imgDepth.convertTo(imgDepth, CV_32FC1);
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr tmpCloud(new PointCloudXYZ);
|
||||||
|
PointCloudXYZ::Ptr oriCloud = depth2Cloud(tmpCloud, depthMat, 0, depthMat.rows);
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr cloudLeft = axisFilter(oriCloud, -1.5, 0, "x", false);
|
||||||
|
PointCloudXYZ::Ptr cloudRight = axisFilter(oriCloud, 0, 1.5, "x", false);
|
||||||
|
|
||||||
|
cloudLeft = downsampling(cloudLeft, 0.02);
|
||||||
|
cloudRight = downsampling(cloudRight, 0.02);
|
||||||
|
*oriCloud = *cloudLeft + *cloudRight;
|
||||||
|
|
||||||
|
// 将点云变换到水平面
|
||||||
|
if(oriCloud->points.size() == 0) return false;
|
||||||
|
transformPointCloud(*oriCloud, *cloud, transform);
|
||||||
|
|
||||||
|
std::vector<std::vector<int>> histogram;
|
||||||
|
|
||||||
|
//创建直方图
|
||||||
|
calHistogram(cloud, camHigh, histogram);
|
||||||
|
|
||||||
|
//判断点云最多的直方图
|
||||||
|
int max_value = 0;
|
||||||
|
int max_n = 0;
|
||||||
|
for (int i = 0; i < histogram.size(); i++) {
|
||||||
|
if (histogram[i].size() > max_value) {
|
||||||
|
max_value = histogram[i].size(); // 更新最大值
|
||||||
|
max_n = i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
float sum = 0;
|
||||||
|
|
||||||
|
//取最多的一块点相邻的块进行平面拟合,内点多则用其计算均值
|
||||||
|
PointCloudXYZ::Ptr TCloud ( new PointCloudXYZ );
|
||||||
|
int num = -1;
|
||||||
|
|
||||||
|
if(max_n == histogram.size() -1){
|
||||||
|
for(;num <= 0; num ++)
|
||||||
|
for(auto Tpoint:histogram[max_n + num])
|
||||||
|
TCloud->push_back(cloud->points[Tpoint]);
|
||||||
|
}else{
|
||||||
|
for(;num <= 1; num ++)
|
||||||
|
for(auto Tpoint:histogram[max_n + num])
|
||||||
|
TCloud->push_back(cloud->points[Tpoint]);
|
||||||
|
}
|
||||||
|
|
||||||
|
// 创建分割器对象
|
||||||
|
SACSegmentation<PointXYZ> seg;
|
||||||
|
seg.setOptimizeCoefficients(true);
|
||||||
|
|
||||||
|
// 设置分割模型类型(平面模型)
|
||||||
|
seg.setModelType(SACMODEL_PLANE);
|
||||||
|
// 设置方法类型(RANSAC)
|
||||||
|
seg.setMethodType(SAC_RANSAC);
|
||||||
|
// 设置最大迭代次数和拟合阈值(点到平面的垂直距离)
|
||||||
|
seg.setMaxIterations(2000);
|
||||||
|
seg.setDistanceThreshold(0.02);
|
||||||
|
// 输入点云
|
||||||
|
seg.setInputCloud(TCloud);
|
||||||
|
// 创建存储模型系数的对象
|
||||||
|
ModelCoefficients::Ptr coefficients(new ModelCoefficients);
|
||||||
|
// 创建存储内点索引的对象
|
||||||
|
PointIndices::Ptr inliers(new PointIndices);
|
||||||
|
// 分割点云
|
||||||
|
seg.segment(*inliers, *coefficients);
|
||||||
|
|
||||||
|
//设置的点阈值,认为200个点以上才是地面
|
||||||
|
if(inliers->indices.size() > 200){
|
||||||
|
for(auto ind : inliers->indices)
|
||||||
|
sum = sum + TCloud->points[ind].y;
|
||||||
|
camHigh = sum / inliers->indices.size();
|
||||||
|
|
||||||
|
}else{
|
||||||
|
for(int i = 0; i< histogram[max_n].size(); i++){
|
||||||
|
sum = sum + cloud->points[histogram[max_n][i]].y;
|
||||||
|
}
|
||||||
|
camHigh = sum / histogram[max_n].size(); //myx
|
||||||
|
}
|
||||||
|
|
||||||
|
pcdViewer->updatePointCloud(cloud, "cloud1");
|
||||||
|
pcdViewer->updatePointCloud(TCloud, "cloud2");
|
||||||
|
pcdViewer->spinOnce(5);
|
||||||
|
|
||||||
|
//判断地面高度合理性
|
||||||
|
if(camHigh < 1.5 && camHigh > 0.5)
|
||||||
|
return true;
|
||||||
|
else
|
||||||
|
std::cout << "高度:"<< camHigh;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
//检测物体,返回是否检测到物体并将物体信息放在成员变量中
|
||||||
|
bool DepthProcessor::obstacleDetect(const cv::Mat depthMat, const Eigen::Affine3f& transform){
|
||||||
|
imgDepth = depthMat.clone();
|
||||||
|
imgDepth.convertTo(imgDepth, CV_32FC1);
|
||||||
|
|
||||||
|
//深度图转点云
|
||||||
|
PointCloudXYZ::Ptr c(new PointCloudXYZ);
|
||||||
|
PointCloudXYZ::Ptr oriCloud = depth2Cloud(c, depthMat, 0, depthMat.rows);
|
||||||
|
|
||||||
|
//下采样减少点数量
|
||||||
|
PointCloudXYZ::Ptr cloudLeft = axisFilter(oriCloud, -1.5, 0, "x", false);
|
||||||
|
PointCloudXYZ::Ptr cloudRight = axisFilter(oriCloud, 0, 1.5, "x", false);
|
||||||
|
cloudLeft = downsampling(cloudLeft, 0.02);
|
||||||
|
cloudRight = downsampling(cloudRight, 0.02);
|
||||||
|
*oriCloud = *cloudLeft + *cloudRight;
|
||||||
|
|
||||||
|
// 将点云变换到水平面
|
||||||
|
if(oriCloud->points.size() == 0) return false;
|
||||||
|
|
||||||
|
//旋转点云
|
||||||
|
transformPointCloud(*oriCloud, *cloud, transform);
|
||||||
|
|
||||||
|
//剔除camHight初始化高度以下的点
|
||||||
|
cloud = axisFilter(cloud, camHigh +0.01, camHigh +0.01+ 1, "y", true);
|
||||||
|
|
||||||
|
// 在各个方向上截取点云
|
||||||
|
if(cloud->points.size() == 0) return false;
|
||||||
|
cloud = axisFilter(cloud, -0.4, 0.4, "x", false);
|
||||||
|
|
||||||
|
if(cloud->points.size() <= 10) return false;
|
||||||
|
cloud = axisFilter(cloud, 0, 2, "z", false);
|
||||||
|
|
||||||
|
if(cloud->points.size() <= 10) return false;
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr tmpCloud(new PointCloudXYZ);
|
||||||
|
PointCloudXYZ::Ptr resultCloud(new PointCloudXYZ);
|
||||||
|
|
||||||
|
//分块处理地面点云部分
|
||||||
|
for(int i = 0; i < 4; i++){
|
||||||
|
tmpCloud = axisFilter(cloud, i*0.5, (i+1)*0.5, "z", false);
|
||||||
|
|
||||||
|
if(tmpCloud->size() == 0) continue;
|
||||||
|
float tmp_height;
|
||||||
|
std::vector<std::vector<int>> histogram_y;
|
||||||
|
|
||||||
|
calHistogram(tmpCloud, tmp_height, histogram_y);
|
||||||
|
|
||||||
|
if(tmp_height < camHigh -0.1 )
|
||||||
|
*resultCloud += *tmpCloud;
|
||||||
|
else
|
||||||
|
*resultCloud += *delGround(tmpCloud);
|
||||||
|
}
|
||||||
|
|
||||||
|
cloud = resultCloud;
|
||||||
|
|
||||||
|
if(cloud->points.size() == 0)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
std::vector<std::vector<int>> histograms;
|
||||||
|
calHistogramZ(cloud, histograms);
|
||||||
|
|
||||||
|
pcl::PointCloud<pcl::PointXYZ>::Ptr nearestCloud(new pcl::PointCloud<pcl::PointXYZ>);
|
||||||
|
pcl::PointCloud<pcl::PointXYZ>::Ptr otherCloud(new pcl::PointCloud<pcl::PointXYZ>);
|
||||||
|
//通过最近邻或半径滤波做处理,这里用半径滤波
|
||||||
|
int count = 0, temp_outerindex = -1;
|
||||||
|
//暂存已经查过的点的索引值
|
||||||
|
std::vector<int> tmp_outersindex;
|
||||||
|
std::vector<int> tmp_index;
|
||||||
|
|
||||||
|
//记录是否有物体
|
||||||
|
bool haveObstacle = false;
|
||||||
|
|
||||||
|
for(int i = 0; i < histograms.size();){
|
||||||
|
PointXYZ pointZ;
|
||||||
|
pointZ.z = 100.00;
|
||||||
|
if(histograms[i].size() == 0){
|
||||||
|
i++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
//获取点云中Z轴方向最近的点
|
||||||
|
for(int j = 0; j < histograms[i].size(); j++){
|
||||||
|
if(tmp_outersindex.size() >= histograms[i].size()){
|
||||||
|
tmp_outersindex.clear();
|
||||||
|
i++;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if(std::find(tmp_outersindex.begin(), tmp_outersindex.end(), histograms[i][j]) != tmp_outersindex.end())
|
||||||
|
continue;
|
||||||
|
if(cloud->points[histograms[i][j]].z <= pointZ.z){
|
||||||
|
pointZ = cloud->points[histograms[i][j]];
|
||||||
|
temp_outerindex = histograms[i][j];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//通过半径聚类结果判断最近点是否是障碍物
|
||||||
|
radiusSearch(cloud, pointZ, 0.1, tmp_index);
|
||||||
|
if(tmp_index.size() < /*thre_ponit_count*/ 60){
|
||||||
|
//TODO:认为这个点不是物体上的点,做一些剔除操作
|
||||||
|
tmp_outersindex.push_back(temp_outerindex);
|
||||||
|
count++;
|
||||||
|
continue;
|
||||||
|
}else{
|
||||||
|
// 创建一个 pcl::PointIndices 对象,指定要删除的点的索引
|
||||||
|
pcl::PointIndices::Ptr indices(new pcl::PointIndices);
|
||||||
|
indices->indices = tmp_index;
|
||||||
|
// 创建 pcl::ExtractIndices 对象
|
||||||
|
pcl::ExtractIndices<pcl::PointXYZ> extract;
|
||||||
|
// 设置要分割的输入点云
|
||||||
|
extract.setInputCloud(cloud);
|
||||||
|
|
||||||
|
// 设置要删除的点的索引
|
||||||
|
extract.setIndices(indices);
|
||||||
|
|
||||||
|
// 设置分割标志,为 true 表示提取非内点,即删除指定的点
|
||||||
|
extract.setNegative(true);
|
||||||
|
extract.filter(*otherCloud);
|
||||||
|
|
||||||
|
extract.setNegative(false);
|
||||||
|
extract.filter(*nearestCloud);
|
||||||
|
//计算像素坐标的四个顶角
|
||||||
|
Eigen::Affine3f Intransform = transform.inverse();
|
||||||
|
PointXYZ point;
|
||||||
|
|
||||||
|
pcl::PointXYZRGB red_point;
|
||||||
|
int minU = 2000;
|
||||||
|
int minV = 2000;
|
||||||
|
int maxU = -10;
|
||||||
|
int maxV = -10;
|
||||||
|
|
||||||
|
for(int i=0; i<nearestCloud->points.size();i++){
|
||||||
|
point = nearestCloud->points[i];
|
||||||
|
PointXYZ outPoint = pcl::transformPoint(point, Intransform);
|
||||||
|
|
||||||
|
int u = outPoint.x * fx / (outPoint.z) + cx;
|
||||||
|
int v = outPoint.y * fy / (outPoint.z) + cy;
|
||||||
|
minU = u < minU ? u : minU;
|
||||||
|
minV = v < minV ? v : minV;
|
||||||
|
maxU = u > maxU ? u : maxU;
|
||||||
|
maxV = v > maxV ? v : maxV;
|
||||||
|
}
|
||||||
|
|
||||||
|
max_x = maxU;
|
||||||
|
min_x = minU;
|
||||||
|
max_y = maxV;
|
||||||
|
min_y = minV;
|
||||||
|
|
||||||
|
dist = pointZ.z;
|
||||||
|
haveObstacle = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
pcdViewer->updatePointCloud(otherCloud, "cloud1");
|
||||||
|
pcdViewer->updatePointCloud(nearestCloud, "cloud2");
|
||||||
|
pcdViewer->spinOnce(5);
|
||||||
|
|
||||||
|
return haveObstacle;
|
||||||
|
}
|
||||||
|
|
||||||
|
//计算两个框的交并比
|
||||||
|
double DepthProcessor::IOU(double max_x1,double min_x1,double max_y1,double min_y1,
|
||||||
|
double max_x2,double min_x2,double max_y2,double min_y2){
|
||||||
|
double maxx,maxy,minx,miny;
|
||||||
|
maxx = (max_x1 < max_x2) ? max_x1 : max_x2;
|
||||||
|
minx = (min_x1 < min_x2) ? min_x2 : min_x1;
|
||||||
|
maxy = (max_y1 < max_y2) ? max_y1 : max_y2;
|
||||||
|
miny = (min_y1 < min_y2) ? min_y2 : min_y1;
|
||||||
|
|
||||||
|
double w = maxx - minx;
|
||||||
|
double h = maxy - miny;
|
||||||
|
double size = abs((max_x1 - min_x1) * (max_y1 - min_y1) + (max_x2 - min_x2)* (max_y2 - min_y2) - h * w);
|
||||||
|
|
||||||
|
double size_box1 = (max_x1 - min_x1) * (max_y1 - min_y1);
|
||||||
|
double size_box2 = (max_x2 - min_x2) * (max_y2 - min_y2);
|
||||||
|
|
||||||
|
return (size_box2 < size_box1) ? (h*w / size_box2):(h*w / size_box1);
|
||||||
|
}
|
||||||
|
|
||||||
|
//Z轴方向的直方图
|
||||||
|
void DepthProcessor::calHistogramZ(const PointCloudXYZ::Ptr &pointCloud, std::vector<std::vector<int>> &histogram){
|
||||||
|
float minZ = 2;
|
||||||
|
float maxZ = -2;
|
||||||
|
for(int i = 0; i < pointCloud->points.size(); i++){
|
||||||
|
if(pointCloud->points[i].z > maxZ)
|
||||||
|
maxZ = pointCloud->points[i].z;
|
||||||
|
if(pointCloud->points[i].z < minZ)
|
||||||
|
minZ = pointCloud->points[i].z;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 创建直方图统计数组
|
||||||
|
int num_bins = (maxZ - minZ) / 0.05;
|
||||||
|
if (num_bins == 0)
|
||||||
|
num_bins = 1;
|
||||||
|
|
||||||
|
histogram.resize(num_bins);
|
||||||
|
|
||||||
|
// 遍历点云,统计 Y 轴坐标
|
||||||
|
for(int i = 0; i < pointCloud->points.size(); i ++){
|
||||||
|
float z_value = pointCloud->points[i].z;
|
||||||
|
int bin_index = static_cast<int>((z_value - minZ) / (maxZ - minZ) * num_bins);
|
||||||
|
bin_index = std::max(0, std::min(num_bins - 1, bin_index));
|
||||||
|
histogram[bin_index].push_back(i);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
DepthProcessor::DepthProcessor(const std::string file_path, const cv::Mat tmp_mk){
|
||||||
|
mK = tmp_mk;
|
||||||
|
|
||||||
|
cloud = PointCloudXYZ::Ptr(new PointCloudXYZ);
|
||||||
|
pcdViewer = visualization::PCLVisualizer::Ptr (new visualization::PCLVisualizer("Point Cloud Viewer"));
|
||||||
|
// 设置背景颜色
|
||||||
|
pcdViewer->setBackgroundColor(0, 0, 0);
|
||||||
|
// 添加坐标轴
|
||||||
|
pcdViewer->addCoordinateSystem(1.0);
|
||||||
|
|
||||||
|
pcdViewer->addPointCloud<PointXYZ>(cloud, "cloud1");
|
||||||
|
pcdViewer->addPointCloud<PointXYZ>(cloud, "cloud2");
|
||||||
|
// 设置第二个点云的颜色为色
|
||||||
|
pcdViewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, "cloud2");
|
||||||
|
|
||||||
|
// 设置点云大小
|
||||||
|
// pcdViewer->setPointCloudRenderingProperties(visualization::PCL_VISUALIZER_POINT_SIZE, 2, "cloud2");
|
||||||
|
}
|
||||||
|
|
||||||
|
PointCloudXYZ::Ptr DepthProcessor::downsampling(const PointCloudXYZ::Ptr& pointCloud, float leaf){
|
||||||
|
// 创建 VoxelGrid 滤波器对象
|
||||||
|
VoxelGrid<PointXYZ> vg;
|
||||||
|
vg.setInputCloud (pointCloud);
|
||||||
|
vg.setLeafSize (leaf, leaf, leaf); // 设置体素的大小
|
||||||
|
|
||||||
|
// 执行下采样
|
||||||
|
PointCloudXYZ::Ptr filteredCloud (new PointCloudXYZ);
|
||||||
|
vg.filter (*filteredCloud);
|
||||||
|
// 保存下采样后的点云
|
||||||
|
return filteredCloud;
|
||||||
|
}
|
||||||
|
|
||||||
|
//另一个去除地面的方法
|
||||||
|
PointCloudXYZ::Ptr DepthProcessor::delGround_else(const PointCloudXYZ::Ptr &pointCloud, std::vector<int> index)
|
||||||
|
{
|
||||||
|
// 创建分割器对象
|
||||||
|
SACSegmentation<PointXYZ> seg;
|
||||||
|
seg.setOptimizeCoefficients(true);
|
||||||
|
|
||||||
|
// 设置分割模型类型(平面模型)
|
||||||
|
seg.setModelType(SACMODEL_PLANE);
|
||||||
|
// 设置方法类型(RANSAC)
|
||||||
|
seg.setMethodType(SAC_RANSAC);
|
||||||
|
// 设置最大迭代次数和拟合阈值(点到平面的垂直距离)
|
||||||
|
seg.setMaxIterations(2000);
|
||||||
|
seg.setDistanceThreshold(0.1);
|
||||||
|
// 输入点云
|
||||||
|
seg.setInputCloud(cloud);
|
||||||
|
|
||||||
|
// 创建存储模型系数的对象
|
||||||
|
ModelCoefficients::Ptr coefficients(new ModelCoefficients);
|
||||||
|
|
||||||
|
// 创建存储内点索引的对象
|
||||||
|
PointIndices::Ptr inliers(new PointIndices);
|
||||||
|
inliers->indices = index;
|
||||||
|
|
||||||
|
// 分割点云
|
||||||
|
seg.segment(*inliers, *coefficients);
|
||||||
|
|
||||||
|
// 创建提取器对象
|
||||||
|
ExtractIndices<PointXYZ> extract;
|
||||||
|
|
||||||
|
// 设置提取器输入点云
|
||||||
|
extract.setInputCloud(cloud);
|
||||||
|
|
||||||
|
// 设置提取器的内点索引
|
||||||
|
extract.setIndices(inliers);
|
||||||
|
|
||||||
|
// 设置提取器的标志,为 true 表示提取非内点,即删除地面
|
||||||
|
extract.setNegative(true);
|
||||||
|
|
||||||
|
// 提取非地面点
|
||||||
|
PointCloudXYZ::Ptr no_ground_cloud(new PointCloudXYZ);
|
||||||
|
extract.filter(*no_ground_cloud);
|
||||||
|
|
||||||
|
return no_ground_cloud;
|
||||||
|
}
|
|
@ -0,0 +1,39 @@
|
||||||
|
|
||||||
|
#include <opencv2/opencv.hpp>
|
||||||
|
|
||||||
|
#include "cpm.hpp"
|
||||||
|
#include "infer.hpp"
|
||||||
|
#include "Yolo.hpp"
|
||||||
|
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
const string& engine_file = "best.transd.engine";
|
||||||
|
const char * Yolo::cocoLabels[] = {"person", "bicycle",
|
||||||
|
"motorcycle", "bus", "fire hydrant",
|
||||||
|
"cat", "dog",
|
||||||
|
"bottle", "cup", "chair",
|
||||||
|
"couch", "potted plant", "bed",
|
||||||
|
"dining table", "toilet", "tv",
|
||||||
|
"refrigerator"};
|
||||||
|
|
||||||
|
|
||||||
|
Image cvimg(const cv::Mat &image) { return Image(image.data, image.cols, image.rows); }
|
||||||
|
|
||||||
|
BoxArray Yolo::detect(cv::Mat colorMat){
|
||||||
|
if (detector == nullptr) {
|
||||||
|
std::cout << "Yolo is not work !!!" << std::endl;
|
||||||
|
}
|
||||||
|
BoxArray objs = detector->forward(cvimg(colorMat));//返回一个包含检测到的目标的对象数组objs
|
||||||
|
|
||||||
|
for (Box &obj : objs) {
|
||||||
|
const char* name = cocoLabels[obj.classLabel];
|
||||||
|
//std::cout << "////////////cocoLabels[obj.classLabel]////////////////////" << name << std::endl;
|
||||||
|
std::string caption = cv::format("%s", name);
|
||||||
|
cv::rectangle(colorMat, cv::Point(obj.left, obj.top), cv::Point(obj.right, obj.bottom),
|
||||||
|
cv::Scalar(0, 255, 0), 1);
|
||||||
|
cv::putText(colorMat, caption, cv::Point(obj.left, obj.bottom-5), 0, 0.7, cv::Scalar(0, 255, 0), 1, 8);
|
||||||
|
}
|
||||||
|
|
||||||
|
return objs;
|
||||||
|
}
|
||||||
|
|
|
@ -0,0 +1,443 @@
|
||||||
|
#include <NvInfer.h>
|
||||||
|
#include <cuda_runtime.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
|
||||||
|
#include <fstream>
|
||||||
|
#include <numeric>
|
||||||
|
#include <sstream>
|
||||||
|
#include <unordered_map>
|
||||||
|
|
||||||
|
#include "infer.hpp"
|
||||||
|
|
||||||
|
namespace trt {
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace nvinfer1;
|
||||||
|
|
||||||
|
#define checkRuntime(call) \
|
||||||
|
do { \
|
||||||
|
auto ___call__ret_code__ = (call); \
|
||||||
|
if (___call__ret_code__ != cudaSuccess) { \
|
||||||
|
INFO("CUDA Runtime error💥 %s # %s, code = %s [ %d ]", #call, \
|
||||||
|
cudaGetErrorString(___call__ret_code__), cudaGetErrorName(___call__ret_code__), \
|
||||||
|
___call__ret_code__); \
|
||||||
|
abort(); \
|
||||||
|
} \
|
||||||
|
} while (0)
|
||||||
|
|
||||||
|
#define checkKernel(...) \
|
||||||
|
do { \
|
||||||
|
{ (__VA_ARGS__); } \
|
||||||
|
checkRuntime(cudaPeekAtLastError()); \
|
||||||
|
} while (0)
|
||||||
|
|
||||||
|
#define Assert(op) \
|
||||||
|
do { \
|
||||||
|
bool cond = !(!(op)); \
|
||||||
|
if (!cond) { \
|
||||||
|
INFO("Assert failed, " #op); \
|
||||||
|
abort(); \
|
||||||
|
} \
|
||||||
|
} while (0)
|
||||||
|
|
||||||
|
#define Assertf(op, ...) \
|
||||||
|
do { \
|
||||||
|
bool cond = !(!(op)); \
|
||||||
|
if (!cond) { \
|
||||||
|
INFO("Assert failed, " #op " : " __VA_ARGS__); \
|
||||||
|
abort(); \
|
||||||
|
} \
|
||||||
|
} while (0)
|
||||||
|
|
||||||
|
static string file_name(const string &path, bool include_suffix) {
|
||||||
|
if (path.empty()) return "";
|
||||||
|
|
||||||
|
int p = path.rfind('/');
|
||||||
|
int e = path.rfind('\\');
|
||||||
|
p = std::max(p, e);
|
||||||
|
p += 1;
|
||||||
|
|
||||||
|
// include suffix
|
||||||
|
if (include_suffix) return path.substr(p);
|
||||||
|
|
||||||
|
int u = path.rfind('.');
|
||||||
|
if (u == -1) return path.substr(p);
|
||||||
|
|
||||||
|
if (u <= p) u = path.size();
|
||||||
|
return path.substr(p, u - p);
|
||||||
|
}
|
||||||
|
|
||||||
|
void __log_func(const char *file, int line, const char *fmt, ...) {
|
||||||
|
va_list vl;
|
||||||
|
va_start(vl, fmt);
|
||||||
|
char buffer[2048];
|
||||||
|
string filename = file_name(file, true);
|
||||||
|
int n = snprintf(buffer, sizeof(buffer), "[%s:%d]: ", filename.c_str(), line);
|
||||||
|
vsnprintf(buffer + n, sizeof(buffer) - n, fmt, vl);
|
||||||
|
fprintf(stdout, "%s\n", buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
static std::string format_shape(const Dims &shape) {
|
||||||
|
stringstream output;
|
||||||
|
char buf[64];
|
||||||
|
const char *fmts[] = {"%d", "x%d"};
|
||||||
|
for (int i = 0; i < shape.nbDims; ++i) {
|
||||||
|
snprintf(buf, sizeof(buf), fmts[i != 0], shape.d[i]);
|
||||||
|
output << buf;
|
||||||
|
}
|
||||||
|
return output.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
Timer::Timer() {
|
||||||
|
checkRuntime(cudaEventCreate((cudaEvent_t *)&start_));
|
||||||
|
checkRuntime(cudaEventCreate((cudaEvent_t *)&stop_));
|
||||||
|
}
|
||||||
|
|
||||||
|
Timer::~Timer() {
|
||||||
|
checkRuntime(cudaEventDestroy((cudaEvent_t)start_));
|
||||||
|
checkRuntime(cudaEventDestroy((cudaEvent_t)stop_));
|
||||||
|
}
|
||||||
|
|
||||||
|
void Timer::start(void *stream) {
|
||||||
|
stream_ = stream;
|
||||||
|
checkRuntime(cudaEventRecord((cudaEvent_t)start_, (cudaStream_t)stream_));
|
||||||
|
}
|
||||||
|
|
||||||
|
float Timer::stop(const char *prefix, bool print) {
|
||||||
|
checkRuntime(cudaEventRecord((cudaEvent_t)stop_, (cudaStream_t)stream_));
|
||||||
|
checkRuntime(cudaEventSynchronize((cudaEvent_t)stop_));
|
||||||
|
|
||||||
|
float latency = 0;
|
||||||
|
checkRuntime(cudaEventElapsedTime(&latency, (cudaEvent_t)start_, (cudaEvent_t)stop_));
|
||||||
|
|
||||||
|
if (print) {
|
||||||
|
printf("[%s]: %.5f ms\n", prefix, latency);
|
||||||
|
}
|
||||||
|
return latency;
|
||||||
|
}
|
||||||
|
|
||||||
|
BaseMemory::BaseMemory(void *cpu, size_t cpu_bytes, void *gpu, size_t gpu_bytes) {
|
||||||
|
reference(cpu, cpu_bytes, gpu, gpu_bytes);
|
||||||
|
}
|
||||||
|
|
||||||
|
void BaseMemory::reference(void *cpu, size_t cpu_bytes, void *gpu, size_t gpu_bytes) {
|
||||||
|
release();
|
||||||
|
|
||||||
|
if (cpu == nullptr || cpu_bytes == 0) {
|
||||||
|
cpu = nullptr;
|
||||||
|
cpu_bytes = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gpu == nullptr || gpu_bytes == 0) {
|
||||||
|
gpu = nullptr;
|
||||||
|
gpu_bytes = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
this->cpu_ = cpu;
|
||||||
|
this->cpu_capacity_ = cpu_bytes;
|
||||||
|
this->cpu_bytes_ = cpu_bytes;
|
||||||
|
this->gpu_ = gpu;
|
||||||
|
this->gpu_capacity_ = gpu_bytes;
|
||||||
|
this->gpu_bytes_ = gpu_bytes;
|
||||||
|
|
||||||
|
this->owner_cpu_ = !(cpu && cpu_bytes > 0);
|
||||||
|
this->owner_gpu_ = !(gpu && gpu_bytes > 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
BaseMemory::~BaseMemory() { release(); }
|
||||||
|
|
||||||
|
void *BaseMemory::gpu_realloc(size_t bytes) {
|
||||||
|
if (gpu_capacity_ < bytes) {
|
||||||
|
release_gpu();
|
||||||
|
|
||||||
|
gpu_capacity_ = bytes;
|
||||||
|
checkRuntime(cudaMalloc(&gpu_, bytes));
|
||||||
|
// checkRuntime(cudaMemset(gpu_, 0, size));
|
||||||
|
}
|
||||||
|
gpu_bytes_ = bytes;
|
||||||
|
return gpu_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void *BaseMemory::cpu_realloc(size_t bytes) {
|
||||||
|
if (cpu_capacity_ < bytes) {
|
||||||
|
release_cpu();
|
||||||
|
|
||||||
|
cpu_capacity_ = bytes;
|
||||||
|
checkRuntime(cudaMallocHost(&cpu_, bytes));
|
||||||
|
Assert(cpu_ != nullptr);
|
||||||
|
// memset(cpu_, 0, size);
|
||||||
|
}
|
||||||
|
cpu_bytes_ = bytes;
|
||||||
|
return cpu_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void BaseMemory::release_cpu() {
|
||||||
|
if (cpu_) {
|
||||||
|
if (owner_cpu_) {
|
||||||
|
checkRuntime(cudaFreeHost(cpu_));
|
||||||
|
}
|
||||||
|
cpu_ = nullptr;
|
||||||
|
}
|
||||||
|
cpu_capacity_ = 0;
|
||||||
|
cpu_bytes_ = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void BaseMemory::release_gpu() {
|
||||||
|
if (gpu_) {
|
||||||
|
if (owner_gpu_) {
|
||||||
|
checkRuntime(cudaFree(gpu_));
|
||||||
|
}
|
||||||
|
gpu_ = nullptr;
|
||||||
|
}
|
||||||
|
gpu_capacity_ = 0;
|
||||||
|
gpu_bytes_ = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void BaseMemory::release() {
|
||||||
|
release_cpu();
|
||||||
|
release_gpu();
|
||||||
|
}
|
||||||
|
|
||||||
|
class __native_nvinfer_logger : public ILogger {
|
||||||
|
public:
|
||||||
|
virtual void log(Severity severity, const char *msg) noexcept override {
|
||||||
|
if (severity == Severity::kINTERNAL_ERROR) {
|
||||||
|
INFO("NVInfer INTERNAL_ERROR: %s", msg);
|
||||||
|
abort();
|
||||||
|
} else if (severity == Severity::kERROR) {
|
||||||
|
INFO("NVInfer: %s", msg);
|
||||||
|
}
|
||||||
|
// else if (severity == Severity::kWARNING) {
|
||||||
|
// INFO("NVInfer: %s", msg);
|
||||||
|
// }
|
||||||
|
// else if (severity == Severity::kINFO) {
|
||||||
|
// INFO("NVInfer: %s", msg);
|
||||||
|
// }
|
||||||
|
// else {
|
||||||
|
// INFO("%s", msg);
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
};
|
||||||
|
static __native_nvinfer_logger gLogger;
|
||||||
|
|
||||||
|
template <typename _T>
|
||||||
|
static void destroy_nvidia_pointer(_T *ptr) {
|
||||||
|
if (ptr) ptr->destroy();
|
||||||
|
}
|
||||||
|
|
||||||
|
static std::vector<uint8_t> load_file(const string &file) {
|
||||||
|
ifstream in(file, ios::in | ios::binary);
|
||||||
|
if (!in.is_open()) return {};
|
||||||
|
|
||||||
|
in.seekg(0, ios::end);
|
||||||
|
size_t length = in.tellg();
|
||||||
|
|
||||||
|
std::vector<uint8_t> data;
|
||||||
|
if (length > 0) {
|
||||||
|
in.seekg(0, ios::beg);
|
||||||
|
data.resize(length);
|
||||||
|
|
||||||
|
in.read((char *)&data[0], length);
|
||||||
|
}
|
||||||
|
in.close();
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
class __native_engine_context {
|
||||||
|
public:
|
||||||
|
virtual ~__native_engine_context() { destroy(); }
|
||||||
|
|
||||||
|
bool construct(const void *pdata, size_t size) {
|
||||||
|
destroy();
|
||||||
|
|
||||||
|
if (pdata == nullptr || size == 0) return false;
|
||||||
|
|
||||||
|
runtime_ = shared_ptr<IRuntime>(createInferRuntime(gLogger), destroy_nvidia_pointer<IRuntime>);
|
||||||
|
if (runtime_ == nullptr) return false;
|
||||||
|
|
||||||
|
engine_ = shared_ptr<ICudaEngine>(runtime_->deserializeCudaEngine(pdata, size, nullptr),
|
||||||
|
destroy_nvidia_pointer<ICudaEngine>);
|
||||||
|
if (engine_ == nullptr) return false;
|
||||||
|
|
||||||
|
context_ = shared_ptr<IExecutionContext>(engine_->createExecutionContext(),
|
||||||
|
destroy_nvidia_pointer<IExecutionContext>);
|
||||||
|
return context_ != nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
void destroy() {
|
||||||
|
context_.reset();
|
||||||
|
engine_.reset();
|
||||||
|
runtime_.reset();
|
||||||
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
shared_ptr<IExecutionContext> context_;
|
||||||
|
shared_ptr<ICudaEngine> engine_;
|
||||||
|
shared_ptr<IRuntime> runtime_ = nullptr;
|
||||||
|
};
|
||||||
|
|
||||||
|
class InferImpl : public Infer {
|
||||||
|
public:
|
||||||
|
shared_ptr<__native_engine_context> context_;
|
||||||
|
unordered_map<string, int> binding_name_to_index_;
|
||||||
|
|
||||||
|
virtual ~InferImpl() = default;
|
||||||
|
|
||||||
|
bool construct(const void *data, size_t size) {
|
||||||
|
context_ = make_shared<__native_engine_context>();
|
||||||
|
if (!context_->construct(data, size)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
setup();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool load(const string &file) {
|
||||||
|
auto data = load_file(file);
|
||||||
|
if (data.empty()) {
|
||||||
|
INFO("An empty file has been loaded. Please confirm your file path: %s", file.c_str());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return this->construct(data.data(), data.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
auto engine = this->context_->engine_;
|
||||||
|
int nbBindings = engine->getNbBindings();
|
||||||
|
|
||||||
|
binding_name_to_index_.clear();
|
||||||
|
for (int i = 0; i < nbBindings; ++i) {
|
||||||
|
const char *bindingName = engine->getBindingName(i);
|
||||||
|
binding_name_to_index_[bindingName] = i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual int index(const std::string &name) override {
|
||||||
|
auto iter = binding_name_to_index_.find(name);
|
||||||
|
Assertf(iter != binding_name_to_index_.end(), "Can not found the binding name: %s",
|
||||||
|
name.c_str());
|
||||||
|
return iter->second;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool forward(const std::vector<void *> &bindings, void *stream,
|
||||||
|
void *input_consum_event) override {
|
||||||
|
return this->context_->context_->enqueueV2((void**)bindings.data(), (cudaStream_t)stream,
|
||||||
|
(cudaEvent_t *)input_consum_event);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual std::vector<int> run_dims(const std::string &name) override {
|
||||||
|
return run_dims(index(name));
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual std::vector<int> run_dims(int ibinding) override {
|
||||||
|
auto dim = this->context_->context_->getBindingDimensions(ibinding);
|
||||||
|
return std::vector<int>(dim.d, dim.d + dim.nbDims);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual std::vector<int> static_dims(const std::string &name) override {
|
||||||
|
return static_dims(index(name));
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual std::vector<int> static_dims(int ibinding) override {
|
||||||
|
auto dim = this->context_->engine_->getBindingDimensions(ibinding);
|
||||||
|
return std::vector<int>(dim.d, dim.d + dim.nbDims);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual int num_bindings() override { return this->context_->engine_->getNbBindings(); }
|
||||||
|
|
||||||
|
virtual bool is_input(int ibinding) override {
|
||||||
|
return this->context_->engine_->bindingIsInput(ibinding);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool set_run_dims(const std::string &name, const std::vector<int> &dims) override {
|
||||||
|
return this->set_run_dims(index(name), dims);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool set_run_dims(int ibinding, const std::vector<int> &dims) override {
|
||||||
|
Dims d;
|
||||||
|
memcpy(d.d, dims.data(), sizeof(int) * dims.size());
|
||||||
|
d.nbDims = dims.size();
|
||||||
|
return this->context_->context_->setBindingDimensions(ibinding, d);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual int numel(const std::string &name) override { return numel(index(name)); }
|
||||||
|
|
||||||
|
virtual int numel(int ibinding) override {
|
||||||
|
auto dim = this->context_->context_->getBindingDimensions(ibinding);
|
||||||
|
return std::accumulate(dim.d, dim.d + dim.nbDims, 1, std::multiplies<int>());
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual DType dtype(const std::string &name) override { return dtype(index(name)); }
|
||||||
|
|
||||||
|
virtual DType dtype(int ibinding) override {
|
||||||
|
return (DType)this->context_->engine_->getBindingDataType(ibinding);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool has_dynamic_dim() override {
|
||||||
|
// check if any input or output bindings have dynamic shapes
|
||||||
|
// code from ChatGPT
|
||||||
|
int numBindings = this->context_->engine_->getNbBindings();
|
||||||
|
for (int i = 0; i < numBindings; ++i) {
|
||||||
|
nvinfer1::Dims dims = this->context_->engine_->getBindingDimensions(i);
|
||||||
|
for (int j = 0; j < dims.nbDims; ++j) {
|
||||||
|
if (dims.d[j] == -1) return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void print() override {
|
||||||
|
INFO("Infer %p [%s]", this, has_dynamic_dim() ? "DynamicShape" : "StaticShape");
|
||||||
|
|
||||||
|
int num_input = 0;
|
||||||
|
int num_output = 0;
|
||||||
|
auto engine = this->context_->engine_;
|
||||||
|
for (int i = 0; i < engine->getNbBindings(); ++i) {
|
||||||
|
if (engine->bindingIsInput(i))
|
||||||
|
num_input++;
|
||||||
|
else
|
||||||
|
num_output++;
|
||||||
|
}
|
||||||
|
|
||||||
|
INFO("Inputs: %d", num_input);
|
||||||
|
for (int i = 0; i < num_input; ++i) {
|
||||||
|
auto name = engine->getBindingName(i);
|
||||||
|
auto dim = engine->getBindingDimensions(i);
|
||||||
|
INFO("\t%d.%s : shape {%s}", i, name, format_shape(dim).c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
INFO("Outputs: %d", num_output);
|
||||||
|
for (int i = 0; i < num_output; ++i) {
|
||||||
|
auto name = engine->getBindingName(i + num_input);
|
||||||
|
auto dim = engine->getBindingDimensions(i + num_input);
|
||||||
|
INFO("\t%d.%s : shape {%s}", i, name, format_shape(dim).c_str());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
Infer *loadraw(const std::string &file) {
|
||||||
|
InferImpl *impl = new InferImpl();
|
||||||
|
if (!impl->load(file)) {
|
||||||
|
delete impl;
|
||||||
|
impl = nullptr;
|
||||||
|
}
|
||||||
|
return impl;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_ptr<Infer> load(const std::string &file) {
|
||||||
|
return std::shared_ptr<InferImpl>((InferImpl *)loadraw(file));
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string format_shape(const std::vector<int> &shape) {
|
||||||
|
stringstream output;
|
||||||
|
char buf[64];
|
||||||
|
const char *fmts[] = {"%d", "x%d"};
|
||||||
|
for (int i = 0; i < (int)shape.size(); ++i) {
|
||||||
|
snprintf(buf, sizeof(buf), fmts[i != 0], shape[i]);
|
||||||
|
output << buf;
|
||||||
|
}
|
||||||
|
return output.str();
|
||||||
|
}
|
||||||
|
}; // namespace trt
|
|
@ -0,0 +1,955 @@
|
||||||
|
///摄像头
|
||||||
|
#include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
|
||||||
|
#include <librealsense2/hpp/rs_processing.hpp>
|
||||||
|
#include "example.hpp"
|
||||||
|
|
||||||
|
#include <opencv2/opencv.hpp>
|
||||||
|
#include <iostream>
|
||||||
|
#include <vector>
|
||||||
|
#include <set>
|
||||||
|
#include <string>
|
||||||
|
#include <mutex>
|
||||||
|
#include <sstream>
|
||||||
|
|
||||||
|
#include <fstream>
|
||||||
|
#include <algorithm>
|
||||||
|
#include <cstring>
|
||||||
|
|
||||||
|
// opencv 用于图像数据读取与处理
|
||||||
|
#include <opencv2/core/core.hpp>
|
||||||
|
#include <opencv2/imgproc/imgproc.hpp>
|
||||||
|
#include <opencv2/highgui/highgui.hpp>
|
||||||
|
// #include <opencv2/core/eigen.hpp>
|
||||||
|
|
||||||
|
// 使用Eigen的Geometry模块处理3d运动
|
||||||
|
#include <Eigen/Core>
|
||||||
|
#include <Eigen/Geometry>
|
||||||
|
#include <Eigen/Dense>
|
||||||
|
|
||||||
|
#include <opencv2/core/eigen.hpp>
|
||||||
|
/*........................................................................*/
|
||||||
|
|
||||||
|
#include<librealsense2/rsutil.h>
|
||||||
|
///摄像头
|
||||||
|
#include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
|
||||||
|
#include <librealsense2/hpp/rs_processing.hpp>
|
||||||
|
#include "../include/example.hpp"
|
||||||
|
#include <opencv2/opencv.hpp>
|
||||||
|
|
||||||
|
/*........................................................................*/
|
||||||
|
// pcl
|
||||||
|
#include <pcl/common/transforms.h>
|
||||||
|
#include <pcl/point_types.h>
|
||||||
|
#include <pcl/io/pcd_io.h>
|
||||||
|
#include <pcl/filters/conditional_removal.h> //条件滤波器头文件
|
||||||
|
#include <pcl/filters/passthrough.h> //直通滤波器头文件
|
||||||
|
#include <pcl/filters/radius_outlier_removal.h> //半径滤波器头文件
|
||||||
|
#include <pcl/filters/statistical_outlier_removal.h> //统计滤波器头文件
|
||||||
|
#include <pcl/filters/voxel_grid.h> //体素滤波器头文件
|
||||||
|
#include <pcl/segmentation/extract_clusters.h>
|
||||||
|
#include <pcl/point_cloud.h>
|
||||||
|
#include <pcl/kdtree/kdtree_flann.h>
|
||||||
|
|
||||||
|
#include <pcl/PointIndices.h>
|
||||||
|
|
||||||
|
// boost.format 字符串处理
|
||||||
|
//#include <boost/format.hpp>
|
||||||
|
|
||||||
|
#include "Yolo.hpp"
|
||||||
|
#include "DepthProcessor.hpp"
|
||||||
|
#include "IMUProcessor.hpp"
|
||||||
|
|
||||||
|
|
||||||
|
// 语音
|
||||||
|
#include <string.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include "serialport.h"
|
||||||
|
#include<map>
|
||||||
|
#include<chrono>
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
// 超声波
|
||||||
|
#include "../include/dyp-a05/sonar_driver.h"
|
||||||
|
#include <bitset>
|
||||||
|
#include <thread>
|
||||||
|
#include <condition_variable>
|
||||||
|
#include<functional>
|
||||||
|
// 蜂鸣器
|
||||||
|
#include <JetsonGPIO.h>
|
||||||
|
#include <signal.h>
|
||||||
|
/* Private variables ---------------------------------------------------------*/
|
||||||
|
static int addr = 0;
|
||||||
|
static int error = 0;
|
||||||
|
static int fdcom = 0;
|
||||||
|
static PortInfo_t portinfo = {9600, 8, 0, 0, 1, 0};
|
||||||
|
|
||||||
|
/*
|
||||||
|
=========================================
|
||||||
|
| header | id | 指令 | 校验和 |
|
||||||
|
-----------------------------------------
|
||||||
|
| 0x55 0xaa | 0x01 | 0x01 | 0x01 |
|
||||||
|
=========================================
|
||||||
|
*/
|
||||||
|
static unsigned char tx_buffer[TX_BUFFER_MAX] = {0x55, 0xaa, 0x01, 0x01, 0x01};
|
||||||
|
|
||||||
|
/*
|
||||||
|
=========================================
|
||||||
|
| 帧头 | 地址 | 指令 | 校验和 |
|
||||||
|
-----------------------------------------
|
||||||
|
| 0x55 0xaa | 0x01 | 0x01 | 0x01 |
|
||||||
|
=========================================
|
||||||
|
*/
|
||||||
|
static unsigned char rx_buffer[RX_BUFFER_MAX];
|
||||||
|
|
||||||
|
static double Distance[4] = {0, 0, 0, 0};
|
||||||
|
std::string port = "/dev/ultrasound";
|
||||||
|
|
||||||
|
/*初始化参数定义*/
|
||||||
|
int ini = 0;
|
||||||
|
int initial_times = 10;
|
||||||
|
bool initial = false;
|
||||||
|
double max_wrong =2.5;
|
||||||
|
double min_wrong =0.25;
|
||||||
|
double dis0[10];
|
||||||
|
double dis1[10];
|
||||||
|
|
||||||
|
bool end_this_program = false;
|
||||||
|
// 差值
|
||||||
|
double dis0_d = 0.0;
|
||||||
|
double dis1_d = 0.0;
|
||||||
|
// 差值阈值
|
||||||
|
double Thr = 0.5;
|
||||||
|
|
||||||
|
// 播报选择
|
||||||
|
static int voice_status = 0;
|
||||||
|
std::mutex mtx;
|
||||||
|
bool ToPlay = false;
|
||||||
|
int distt;
|
||||||
|
bool isObjectt;
|
||||||
|
// declare
|
||||||
|
void play_voice(string);
|
||||||
|
|
||||||
|
// 检查校验和
|
||||||
|
int data_check(unsigned char buf[RX_BUFFER_MAX], int datalen)
|
||||||
|
{
|
||||||
|
int checksum = 0;
|
||||||
|
|
||||||
|
if((buf[0]==0xFF) && datalen == 10)
|
||||||
|
{
|
||||||
|
for(int i=0; i<RX_BUFFER_MAX-1; i++)
|
||||||
|
{
|
||||||
|
checksum += buf[i];
|
||||||
|
}
|
||||||
|
if((checksum&0x00ff)== buf[RX_BUFFER_MAX-1])
|
||||||
|
{
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
printf("first : %x,校验和不对, 数据长度datalen: %d\n", buf[0],datalen);
|
||||||
|
error = 2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 超声波高低八位合并
|
||||||
|
unsigned int data_merge(unsigned short dt_h, unsigned short dt_l)
|
||||||
|
{
|
||||||
|
unsigned int tmp;
|
||||||
|
tmp = dt_h;
|
||||||
|
tmp <<= 8;
|
||||||
|
tmp |= dt_l;
|
||||||
|
return tmp;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 物体转16进制
|
||||||
|
map<string, char> Objects = {
|
||||||
|
{"person", 0x51},
|
||||||
|
{"bicycle", 0x52},
|
||||||
|
{"motorcycle", 0x53},
|
||||||
|
{"bus", 0x54},
|
||||||
|
{"cat", 0x55},
|
||||||
|
{"dog", 0x56},
|
||||||
|
{"fire hydrant", 0x57},
|
||||||
|
{"bottle", 0x58},
|
||||||
|
{"cup", 0x59},
|
||||||
|
{"chair", 0x5a},
|
||||||
|
{"couch", 0x5b},
|
||||||
|
{"potted plant", 0x5c},
|
||||||
|
{"bed", 0x5d},
|
||||||
|
{"dining table", 0x5e},
|
||||||
|
{"toilet", 0x5f},
|
||||||
|
{"tv", 0x60},
|
||||||
|
{"refrigerator", 0x61},
|
||||||
|
|
||||||
|
{"object", 0x6e},
|
||||||
|
// 待增物体todo
|
||||||
|
};
|
||||||
|
|
||||||
|
// 播报函数
|
||||||
|
// 10->16进制,conver使用
|
||||||
|
char tenTo16(int i){
|
||||||
|
char output = 'a' ;
|
||||||
|
switch(i){
|
||||||
|
case 1: output = 0x01; break;
|
||||||
|
case 2: output = 0x02; break;
|
||||||
|
case 3: output = 0x03; break;
|
||||||
|
case 4: output = 0x04; break;
|
||||||
|
case 5: output = 0x05; break;
|
||||||
|
case 6: output = 0x06; break;
|
||||||
|
case 7: output = 0x07; break;
|
||||||
|
case 8: output = 0x08; break;
|
||||||
|
case 9: output = 0x09; break;
|
||||||
|
case 0: output = 0x0e; break;
|
||||||
|
}
|
||||||
|
return output;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 待传输数组,结合距离和物体,未用
|
||||||
|
void conver(char out[], double dis, string obj){
|
||||||
|
// todo 四舍五入一下 0.29->0.3
|
||||||
|
int ge = -1,shi=-1,bai=-1,qian=-1, dian= -1, dian2 = -1;;
|
||||||
|
//char out[] = {0x8b};
|
||||||
|
//auto *beg = begin(out);
|
||||||
|
int p = 0;
|
||||||
|
//printf("qian: %d,bai:%d,shi:%d,ge:%d,dian:%d\n",qian,bai,shi,ge,dian);
|
||||||
|
//将距离转为十六进制
|
||||||
|
if(dis >= 1000){
|
||||||
|
qian = (int)dis/1000;
|
||||||
|
bai = (int)dis/100%10;
|
||||||
|
shi = (int)dis/10%10;
|
||||||
|
ge = (int)dis%10;
|
||||||
|
}else if(dis >= 100){
|
||||||
|
bai = (int)dis/100;
|
||||||
|
shi = (int)dis/10%10;
|
||||||
|
ge = (int)dis%10;
|
||||||
|
}else if(dis >= 10){
|
||||||
|
shi = (int)dis/10;
|
||||||
|
ge = (int)dis%10;
|
||||||
|
}else if(dis >=1){
|
||||||
|
ge = (int)dis%10;
|
||||||
|
}else{
|
||||||
|
ge = 0;
|
||||||
|
}
|
||||||
|
dian = (int)(dis*10)%10;
|
||||||
|
dian2 = (int)(dis*100)%10;
|
||||||
|
//printf("qian: %d,bai:%d,shi:%d,ge:%d,dian:%d\n",qian,bai,shi,ge,dian);
|
||||||
|
if(qian != -1){
|
||||||
|
out[p++] = tenTo16(qian);
|
||||||
|
out[p++] = 0x0c;
|
||||||
|
out[p++] = tenTo16(bai);
|
||||||
|
out[p++] = 0x0b;
|
||||||
|
out[p++] = tenTo16(shi);
|
||||||
|
out[p++] = 0x0a;
|
||||||
|
}else if(bai != -1){
|
||||||
|
out[p++] = tenTo16(bai);
|
||||||
|
out[p++] = 0x0b;
|
||||||
|
out[p++] = tenTo16(shi);
|
||||||
|
out[p++] = 0x0a;
|
||||||
|
}else if(shi != -1){
|
||||||
|
out[p++] = tenTo16(shi);
|
||||||
|
out[p++] = 0x0a;
|
||||||
|
}
|
||||||
|
// 个位数
|
||||||
|
out[p++] = tenTo16(ge);
|
||||||
|
// 点数
|
||||||
|
out[p++] = 0x0d;
|
||||||
|
// 小数点后一位
|
||||||
|
out[p++] = tenTo16(dian);
|
||||||
|
// 小数点后两位
|
||||||
|
out[p++] = tenTo16(dian2);
|
||||||
|
|
||||||
|
//printf("p:%d, out[0]:%x\n",p,out[1]);
|
||||||
|
//将string转换成对应的十六进制
|
||||||
|
auto iter = Objects.find(obj);
|
||||||
|
if(iter != Objects.end()){
|
||||||
|
out[p++] = iter->second;
|
||||||
|
}
|
||||||
|
|
||||||
|
//return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 串口发送起始120,十六进制78
|
||||||
|
bool serial_com(char n16){
|
||||||
|
SerialPort serialport;
|
||||||
|
SerialPort::Port_INFO *pPort;
|
||||||
|
// Init SerialPort
|
||||||
|
int COM_id = 0;
|
||||||
|
pPort = (SerialPort::Port_INFO *)malloc(sizeof(SerialPort::Port_INFO));
|
||||||
|
if(pPort == NULL) {
|
||||||
|
fprintf(stderr, "Error malloc... [FAIL]\n");
|
||||||
|
}
|
||||||
|
memset(pPort, 0, sizeof(SerialPort::Port_INFO));
|
||||||
|
int result = serialport.InitPort(pPort, COM_id);
|
||||||
|
if(result < 0) {
|
||||||
|
fprintf(stderr, "Error Running SerialPort... [FAIL]\n");
|
||||||
|
}
|
||||||
|
// fprintf(stdout, "SerialPort [%s] running... [OK]\n", pPort->name);
|
||||||
|
|
||||||
|
int send_size = 15;
|
||||||
|
char serial_sendmsg[send_size] = {n16};
|
||||||
|
|
||||||
|
int msg_len = strlen(serial_sendmsg);
|
||||||
|
int send_nbyte = serialport.sendnPort(pPort,const_cast<char*>(serial_sendmsg),msg_len);
|
||||||
|
if (send_nbyte > 0) {
|
||||||
|
// 收到数据
|
||||||
|
printf("Send: [%d] ... [OK]\n", send_nbyte);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 串口发送接口函数-发送单个物体
|
||||||
|
bool serial_com(string object){
|
||||||
|
SerialPort serialport;
|
||||||
|
SerialPort::Port_INFO *pPort;
|
||||||
|
// Init SerialPort
|
||||||
|
int COM_id = 0;
|
||||||
|
pPort = (SerialPort::Port_INFO *)malloc(sizeof(SerialPort::Port_INFO));
|
||||||
|
if(pPort == NULL) {
|
||||||
|
fprintf(stderr, "Error malloc... [FAIL]\n");
|
||||||
|
}
|
||||||
|
memset(pPort, 0, sizeof(SerialPort::Port_INFO));
|
||||||
|
int result = serialport.InitPort(pPort, COM_id);
|
||||||
|
if(result < 0) {
|
||||||
|
fprintf(stderr, "Error Running SerialPort... [FAIL]\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
// COM Send
|
||||||
|
// 设置参数
|
||||||
|
// 物体
|
||||||
|
//string object= "bed";
|
||||||
|
// 距离
|
||||||
|
//double Distance= 5.5;
|
||||||
|
|
||||||
|
int send_size = 15;
|
||||||
|
char serial_sendmsg[send_size] = {};
|
||||||
|
|
||||||
|
auto iter = Objects.find(object);
|
||||||
|
if(iter != Objects.end()){
|
||||||
|
serial_sendmsg[0] = iter->second;
|
||||||
|
}
|
||||||
|
// conver(serial_sendmsg, Distance, object);
|
||||||
|
|
||||||
|
int msg_len = strlen(serial_sendmsg);
|
||||||
|
int send_nbyte = serialport.sendnPort(pPort,const_cast<char*>(serial_sendmsg),msg_len);
|
||||||
|
if (send_nbyte > 0) {
|
||||||
|
// todo...
|
||||||
|
fprintf(stdout, "Send: [%d] %s... [OK]\n", send_nbyte, serial_sendmsg);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// 串口发送接口函数-发送多个物体类别
|
||||||
|
bool serial_com(set<string> objects){
|
||||||
|
SerialPort serialport;
|
||||||
|
SerialPort::Port_INFO *pPort;
|
||||||
|
/* Init SerialPort */
|
||||||
|
int COM_id = 0;
|
||||||
|
pPort = (SerialPort::Port_INFO *)malloc(sizeof(SerialPort::Port_INFO));
|
||||||
|
if(pPort == NULL) {
|
||||||
|
fprintf(stderr, "Error malloc... [FAIL]\n");
|
||||||
|
}
|
||||||
|
memset(pPort, 0, sizeof(SerialPort::Port_INFO));
|
||||||
|
int result = serialport.InitPort(pPort, COM_id);
|
||||||
|
if(result < 0) {
|
||||||
|
fprintf(stderr, "Error Running SerialPort... [FAIL]\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
int send_size = 50;
|
||||||
|
char serial_sendmsg[send_size] = {0x02};
|
||||||
|
// conver(serial_sendmsg, distance, object);
|
||||||
|
int p=0;
|
||||||
|
for(auto e: objects){
|
||||||
|
// Objects
|
||||||
|
auto iter = Objects.find(e);
|
||||||
|
if(iter != Objects.end()){
|
||||||
|
// 找到
|
||||||
|
serial_sendmsg[p++] = iter->second;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int msg_len = strlen(serial_sendmsg);
|
||||||
|
int send_nbyte = serialport.sendnPort(pPort,const_cast<char*>(serial_sendmsg),msg_len);
|
||||||
|
if (send_nbyte > 0) {
|
||||||
|
// todo...
|
||||||
|
fprintf(stdout, "Send: [%d] %s... [OK]\n", send_nbyte, serial_sendmsg);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// 串口接收函数
|
||||||
|
void serial_receive(char response_buf[]){
|
||||||
|
SerialPort serialport;
|
||||||
|
SerialPort::Port_INFO *pPort;
|
||||||
|
// Init SerialPort
|
||||||
|
int COM_id = 0;
|
||||||
|
pPort = (SerialPort::Port_INFO *)malloc(sizeof(SerialPort::Port_INFO));
|
||||||
|
if(pPort == NULL) {
|
||||||
|
fprintf(stderr, "Error malloc... [FAIL]\n");
|
||||||
|
}
|
||||||
|
memset(pPort, 0, sizeof(SerialPort::Port_INFO));
|
||||||
|
int result = serialport.InitPort(pPort, COM_id);
|
||||||
|
if(result < 0) {
|
||||||
|
fprintf(stderr, "Error Running SerialPort... [FAIL]\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
// COM Receive
|
||||||
|
int receive_nbyte = 0;
|
||||||
|
int size = COM_BUFFER_SIZE;
|
||||||
|
// char response_buf[COM_BUFFER_SIZE] = {'\0'};
|
||||||
|
while (1) {
|
||||||
|
// 收取一次
|
||||||
|
receive_nbyte = serialport.signal_recvnPort(pPort, response_buf, size);
|
||||||
|
if(receive_nbyte > 0) {
|
||||||
|
for(int i = 0; i < receive_nbyte; i++) {
|
||||||
|
response_buf[i] = response_buf[i];
|
||||||
|
}
|
||||||
|
response_buf[receive_nbyte] = '\0';
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// if (receive_nbyte == 0) break;
|
||||||
|
}
|
||||||
|
// fprintf(stdout, "Receive: [%d] %s... [OK]\n", receive_nbyte, response_buf);
|
||||||
|
}
|
||||||
|
|
||||||
|
// 为了剔除类别中不属于检测出的类别
|
||||||
|
std::vector<std::string> currentLabel= {
|
||||||
|
"person", "bicycle", "motorcycle", "bus", "cat", "dog", "fire hydrant",
|
||||||
|
"bottle", "cup", "chair", "couch", "potted plant", "bed",
|
||||||
|
"dining table", "toilet", "tv", "refrigerator",
|
||||||
|
};
|
||||||
|
|
||||||
|
// 检查label是否在currentLabel中
|
||||||
|
bool labelCheck(std::string label){
|
||||||
|
// 使用 std::find() 在 vector 中查找目标字符串
|
||||||
|
auto it = std::find(currentLabel.begin(), currentLabel.end(), label);
|
||||||
|
|
||||||
|
if(it != currentLabel.end()) {
|
||||||
|
return 1;
|
||||||
|
}else{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 超声波检测线程函数
|
||||||
|
void ultrasound_play(){
|
||||||
|
fdcom = uart_init(port.c_str());
|
||||||
|
std::cout << fdcom << std::endl;
|
||||||
|
if(fdcom > 0)
|
||||||
|
{
|
||||||
|
uart_set(fdcom, &portinfo);
|
||||||
|
printf("[板卡%d通信参数]: %d, 8, 0, 0, 1, 0.\n",addr,9600);
|
||||||
|
}
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
if(error)
|
||||||
|
{
|
||||||
|
Distance[0] = 0;
|
||||||
|
Distance[1] = 0;
|
||||||
|
Distance[2] = 0;
|
||||||
|
Distance[3] = 0;
|
||||||
|
// std::cout<< "串口打开错误!"<<std::endl;
|
||||||
|
uart_deinit(fdcom);
|
||||||
|
fdcom = 0;
|
||||||
|
// 尝试恢复
|
||||||
|
while(fdcom <= 0 ){
|
||||||
|
fdcom = uart_init(port.c_str());
|
||||||
|
printf("超声波串口打开错误,正在恢复..........\n");
|
||||||
|
}
|
||||||
|
error = 0;
|
||||||
|
if(fdcom > 0)
|
||||||
|
{
|
||||||
|
uart_set(fdcom, &portinfo);
|
||||||
|
printf("fdcom:%d重启成功!!!!!!!!!!\n", fdcom);
|
||||||
|
}
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
uart_txd(fdcom, tx_buffer, TX_BUFFER_MAX);
|
||||||
|
// 接收数据
|
||||||
|
int datalen = uart_rxd(fdcom, rx_buffer, RX_BUFFER_MAX, portinfo.baudrate);
|
||||||
|
if(data_check(rx_buffer, datalen))
|
||||||
|
{
|
||||||
|
Distance[0] = double(data_merge(rx_buffer[1], rx_buffer[2]))/1000;// 前一个为high,后一个为low
|
||||||
|
Distance[1] = double(data_merge(rx_buffer[3], rx_buffer[4]))/1000;
|
||||||
|
Distance[2] = double(data_merge(rx_buffer[5], rx_buffer[6]))/1000;
|
||||||
|
Distance[3] = double(data_merge(rx_buffer[7], rx_buffer[8]))/1000;
|
||||||
|
// std::cout<<"Distance[0]:"<<Distance[0]<<"米 "<<"Distance[1]:"<<Distance[1]<<"米 "<<"Distance[2]:"<<Distance[2]<<"米 "<<"Distance[3]:"<<Distance[3]<<"米 "<<std::endl;
|
||||||
|
|
||||||
|
if(((Distance[0] <= Thr)&&(Distance[0]>min_wrong)) || ((Distance[1] <= Thr)&&(Distance[1]>min_wrong))){
|
||||||
|
// 定义全局变量
|
||||||
|
{
|
||||||
|
std::cout<<"Distance[0]:"<<Distance[0]<<"米 "<<"Distance[1]:"<<Distance[1]<<"米 "<<"Distance[2]:"<<Distance[2]<<"米 "<<"Distance[3]:"<<Distance[3]<<"米 "<<std::endl;
|
||||||
|
ToPlay = true;
|
||||||
|
voice_status = 3;
|
||||||
|
}
|
||||||
|
continue;
|
||||||
|
|
||||||
|
}
|
||||||
|
else ToPlay = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
uart_deinit(fdcom);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// 要播报的物体类别
|
||||||
|
// 播报前赋值,播报完清空
|
||||||
|
set<string> classes = {};
|
||||||
|
|
||||||
|
// 播报全部类别, 新开一个线程等待串口的指令
|
||||||
|
void play_all_class(){
|
||||||
|
// 接收到202就发送全部物体类别
|
||||||
|
char resp[COM_BUFFER_SIZE];
|
||||||
|
std::string resp_s;
|
||||||
|
while(1){
|
||||||
|
usleep(200000);
|
||||||
|
serial_receive(resp);
|
||||||
|
resp_s = resp;
|
||||||
|
|
||||||
|
if(resp_s == "202"){
|
||||||
|
if(classes.empty()){
|
||||||
|
// std::cout<< "wbw111"<< std::endl;
|
||||||
|
if(!serial_com(0x73)){
|
||||||
|
std::cout<< "115发送失败,没有物体不播报"<< std::endl;
|
||||||
|
}
|
||||||
|
}else{
|
||||||
|
voice_status = 4;
|
||||||
|
// 任意传入,不会播报传入的物体
|
||||||
|
play_voice("cup");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 语音播报 play_voice(label)
|
||||||
|
void play_voice(string object){
|
||||||
|
// 上锁
|
||||||
|
std::lock_guard<std::mutex> lock(mtx);
|
||||||
|
// 发送开始的200
|
||||||
|
if(!serial_com(0x78)){
|
||||||
|
std::cout<< "200发送失败,此次不播报"<< std::endl;
|
||||||
|
}
|
||||||
|
switch(voice_status){
|
||||||
|
case 1: {
|
||||||
|
// 发送距离和障碍物
|
||||||
|
if(serial_com(object)){
|
||||||
|
std::cout << "finish_object_label" << std::endl;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 2:{
|
||||||
|
// 发送距离
|
||||||
|
if(serial_com("object")){
|
||||||
|
std::cout << "finish_object" << std::endl;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 3:{
|
||||||
|
// 超声波检测,传入无用的一个字符,语音不做处理
|
||||||
|
if(serial_com(0x0f)){
|
||||||
|
std::cout << "finish_ultrasound" << std::endl;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 4:{
|
||||||
|
// 全部类别播报
|
||||||
|
if(serial_com(classes)){
|
||||||
|
std::cout<< classes.size() << std::endl;
|
||||||
|
std::cout << "finish_all_classes" << std::endl;
|
||||||
|
classes.clear();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 0:{
|
||||||
|
std::cout << "仍在初始化阶段" << std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 蜂鸣器播报
|
||||||
|
void signalHandler(int s) { end_this_program = true; }
|
||||||
|
|
||||||
|
void Bee()// 启动
|
||||||
|
{
|
||||||
|
int output_pin = 13;
|
||||||
|
GPIO::setmode(GPIO::BCM);
|
||||||
|
//signal(SIGINT, signalHandler);
|
||||||
|
GPIO::setup(output_pin, GPIO::OUT, GPIO::LOW);
|
||||||
|
std::cout << "Bee" << std::endl;
|
||||||
|
while(!end_this_program){
|
||||||
|
if(ToPlay || (isObjectt && distt <= 0.5))
|
||||||
|
{
|
||||||
|
// set pin as an output pin with optional initial state of HIGH
|
||||||
|
GPIO::output(output_pin, GPIO::HIGH);
|
||||||
|
usleep(100000);// 300000
|
||||||
|
GPIO::output(output_pin, GPIO::LOW);
|
||||||
|
usleep(100000);
|
||||||
|
}else if(isObjectt && distt > 0.5){
|
||||||
|
GPIO::output(output_pin, GPIO::HIGH);
|
||||||
|
usleep(100000);// 300000
|
||||||
|
GPIO::output(output_pin, GPIO::LOW);
|
||||||
|
usleep(300000);
|
||||||
|
}
|
||||||
|
else GPIO::output(output_pin, GPIO::LOW);
|
||||||
|
}
|
||||||
|
GPIO::cleanup();
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(){
|
||||||
|
rs2::log_to_console(RS2_LOG_SEVERITY_ERROR);
|
||||||
|
// 声明 RealSense 管道,封装实际设备和传感器
|
||||||
|
rs2::pipeline cameraPipe, imuPipe;
|
||||||
|
// 使用推荐的默认配置开始流式传输
|
||||||
|
// 默认视频配置包含深度流和色彩流
|
||||||
|
// 如果设备能够流式传输 IMU 数据,则默认启用陀螺仪和加速计
|
||||||
|
rs2::config cameraCfg, imuCfg;
|
||||||
|
// IMU数据流设置帧率会报错,或是帧率设置过大?
|
||||||
|
imuCfg.enable_stream(rs2_stream::RS2_STREAM_ACCEL, rs2_format::RS2_FORMAT_MOTION_XYZ32F);
|
||||||
|
imuCfg.enable_stream(rs2_stream::RS2_STREAM_GYRO, rs2_format::RS2_FORMAT_MOTION_XYZ32F);
|
||||||
|
// Declare object that handles camera pose calculations
|
||||||
|
IMUProcessor imuProcessor;
|
||||||
|
rs2::pipeline_profile imuProfile = imuPipe.start(imuCfg, [&](rs2::frame frame)
|
||||||
|
{
|
||||||
|
// Cast the frame that arrived to motion frame
|
||||||
|
auto motion = frame.as<rs2::motion_frame>();
|
||||||
|
// If casting succeeded and the arrived frame is from gyro stream
|
||||||
|
if (motion && motion.get_profile().stream_type() == RS2_STREAM_GYRO && motion.get_profile().format() == RS2_FORMAT_MOTION_XYZ32F)
|
||||||
|
{
|
||||||
|
// Get the timestamp of the current frame
|
||||||
|
double ts = motion.get_timestamp();
|
||||||
|
// Get gyro measures
|
||||||
|
rs2_vector gyroData = motion.get_motion_data();
|
||||||
|
// Call function that computes the angle of motion based on the retrieved measures
|
||||||
|
imuProcessor.process_gyro(gyroData, ts);
|
||||||
|
}
|
||||||
|
// If casting succeeded and the arrived frame is from accelerometer stream
|
||||||
|
if (motion && motion.get_profile().stream_type() == RS2_STREAM_ACCEL && motion.get_profile().format() == RS2_FORMAT_MOTION_XYZ32F)
|
||||||
|
{
|
||||||
|
// Get accelerometer measures
|
||||||
|
rs2_vector accelData = motion.get_motion_data();
|
||||||
|
// Call function that computes the angle of motion based on the retrieved measures
|
||||||
|
imuProcessor.process_accel(accelData);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
cameraCfg.enable_stream(rs2_stream::RS2_STREAM_COLOR, 640, 480, rs2_format::RS2_FORMAT_BGR8, 30);
|
||||||
|
cameraCfg.enable_stream(rs2_stream::RS2_STREAM_DEPTH, 640, 480, rs2_format::RS2_FORMAT_Z16, 30);
|
||||||
|
|
||||||
|
rs2::pipeline_profile cameraProfile = cameraPipe.start(cameraCfg);
|
||||||
|
|
||||||
|
// 创建一个对齐模块
|
||||||
|
rs2::align align2Depth(RS2_STREAM_DEPTH);
|
||||||
|
// 对掩码进行腐蚀,定义腐蚀核
|
||||||
|
cv::Mat kernel = cv::getStructuringElement(cv::MORPH_RECT, cv::Size(5, 5));
|
||||||
|
|
||||||
|
// 创建yolov8
|
||||||
|
Yolo yoloV8("/home/jetson/tmp/obstacle-detection-new1/workspace/best.transd.engine");
|
||||||
|
// 创建点云处理器
|
||||||
|
string cfgPath = "";
|
||||||
|
cv::Mat mK(4, 4, CV_32F);
|
||||||
|
DepthProcessor depthProcessor(cfgPath, mK);
|
||||||
|
depthProcessor.fx = 388.588;
|
||||||
|
depthProcessor.fy = 388.588;
|
||||||
|
depthProcessor.cx = 322.771;
|
||||||
|
depthProcessor.cy = 236.947;
|
||||||
|
|
||||||
|
bool isObject = false, isLabel = false;
|
||||||
|
std::string label = "";
|
||||||
|
auto startTime = std::chrono::high_resolution_clock::now();
|
||||||
|
int count = 1;
|
||||||
|
|
||||||
|
// 初始化时必须让摄像头看到地面
|
||||||
|
rs2::frameset allFrames = cameraPipe.wait_for_frames();
|
||||||
|
float3 theta = imuProcessor.get_theta();
|
||||||
|
rs2::frameset alignedFrames = align2Depth.process(allFrames);
|
||||||
|
rs2::depth_frame depthFrame = alignedFrames.get_depth_frame();
|
||||||
|
rs2::video_frame colorFrame = alignedFrames.get_color_frame();
|
||||||
|
|
||||||
|
//获取深度图的长宽
|
||||||
|
int widthD = depthFrame.get_width();
|
||||||
|
int heightD = depthFrame.get_height();
|
||||||
|
cv::Mat depthMat(cv::Size(widthD, heightD), CV_16U, (void*)depthFrame.get_data(), cv::Mat::AUTO_STEP);
|
||||||
|
|
||||||
|
// 将彩色图像转换为cv::Mat类型
|
||||||
|
int widthC = colorFrame.get_width();
|
||||||
|
int heightC = colorFrame.get_height();
|
||||||
|
cv::Mat colorMat(cv::Size(widthC, heightC), CV_8UC3, (void*)colorFrame.get_data(), cv::Mat::AUTO_STEP);
|
||||||
|
|
||||||
|
// 定义变换矩阵(平移和旋转)
|
||||||
|
Eigen::Affine3f transform = Eigen::Affine3f::Identity();
|
||||||
|
transform.translation() << 0.0, 0.0, 0.0; // 平移
|
||||||
|
transform.rotate(Eigen::AngleAxisf(-theta.x, Eigen::Vector3f::UnitZ()) *
|
||||||
|
Eigen::AngleAxisf(0, Eigen::Vector3f::UnitY()) *
|
||||||
|
Eigen::AngleAxisf(theta.z + PI_FL/2, Eigen::Vector3f::UnitX()));
|
||||||
|
|
||||||
|
int init_count = 0;
|
||||||
|
float tmp_height = 0;
|
||||||
|
// 关闭蜂鸣器
|
||||||
|
int output_pin_ = 13;
|
||||||
|
GPIO::setmode(GPIO::BCM);
|
||||||
|
//signal(SIGINT, signalHandler);
|
||||||
|
GPIO::setup(output_pin_, GPIO::OUT, GPIO::LOW);
|
||||||
|
GPIO::output(output_pin_, GPIO::LOW);
|
||||||
|
|
||||||
|
//相机初始化 10次
|
||||||
|
while(true){
|
||||||
|
if(!depthProcessor.camHighInit(depthMat, transform)){
|
||||||
|
std::cout << "初始化失败" << std::endl;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
tmp_height += depthProcessor.camHigh;
|
||||||
|
init_count ++;
|
||||||
|
if(init_count == 10)
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
theta = imuProcessor.get_theta();
|
||||||
|
|
||||||
|
transform = Eigen::Affine3f::Identity();
|
||||||
|
transform.translation() << 0.0, 0.0, 0.0;
|
||||||
|
|
||||||
|
transform.rotate(Eigen::AngleAxisf(-theta.x, Eigen::Vector3f::UnitZ()) *
|
||||||
|
Eigen::AngleAxisf(0, Eigen::Vector3f::UnitY()) *
|
||||||
|
Eigen::AngleAxisf(theta.z + PI_FL/2, Eigen::Vector3f::UnitX()));
|
||||||
|
|
||||||
|
allFrames = cameraPipe.wait_for_frames();
|
||||||
|
alignedFrames = align2Depth.process(allFrames);
|
||||||
|
depthFrame = alignedFrames.get_depth_frame();
|
||||||
|
depthMat = cv::Mat(cv::Size(widthD, heightD), CV_16U, (void*)depthFrame.get_data(), cv::Mat::AUTO_STEP);
|
||||||
|
}
|
||||||
|
depthProcessor.camHigh = tmp_height / init_count;
|
||||||
|
|
||||||
|
std::cout << "相机初始化:" << depthProcessor.camHigh << std::endl;
|
||||||
|
|
||||||
|
// 超声波模块参数初始化
|
||||||
|
for(int i = 0 ; i < initial_times; i++)// 先初始化数组里的数为0
|
||||||
|
{
|
||||||
|
dis0[i] = 0.0;
|
||||||
|
dis1[i] = 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 创建超声波线程
|
||||||
|
std::thread ultrasonicThread(ultrasound_play);
|
||||||
|
ultrasonicThread.detach();
|
||||||
|
// 创建蜂鸣器线程
|
||||||
|
std::thread BeeThread(Bee);
|
||||||
|
BeeThread.detach();
|
||||||
|
// // classes
|
||||||
|
std::thread playAllClassThread(play_all_class);
|
||||||
|
playAllClassThread.detach();
|
||||||
|
|
||||||
|
// 相机主循环
|
||||||
|
|
||||||
|
while(true) {
|
||||||
|
|
||||||
|
//等待来自摄像机的下一组图像
|
||||||
|
rs2::frameset allFrames = cameraPipe.wait_for_frames();
|
||||||
|
float3 theta = imuProcessor.get_theta();
|
||||||
|
|
||||||
|
// 对齐深度图像和彩色图像
|
||||||
|
rs2::frameset alignedFrames = align2Depth.process(allFrames);
|
||||||
|
// 获取对齐后的深度图像和彩色图像
|
||||||
|
rs2::depth_frame depthFrame = alignedFrames.get_depth_frame();
|
||||||
|
rs2::video_frame colorFrame = alignedFrames.get_color_frame();
|
||||||
|
|
||||||
|
// 检查是否成功获取数据
|
||||||
|
if (depthFrame && colorFrame) {
|
||||||
|
auto start = std::chrono::high_resolution_clock::now();
|
||||||
|
|
||||||
|
// 将深度图像转换为cv::Mat类型
|
||||||
|
int widthD = depthFrame.get_width();
|
||||||
|
int heightD = depthFrame.get_height();
|
||||||
|
cv::Mat depthMat(cv::Size(widthD, heightD), CV_16U, (void*)depthFrame.get_data(), cv::Mat::AUTO_STEP);
|
||||||
|
|
||||||
|
// 将彩色图像转换为cv::Mat类型
|
||||||
|
int widthC = colorFrame.get_width();
|
||||||
|
int heightC = colorFrame.get_height();
|
||||||
|
|
||||||
|
cv::Mat colorMat(cv::Size(widthC, heightC), CV_8UC3, (void*)colorFrame.get_data(), cv::Mat::AUTO_STEP);
|
||||||
|
|
||||||
|
// 定义变换矩阵(平移和旋转)
|
||||||
|
Eigen::Affine3f transform = Eigen::Affine3f::Identity();
|
||||||
|
transform.translation() << 0.0, 0.0, 0.0; // 平移
|
||||||
|
transform.rotate(Eigen::AngleAxisf(-theta.x, Eigen::Vector3f::UnitZ()) *
|
||||||
|
Eigen::AngleAxisf(0, Eigen::Vector3f::UnitY()) *
|
||||||
|
Eigen::AngleAxisf(theta.z + PI_FL/2, Eigen::Vector3f::UnitX()));
|
||||||
|
|
||||||
|
isObject = false;
|
||||||
|
// 在深度图中检测最近障碍物,返回是否存在障碍物,0不存在,1存在
|
||||||
|
try {
|
||||||
|
isObject = depthProcessor.obstacleDetect(depthMat, transform);
|
||||||
|
if(isObject)
|
||||||
|
{
|
||||||
|
isObjectt = true;
|
||||||
|
distt = depthProcessor.dist;
|
||||||
|
}
|
||||||
|
else isObjectt = false;
|
||||||
|
}
|
||||||
|
catch (const std::exception& e) {
|
||||||
|
std::cerr << "Caught exception: " << e.what() << std::endl;
|
||||||
|
isObject = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// YOLOv8分割+检测
|
||||||
|
BoxArray objs = yoloV8.detect(colorMat);
|
||||||
|
|
||||||
|
if(isObject) {
|
||||||
|
cv::rectangle(colorMat, cv::Point(depthProcessor.min_x, depthProcessor.min_y),
|
||||||
|
cv::Point(depthProcessor.max_x, depthProcessor.max_y),
|
||||||
|
cv::Scalar(0, 0, 255), 1);
|
||||||
|
cv::String text = cv::format("dis:%.2f", depthProcessor.dist);
|
||||||
|
cv::putText(colorMat, text, cv::Point(depthProcessor.min_x, depthProcessor.min_y+10),
|
||||||
|
0, 0.7, cv::Scalar(0,0,255), 1, 8);
|
||||||
|
}
|
||||||
|
|
||||||
|
float tmp_depth = 100;
|
||||||
|
if(!classes.empty()){
|
||||||
|
classes.clear();
|
||||||
|
}
|
||||||
|
// 输出识别框信息
|
||||||
|
for(Box &obj : objs) {
|
||||||
|
cout << yoloV8.cocoLabels[obj.classLabel] << " ";
|
||||||
|
}
|
||||||
|
cout << endl;
|
||||||
|
for(Box &obj : objs) {
|
||||||
|
float depth = 0;
|
||||||
|
int i = 0;
|
||||||
|
cv::Mat mask(obj.seg->height, obj.seg->width, CV_8U, obj.seg->data);
|
||||||
|
int objWidth = obj.right - obj.left;
|
||||||
|
int objHeight = obj.bottom - obj.top;
|
||||||
|
cv::resize(mask, mask, cv::Size(objWidth, objHeight));
|
||||||
|
// 进行腐蚀操作
|
||||||
|
cv::erode(mask, mask, kernel);
|
||||||
|
|
||||||
|
// 将掩码绘制到RGB图像上
|
||||||
|
//cv::Rect roi(obj.left, obj.top, obj_width, obj_height);
|
||||||
|
//cv::Mat maskColor;
|
||||||
|
//cv::cvtColor(mask, maskColor, cv::COLOR_GRAY2BGR);
|
||||||
|
//maskColor.copyTo(colorMat(roi));
|
||||||
|
|
||||||
|
for(int x = 0; x < objWidth; x++){
|
||||||
|
for(int y = 0 ;y < objHeight; y++){
|
||||||
|
if(mask.at<uchar>(y, x) > 10){
|
||||||
|
uint16_t d = depthMat.at<uint16_t>(obj.top + y, obj.left + x);
|
||||||
|
if(d > 300) {
|
||||||
|
depth += depthMat.at<uint16_t>(obj.top + y, obj.left + x);
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
depth = depth/(i*1000);
|
||||||
|
|
||||||
|
if(isObject){
|
||||||
|
if (depthProcessor.max_x > obj.left && depthProcessor.min_x < obj.right
|
||||||
|
&& depthProcessor.max_y > obj.top && depthProcessor.min_y < obj.bottom){
|
||||||
|
double rate = depthProcessor.IOU(depthProcessor.max_x, depthProcessor.min_x, depthProcessor.max_y, depthProcessor.min_y,
|
||||||
|
obj.right, obj.left, obj.bottom, obj.top);
|
||||||
|
if(rate >= 0.3){
|
||||||
|
isLabel = true;
|
||||||
|
|
||||||
|
if(tmp_depth > depth){
|
||||||
|
tmp_depth = depth;
|
||||||
|
label = yoloV8.cocoLabels[obj.classLabel];
|
||||||
|
}
|
||||||
|
else isLabel = false;
|
||||||
|
if(!labelCheck(label)){
|
||||||
|
// 如果标签不在所需要的标签中
|
||||||
|
isLabel = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// if(/*isObject && */isLabel){
|
||||||
|
// // if(abs(depthProcessor.dist - depth) > 0.2){
|
||||||
|
// // isLabel = false;
|
||||||
|
|
||||||
|
// // std::cout << " depthProcessor.dist = " << depthProcessor.dist << " depth =" << depth << std::endl;
|
||||||
|
// // }
|
||||||
|
|
||||||
|
// // else
|
||||||
|
// if(tmp_depth > depth){
|
||||||
|
// tmp_depth = depth;
|
||||||
|
// std::cout << "something near" <<std::endl;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// }
|
||||||
|
// 要播报的全部类别
|
||||||
|
classes.insert(yoloV8.cocoLabels[obj.classLabel]);
|
||||||
|
|
||||||
|
cv::String depthText = cv::format("d:%.2f", depth);
|
||||||
|
cv::putText(colorMat, depthText, cv::Point(obj.left, obj.top+10), 0, 0.7, cv::Scalar(0,255,0), 1, 8);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
auto endTime = std::chrono::high_resolution_clock::now();
|
||||||
|
auto duration = std::chrono::duration_cast<std::chrono::seconds>(endTime - startTime);
|
||||||
|
// 语音播报,间隔大于等于秒在进行下一次
|
||||||
|
if(duration.count() >= 7 || count == 1){
|
||||||
|
if(ToPlay){
|
||||||
|
// 超声波播报
|
||||||
|
std::cout << std::endl << "************************有障碍物;dis0_d: " << dis0_d << "|| dis1_d: " << dis1_d << std::endl;
|
||||||
|
// play_voice("object");
|
||||||
|
// Bee(300000);
|
||||||
|
// 回置全局变量
|
||||||
|
// ToPlay = false;
|
||||||
|
voice_status = 0;
|
||||||
|
startTime = std::chrono::high_resolution_clock::now();
|
||||||
|
count++;
|
||||||
|
}else{
|
||||||
|
// 相机播报
|
||||||
|
if(isObject && isLabel){
|
||||||
|
isLabel = false;
|
||||||
|
std::cout << std::endl;
|
||||||
|
std::cout << "前方" << depthProcessor.dist << "米存在" << label << std::endl;
|
||||||
|
{
|
||||||
|
voice_status = 1;
|
||||||
|
}
|
||||||
|
play_voice(label);
|
||||||
|
voice_status = 0;
|
||||||
|
startTime = std::chrono::high_resolution_clock::now();
|
||||||
|
count++;
|
||||||
|
}else if(isObject){
|
||||||
|
std::cout << std::endl;
|
||||||
|
std::cout << "前方" << depthProcessor.dist << "米有障碍物"<< std::endl;
|
||||||
|
{
|
||||||
|
voice_status = 2;
|
||||||
|
}
|
||||||
|
play_voice(label);
|
||||||
|
voice_status = 0;
|
||||||
|
startTime = std::chrono::high_resolution_clock::now();
|
||||||
|
count++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
isLabel = false;
|
||||||
|
// 回置count
|
||||||
|
if(count == 100){
|
||||||
|
count = 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
cv::imshow("RGB Image", colorMat);
|
||||||
|
if (cv::waitKey(5) == 27) break;
|
||||||
|
auto end = std::chrono::high_resolution_clock::now();
|
||||||
|
auto duration_test = std::chrono::duration_cast<std::chrono::microseconds>(end - start).count();
|
||||||
|
std::cout << "Time taken: " << duration_test << " microseconds" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -0,0 +1,338 @@
|
||||||
|
// system header files
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#include <sys/signal.h>
|
||||||
|
#include <sys/file.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <iostream>
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
// user-defined header files
|
||||||
|
#include "likely.h"
|
||||||
|
#include "serialport.h"
|
||||||
|
|
||||||
|
const int SLEEP_TIME_INTERVAL = 2;
|
||||||
|
const int RETRY_INIT_INTERVAL = 5;
|
||||||
|
int wait_flag = noflag;
|
||||||
|
|
||||||
|
SerialPort::Port_INFO *SerialPort::readyPort(int id, Port_INFO *pPort)
|
||||||
|
{
|
||||||
|
pthread_mutex_init(&pPort->mt,NULL);
|
||||||
|
/*Ubuntu<74><75><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
*sudo gpasswd --add zhaojq dialout
|
||||||
|
*logout
|
||||||
|
*<EFBFBD><EFBFBD><EFBFBD><EFBFBD>open /dev/ttyS0Ȩ<EFBFBD><EFBFBD>
|
||||||
|
*/
|
||||||
|
sprintf(pPort->name,"/dev/voice");
|
||||||
|
// pPort->name = "/dev/voice";
|
||||||
|
/*A8<41><38><EFBFBD><EFBFBD><EFBFBD><EFBFBD>*/
|
||||||
|
//sprintf(pPort->name,"/dev/s3c2410_serial%d",id);
|
||||||
|
|
||||||
|
pPort->fd = open(pPort->name, O_RDWR | O_NOCTTY | O_NDELAY);
|
||||||
|
if (unlikely(pPort->fd < 0)) {
|
||||||
|
fprintf(stderr, "Open Serial [%s] Error... [FAIL]\n", pPort->name);
|
||||||
|
free(pPort);
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
return pPort;
|
||||||
|
}
|
||||||
|
|
||||||
|
int SerialPort::cleanPort(Port_INFO *pPort)
|
||||||
|
{
|
||||||
|
if(likely(pPort->fd > 0)) {
|
||||||
|
close(pPort->fd);
|
||||||
|
pPort->fd = -1;
|
||||||
|
free(pPort);
|
||||||
|
pPort = NULL;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*c_cflag:<3A><><EFBFBD><EFBFBD>ģʽ<C4A3><CABD>־,ָ<><D6B8><EFBFBD>ն<EFBFBD>Ӳ<EFBFBD><D3B2><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϣ
|
||||||
|
* CLOCAL:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ե<EFBFBD><EFBFBD>ƽ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>·״̬,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>豸<EFBFBD>DZ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* CREAD:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ý<EFBFBD><EFBFBD><EFBFBD>װ<EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD>Խ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ַ<EFBFBD>
|
||||||
|
*/
|
||||||
|
int SerialPort::setPortSpeed(Port_INFO *pPort, int port_speed)
|
||||||
|
{
|
||||||
|
/*tcgetattr:<3A><><EFBFBD>ڻ<EFBFBD>ȡ<EFBFBD>ն<EFBFBD><D5B6><EFBFBD>صIJ<D8B5><C4B2><EFBFBD>*/
|
||||||
|
if(unlikely(tcgetattr(pPort->fd,&pPort->ntm) != 0)) {
|
||||||
|
fprintf(stderr, "Set Serial [%s] Speed Error... [FAIL]\n",pPort->name);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int speed = 0;
|
||||||
|
switch(port_speed)
|
||||||
|
{
|
||||||
|
case 300:
|
||||||
|
speed = B300;
|
||||||
|
break;
|
||||||
|
case 1200:
|
||||||
|
speed = B1200;
|
||||||
|
break;
|
||||||
|
case 2400:
|
||||||
|
speed = B2400;
|
||||||
|
break;
|
||||||
|
case 4800:
|
||||||
|
speed = B4800;
|
||||||
|
break;
|
||||||
|
case 9600:
|
||||||
|
speed = B9600;
|
||||||
|
break;
|
||||||
|
case 19200:
|
||||||
|
speed = B19200;
|
||||||
|
break;
|
||||||
|
case 38400:
|
||||||
|
speed = B38400;
|
||||||
|
break;
|
||||||
|
case 115200:
|
||||||
|
speed = B115200;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
fprintf(stderr, "Unsupported Port Speed... [FAIL]\n");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
/*<2A><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>벨<EFBFBD><EBB2A8><EFBFBD><EFBFBD>*/
|
||||||
|
cfsetispeed(&pPort->ntm, speed);
|
||||||
|
/*<2A><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>*/
|
||||||
|
cfsetospeed(&pPort->ntm, speed);
|
||||||
|
pPort->ntm.c_cflag |= (CLOCAL | CREAD); //Enable the receiver and set local mode
|
||||||
|
/*tcsetattr:<3A><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ն<EFBFBD><D5B6><EFBFBD>صIJ<D8B5><C4B2><EFBFBD>
|
||||||
|
* TCSANOW:<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ݴ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ͼ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ı<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* TCSADRAIN:<EFBFBD>ȴ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ݴ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ϲŸı<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* TCSAFLUSH:<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ÿı<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
*/
|
||||||
|
tcsetattr(pPort->fd,TCSANOW,&pPort->ntm);
|
||||||
|
// fprintf(stdout, "Set SerialPort Speed:[%d]... [OK]\n", port_speed);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
*c_cflag:
|
||||||
|
* CSIZE:<EFBFBD>ֽڴ<EFBFBD>С<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,ָ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͺͽ<EFBFBD><EFBFBD>յ<EFBFBD>ÿ<EFBFBD><EFBFBD><EFBFBD>ֽڵ<EFBFBD>λ<EFBFBD><EFBFBD>(<EFBFBD><EFBFBD><EFBFBD>Ȳ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>żУ<EFBFBD><EFBFBD>λ).ȡֵ<EFBFBD><EFBFBD>ΧΪCS5,CS6,CS7,CS8
|
||||||
|
* PARENB:<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ż<EFBFBD>ԵIJ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͼ<EFBFBD><EFBFBD>.<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ַ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>żλ,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ַ<EFBFBD>ִ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ż<EFBFBD><EFBFBD>У<EFBFBD><EFBFBD>
|
||||||
|
* PARODD:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ַ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ż<EFBFBD>Զ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>;<EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊż
|
||||||
|
* CSTOPB:<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ֹͣλ;<EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊһ<EFBFBD><EFBFBD>ֹͣλ
|
||||||
|
* CRTSCTS:ʹ<EFBFBD><EFBFBD>RTS/CTS<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
*c_iflag:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ģʽ<EFBFBD><EFBFBD>־,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ն<EFBFBD><EFBFBD><EFBFBD><EFBFBD>뷽ʽ
|
||||||
|
* INPCK:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>żУ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>;<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
*c_oflag:<EFBFBD><EFBFBD><EFBFBD>ģʽ<EFBFBD><EFBFBD>־,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ն<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʽ
|
||||||
|
* OPOST:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD>ִ<EFBFBD><EFBFBD>ʵ<EFBFBD>ֶ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
*c_lflag:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ģʽ<EFBFBD><EFBFBD>־,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ն˱༭<EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* ICANON:ʹ<EFBFBD>ñ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ģʽ
|
||||||
|
* ECHO:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ַ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>͵<EFBFBD><EFBFBD>ն<EFBFBD><EFBFBD>豸
|
||||||
|
* ECHOE:<EFBFBD>ɼ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* ISIG:<EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>INTR,OUIT,SUSPʱ,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ӧ<EFBFBD>ź<EFBFBD>
|
||||||
|
*/
|
||||||
|
int SerialPort::setPortParity(Port_INFO *pPort,int databits,int parity,int stopbits)
|
||||||
|
{
|
||||||
|
if(unlikely(tcgetattr(pPort->fd,&pPort->ntm) != 0)) {
|
||||||
|
fprintf(stderr, "Set Serial [%s] Parity Error... [FAIL]\n",pPort->name);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
pPort->ntm.c_cflag &= ~CSIZE;
|
||||||
|
/*<2A><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>λ*/
|
||||||
|
switch (databits)
|
||||||
|
{
|
||||||
|
case 7:
|
||||||
|
pPort->ntm.c_cflag |= CS7;
|
||||||
|
break;
|
||||||
|
case 8:
|
||||||
|
pPort->ntm.c_cflag |= CS8;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
fprintf(stderr, "Unsupported Port Data bits... [FAIL]\n");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
/*<2A><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>żУ<C5BC><D0A3>λ*/
|
||||||
|
switch (parity)
|
||||||
|
{
|
||||||
|
/*No parity <20><><EFBFBD><EFBFBD>żУ<C5BC><D0A3>λ*/
|
||||||
|
case 'n':
|
||||||
|
case 'N':
|
||||||
|
pPort->ntm.c_cflag &= ~PARENB; /* Clear parity enable */
|
||||||
|
pPort->ntm.c_iflag &= ~INPCK; /* Enable parity checking */
|
||||||
|
break;
|
||||||
|
|
||||||
|
/*Odd parity <20><>У<EFBFBD><D0A3>*/
|
||||||
|
case 'o':
|
||||||
|
case 'O':
|
||||||
|
pPort->ntm.c_cflag |= (PARODD | PARENB);
|
||||||
|
pPort->ntm.c_iflag |= INPCK; /* Disnable parity checking */
|
||||||
|
break;
|
||||||
|
/*Even parity żУ<C5BC><D0A3>*/
|
||||||
|
case 'e':
|
||||||
|
case 'E':
|
||||||
|
pPort->ntm.c_cflag |= PARENB; /* Enable parity */
|
||||||
|
pPort->ntm.c_cflag &= ~PARODD;
|
||||||
|
pPort->ntm.c_iflag |= INPCK;
|
||||||
|
break;
|
||||||
|
case 'S':
|
||||||
|
case 's': /*as no parity*/
|
||||||
|
pPort->ntm.c_cflag &= ~PARENB;
|
||||||
|
pPort->ntm.c_cflag &= ~CSTOPB;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
fprintf(stderr, "Unsupported Port Parity... [FAIL]\n");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
/*<2A><><EFBFBD><EFBFBD>ֹͣλ*/
|
||||||
|
switch (stopbits)
|
||||||
|
{
|
||||||
|
case 1:
|
||||||
|
pPort->ntm.c_cflag &= ~CSTOPB;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
pPort->ntm.c_cflag |= CSTOPB;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
fprintf(stderr, "Unsupported Port Stop bits... [FAIL]\n");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
pPort->ntm.c_cflag &= ~CRTSCTS; // disable hardware flow control
|
||||||
|
pPort->ntm.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); /*Input*/
|
||||||
|
pPort->ntm.c_oflag &= ~OPOST;
|
||||||
|
/*tcflush:<3A><><EFBFBD><EFBFBD>ն<EFBFBD>δ<EFBFBD><CEB4>ɵ<EFBFBD><C9B5><EFBFBD><EFBFBD><EFBFBD>/<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* TCIFLUSH:ˢ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* TCOFLUSH:ˢ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
* TCIOFLUSH:ˢ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>/<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
*/
|
||||||
|
tcflush(pPort->fd, TCIFLUSH);
|
||||||
|
/*<2A>ȴ<EFBFBD>ʱ<EFBFBD><CAB1>(<28>ٺ<EFBFBD><D9BA><EFBFBD>)*/
|
||||||
|
pPort->ntm.c_cc[VTIME] = 5;
|
||||||
|
/*<2A>ȴ<EFBFBD><C8B4><EFBFBD><EFBFBD><EFBFBD>С<EFBFBD>ֽ<EFBFBD><D6BD><EFBFBD>*/
|
||||||
|
pPort->ntm.c_cc[VMIN] = 1;
|
||||||
|
tcsetattr(pPort->fd,TCSANOW,&pPort->ntm);
|
||||||
|
// fprintf(stdout, "Set SerialPort Data bits:[%d], Parity:[%c], Stop bits:[%d]... [OK]\n", databits, parity, stopbits);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int SerialPort::InitPort(Port_INFO *pPort, int COM_id)
|
||||||
|
{
|
||||||
|
int i=0;
|
||||||
|
while(RETRY_INIT_INTERVAL - i) {
|
||||||
|
if(COM_id < 0) COM_id = COM_PORT;
|
||||||
|
pPort = readyPort(COM_id, pPort);
|
||||||
|
if(unlikely(pPort == NULL)) {
|
||||||
|
sleep(SLEEP_TIME_INTERVAL); i++; continue;
|
||||||
|
}
|
||||||
|
// fprintf(stdout, "Ready Serial [%s]... [OK]\n",pPort->name);
|
||||||
|
|
||||||
|
lockPort(pPort);
|
||||||
|
bzero(&pPort->ntm, sizeof(pPort->ntm));
|
||||||
|
if(unlikely(setPortSpeed(pPort, PORT_SPEED) < 0)) {
|
||||||
|
sleep(SLEEP_TIME_INTERVAL); i++; continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(unlikely(setPortParity(pPort, PORT_DATABITS, PORT_PARITY, PORT_STOPBITS) < 0)) {
|
||||||
|
sleep(SLEEP_TIME_INTERVAL); i++; continue;
|
||||||
|
}
|
||||||
|
unlockPort(pPort);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void signal_handler_IO (int status)
|
||||||
|
{
|
||||||
|
wait_flag = noflag;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 弃用
|
||||||
|
int SerialPort::recvnPort(SerialPort::Port_INFO *pPort,char *pbuf,int size)
|
||||||
|
{
|
||||||
|
int ret,left;
|
||||||
|
char *ptmp;
|
||||||
|
|
||||||
|
ret = 0;
|
||||||
|
left = size;
|
||||||
|
ptmp = pbuf;
|
||||||
|
|
||||||
|
while(left > 0) {
|
||||||
|
pthread_mutex_lock(&pPort->mt);
|
||||||
|
ret = read(pPort->fd,ptmp,left);
|
||||||
|
pthread_mutex_unlock(&pPort->mt);
|
||||||
|
if(likely(ret > 0)) {
|
||||||
|
left -= ret;
|
||||||
|
ptmp += ret;
|
||||||
|
} else if(ret <= 0) {
|
||||||
|
tcflush(pPort->fd, TCIOFLUSH);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return size - left;
|
||||||
|
}
|
||||||
|
|
||||||
|
int SerialPort::signal_recvnPort(Port_INFO *pPort,char *pbuf,int size)
|
||||||
|
{
|
||||||
|
int nread = 0;
|
||||||
|
// struct sigaction saio;
|
||||||
|
// saio.sa_handler = signal_handler_IO;
|
||||||
|
// sigemptyset (&saio.sa_mask);
|
||||||
|
// saio.sa_flags = 0;
|
||||||
|
// saio.sa_restorer = NULL;
|
||||||
|
/*
|
||||||
|
*Ӧ<EFBFBD>ò<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>첽֪ͨ:
|
||||||
|
*<EFBFBD><EFBFBD><EFBFBD>豸<EFBFBD><EFBFBD>дʱ,<EFBFBD>豸<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>һ<EFBFBD><EFBFBD><EFBFBD>źŸ<EFBFBD><EFBFBD>ں<EFBFBD>,<EFBFBD><EFBFBD>֪<EFBFBD>ں<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ݿɶ<EFBFBD>,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>֮ǰ,<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
*/
|
||||||
|
//<2F><><EFBFBD>ö<EFBFBD><C3B6>źŵĴ<C5B5><C4B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>,SIGIO:<3A>ļ<EFBFBD><C4BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><D7BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<2C><><EFBFBD>Կ<EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>/<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||||
|
// sigaction(SIGIO, &saio, NULL);
|
||||||
|
//ָ<><D6B8>һ<EFBFBD><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ<EFBFBD>ļ<EFBFBD><C4BC><EFBFBD>"<22><><EFBFBD><EFBFBD>"
|
||||||
|
// fcntl(pPort->fd, F_SETOWN, getpid ());
|
||||||
|
//<2F><><EFBFBD>豸<EFBFBD>ļ<EFBFBD><C4BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>FASYNC<4E><43>־
|
||||||
|
// int f_flags = fcntl(pPort->fd, F_GETFL);
|
||||||
|
// fcntl(pPort->fd, F_SETFL, f_flags|FASYNC);
|
||||||
|
|
||||||
|
memset (pbuf, 0, size);
|
||||||
|
nread = read(pPort->fd, pbuf, size);
|
||||||
|
|
||||||
|
return nread;
|
||||||
|
}
|
||||||
|
|
||||||
|
int SerialPort::sendnPort(SerialPort::Port_INFO *pPort,char *pbuf,int size)
|
||||||
|
{
|
||||||
|
int ret,left;
|
||||||
|
char *ptmp;
|
||||||
|
|
||||||
|
ret = 0;
|
||||||
|
left = size;
|
||||||
|
ptmp = pbuf;
|
||||||
|
|
||||||
|
while(left > 0) {
|
||||||
|
pthread_mutex_lock(&pPort->mt);
|
||||||
|
ret = write(pPort->fd,ptmp,left);
|
||||||
|
pthread_mutex_unlock(&pPort->mt);
|
||||||
|
if(likely(ret > 0)) {
|
||||||
|
left -= ret;
|
||||||
|
ptmp += ret;
|
||||||
|
} else if(ret <= 0) {
|
||||||
|
tcflush(pPort->fd, TCIOFLUSH);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return size - left;
|
||||||
|
}
|
||||||
|
|
||||||
|
int SerialPort::lockPort(Port_INFO *pPort)
|
||||||
|
{
|
||||||
|
if(unlikely(pPort->fd < 0)) {
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
/*LOCK_EX:<3A><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>*/
|
||||||
|
return flock(pPort->fd,LOCK_EX);
|
||||||
|
}
|
||||||
|
|
||||||
|
int SerialPort::unlockPort(Port_INFO *pPort)
|
||||||
|
{
|
||||||
|
if(unlikely(pPort->fd < 0)) {
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
/*LOCK_UN<55><4E><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ļ<EFBFBD><C4BC><EFBFBD><EFBFBD><EFBFBD>*/
|
||||||
|
return flock(pPort->fd,LOCK_UN);
|
||||||
|
}
|
|
@ -0,0 +1,229 @@
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <sys/times.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <termios.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#include<iostream>
|
||||||
|
|
||||||
|
#define TIMEOUT_SEC(buflen,baud) (buflen*20/baud+2) //接收超时
|
||||||
|
#define TIMEOUT_USEC 0
|
||||||
|
|
||||||
|
#include "../include/dyp-a05/uart-ctrl.h"
|
||||||
|
|
||||||
|
|
||||||
|
/*******************************************
|
||||||
|
* 波特率转换函数(请确认是否正确)
|
||||||
|
********************************************/
|
||||||
|
static int convBaudRate(unsigned long int baudrate)
|
||||||
|
{
|
||||||
|
switch(baudrate){
|
||||||
|
case 2400:
|
||||||
|
return B2400;
|
||||||
|
case 4800:
|
||||||
|
return B4800;
|
||||||
|
case 9600:
|
||||||
|
return B9600;
|
||||||
|
case 19200:
|
||||||
|
return B19200;
|
||||||
|
case 38400:
|
||||||
|
return B38400;
|
||||||
|
case 57600:
|
||||||
|
return B57600;
|
||||||
|
case 115200:
|
||||||
|
return B115200;
|
||||||
|
default:
|
||||||
|
return B9600;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*******************************************
|
||||||
|
* Setup serial attr
|
||||||
|
* fdcom: 串口文件描述符,pportinfo: 待设置的端口信息(请确认)
|
||||||
|
*
|
||||||
|
********************************************/
|
||||||
|
int uart_set(int fdcom, const pPortInfo_t pportinfo)
|
||||||
|
{
|
||||||
|
struct termios termios_old, termios_new;
|
||||||
|
int baudrate, tmp;
|
||||||
|
char databit, stopbit, parity, fctl;
|
||||||
|
|
||||||
|
bzero(&termios_old, sizeof(termios_old));
|
||||||
|
bzero(&termios_new, sizeof(termios_new));
|
||||||
|
cfmakeraw(&termios_new);
|
||||||
|
tcgetattr(fdcom, &termios_old); //get the serial port attributions
|
||||||
|
/*------------设置端口属性----------------*/
|
||||||
|
//baudrates
|
||||||
|
baudrate = convBaudRate(pportinfo -> baudrate);
|
||||||
|
cfsetispeed(&termios_new, baudrate); //填入串口输入端的波特率
|
||||||
|
cfsetospeed(&termios_new, baudrate); //填入串口输出端的波特率
|
||||||
|
termios_new.c_cflag |= CLOCAL; //控制模式,保证程序不会成为端口的占有者
|
||||||
|
termios_new.c_cflag |= CREAD; //控制模式,使能端口读取输入的数据
|
||||||
|
|
||||||
|
// 控制模式,flow control
|
||||||
|
fctl = pportinfo-> fctl;
|
||||||
|
switch(fctl){
|
||||||
|
case 0:{
|
||||||
|
termios_new.c_cflag &= ~CRTSCTS; //no flow control
|
||||||
|
}break;
|
||||||
|
case 1:{
|
||||||
|
termios_new.c_cflag |= CRTSCTS; //hardware flow control
|
||||||
|
}break;
|
||||||
|
case 2:{
|
||||||
|
termios_new.c_iflag |= IXON | IXOFF |IXANY; //software flow control
|
||||||
|
}break;
|
||||||
|
}
|
||||||
|
|
||||||
|
//控制模式,data bits
|
||||||
|
termios_new.c_cflag &= ~CSIZE; //控制模式,屏蔽字符大小位
|
||||||
|
databit = pportinfo -> databit;
|
||||||
|
switch(databit){
|
||||||
|
case 5:
|
||||||
|
termios_new.c_cflag |= CS5;
|
||||||
|
case 6:
|
||||||
|
termios_new.c_cflag |= CS6;
|
||||||
|
case 7:
|
||||||
|
termios_new.c_cflag |= CS7;
|
||||||
|
default:
|
||||||
|
termios_new.c_cflag |= CS8;
|
||||||
|
}
|
||||||
|
|
||||||
|
//控制模式 parity check
|
||||||
|
parity = pportinfo -> parity;
|
||||||
|
switch(parity){
|
||||||
|
case 0:{
|
||||||
|
termios_new.c_cflag &= ~PARENB; //no parity check
|
||||||
|
}break;
|
||||||
|
case 1:{
|
||||||
|
termios_new.c_cflag |= PARENB; //odd check
|
||||||
|
termios_new.c_cflag &= ~PARODD;
|
||||||
|
}break;
|
||||||
|
case 2:{
|
||||||
|
termios_new.c_cflag |= PARENB; //even check
|
||||||
|
termios_new.c_cflag |= PARODD;
|
||||||
|
}break;
|
||||||
|
}
|
||||||
|
|
||||||
|
//控制模式,stop bits
|
||||||
|
stopbit = pportinfo -> stopbit;
|
||||||
|
if(stopbit == 2){
|
||||||
|
termios_new.c_cflag |= CSTOPB; //2 stop bits
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
termios_new.c_cflag &= ~CSTOPB; //1 stop bits
|
||||||
|
}
|
||||||
|
|
||||||
|
//other attributions default
|
||||||
|
termios_new.c_oflag &= ~OPOST; //输出模式,原始数据输出
|
||||||
|
termios_new.c_cc[VMIN] = 1; //控制字符, 所要读取字符的最小数量
|
||||||
|
termios_new.c_cc[VTIME] = 5; //控制字符, 读取第一个字符的等待时间 unit: (1/10)second
|
||||||
|
|
||||||
|
tcflush(fdcom, TCIFLUSH); //溢出的数据可以接收,但不读
|
||||||
|
tmp = tcsetattr(fdcom, TCSANOW, &termios_new); //设置新属性,TCSANOW:所有改变立即生效 tcgetattr(fdcom, &termios_old);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
return(tmp);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*******************************************
|
||||||
|
* Open serial port
|
||||||
|
* tty: 端口号 ttyS0, ttyS1, ....
|
||||||
|
* 返回值为串口文件描述符
|
||||||
|
********************************************/
|
||||||
|
int uart_init(const char* dev)
|
||||||
|
{
|
||||||
|
return(open(dev, O_RDWR | O_NOCTTY | O_NONBLOCK));
|
||||||
|
}
|
||||||
|
|
||||||
|
/*******************************************
|
||||||
|
* Close serial port
|
||||||
|
********************************************/
|
||||||
|
void uart_deinit(int fdcom)
|
||||||
|
{
|
||||||
|
close(fdcom);
|
||||||
|
}
|
||||||
|
|
||||||
|
/********************************************
|
||||||
|
* send data
|
||||||
|
* fdcom: 串口描述符,data: 待发送数据,datalen: 数据长度
|
||||||
|
* 返回实际发送长度
|
||||||
|
*********************************************/
|
||||||
|
int uart_txd(int fdcom, const unsigned char *data, int datalen)
|
||||||
|
{
|
||||||
|
int len = 0;
|
||||||
|
|
||||||
|
len = write(fdcom, data, datalen);
|
||||||
|
if(len == datalen){
|
||||||
|
return (len);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
tcflush(fdcom, TCOFLUSH);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*******************************************
|
||||||
|
* receive data
|
||||||
|
* 返回实际读入的字节数
|
||||||
|
*
|
||||||
|
********************************************/
|
||||||
|
int uart_rxd(int fdcom, unsigned char *data, int datalen, int baudrate)
|
||||||
|
{
|
||||||
|
int readlen, fs_sel;
|
||||||
|
|
||||||
|
fd_set fs_read;
|
||||||
|
struct timeval tv_timeout;
|
||||||
|
|
||||||
|
FD_ZERO(&fs_read);
|
||||||
|
FD_SET(fdcom, &fs_read);
|
||||||
|
tv_timeout.tv_sec = TIMEOUT_SEC(datalen, baudrate);
|
||||||
|
tv_timeout.tv_usec = TIMEOUT_USEC;
|
||||||
|
|
||||||
|
fs_sel = select(fdcom+1, &fs_read, NULL, NULL, &tv_timeout);
|
||||||
|
if(fs_sel){
|
||||||
|
// tcflush(fdcom, TCIFLUSH);
|
||||||
|
// ms
|
||||||
|
usleep(300000);
|
||||||
|
readlen = read(fdcom, data, datalen);
|
||||||
|
// unsigned char bit = data[0];
|
||||||
|
return readlen;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
return (-1);
|
||||||
|
}
|
||||||
|
// return -1
|
||||||
|
|
||||||
|
return (readlen);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef TEST
|
||||||
|
int fdcom = 0;
|
||||||
|
/**
|
||||||
|
* @brief
|
||||||
|
* @param
|
||||||
|
* @retval
|
||||||
|
*/
|
||||||
|
int main(int argc, char**argv)
|
||||||
|
{
|
||||||
|
fdcom = uart_init("/dev/COM0");
|
||||||
|
if(fdcom > 0)
|
||||||
|
{
|
||||||
|
PortInfo_t portinfo = {115200, 8, 2, 0, 1, 0};
|
||||||
|
uart_set(fdcom, &portinfo);
|
||||||
|
printf("[PARAM]: 115200, 8, 2, 0, 1, 0\n");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
printf("[ERROR]: open serial port error.\n");
|
||||||
|
}
|
||||||
|
uart_deinit(fdcom);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -0,0 +1,742 @@
|
||||||
|
#include "infer.hpp"
|
||||||
|
#include "Yolo.hpp"
|
||||||
|
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
#define GPU_BLOCK_THREADS 512
|
||||||
|
#define checkRuntime(call) \
|
||||||
|
do { \
|
||||||
|
auto ___call__ret_code__ = (call); \
|
||||||
|
if (___call__ret_code__ != cudaSuccess) { \
|
||||||
|
INFO("CUDA Runtime error💥 %s # %s, code = %s [ %d ]", #call, \
|
||||||
|
cudaGetErrorString(___call__ret_code__), cudaGetErrorName(___call__ret_code__), \
|
||||||
|
___call__ret_code__); \
|
||||||
|
abort(); \
|
||||||
|
} \
|
||||||
|
} while (0)
|
||||||
|
|
||||||
|
#define checkKernel(...) \
|
||||||
|
do { \
|
||||||
|
{ (__VA_ARGS__); } \
|
||||||
|
checkRuntime(cudaPeekAtLastError()); \
|
||||||
|
} while (0)
|
||||||
|
|
||||||
|
enum class NormType : int { None = 0, MeanStd = 1, AlphaBeta = 2 };
|
||||||
|
|
||||||
|
enum class ChannelType : int { None = 0, SwapRB = 1 };
|
||||||
|
|
||||||
|
/* 归一化操作,可以支持均值标准差,alpha beta,和swap RB */
|
||||||
|
struct Norm {
|
||||||
|
float mean[3];
|
||||||
|
float std[3];
|
||||||
|
float alpha, beta;
|
||||||
|
NormType type = NormType::None;
|
||||||
|
ChannelType channel_type = ChannelType::None;
|
||||||
|
|
||||||
|
// out = (x * alpha - mean) / std
|
||||||
|
static Norm mean_std(const float mean[3], const float std[3], float alpha = 1 / 255.0f,
|
||||||
|
ChannelType channel_type = ChannelType::None);
|
||||||
|
|
||||||
|
// out = x * alpha + beta
|
||||||
|
static Norm alpha_beta(float alpha, float beta = 0, ChannelType channel_type = ChannelType::None);
|
||||||
|
|
||||||
|
// None
|
||||||
|
static Norm None();
|
||||||
|
};
|
||||||
|
|
||||||
|
Norm Norm::mean_std(const float mean[3], const float std[3], float alpha,
|
||||||
|
ChannelType channel_type) {
|
||||||
|
Norm out;
|
||||||
|
out.type = NormType::MeanStd;
|
||||||
|
out.alpha = alpha;
|
||||||
|
out.channel_type = channel_type;
|
||||||
|
memcpy(out.mean, mean, sizeof(out.mean));
|
||||||
|
memcpy(out.std, std, sizeof(out.std));
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
Norm Norm::alpha_beta(float alpha, float beta, ChannelType channel_type) {
|
||||||
|
Norm out;
|
||||||
|
out.type = NormType::AlphaBeta;
|
||||||
|
out.alpha = alpha;
|
||||||
|
out.beta = beta;
|
||||||
|
out.channel_type = channel_type;
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
Norm Norm::None() { return Norm(); }
|
||||||
|
|
||||||
|
const int NUM_BOX_ELEMENT = 8; // left, top, right, bottom, confidence, class,
|
||||||
|
// keepflag, row_index(output)
|
||||||
|
const int MAX_IMAGE_BOXES = 1024;
|
||||||
|
inline int upbound(int n, int align = 32) { return (n + align - 1) / align * align; }
|
||||||
|
static __host__ __device__ void affine_project(float *matrix, float x, float y, float *ox,
|
||||||
|
float *oy) {
|
||||||
|
*ox = matrix[0] * x + matrix[1] * y + matrix[2];
|
||||||
|
*oy = matrix[3] * x + matrix[4] * y + matrix[5];
|
||||||
|
}
|
||||||
|
|
||||||
|
static __global__ void decode_kernel_common(float *predict, int num_bboxes, int num_classes,
|
||||||
|
int output_cdim, float confidence_threshold,
|
||||||
|
float *invert_affine_matrix, float *parray,
|
||||||
|
int MAX_IMAGE_BOXES) {
|
||||||
|
int position = blockDim.x * blockIdx.x + threadIdx.x;
|
||||||
|
if (position >= num_bboxes) return;
|
||||||
|
|
||||||
|
float *pitem = predict + output_cdim * position;
|
||||||
|
float objectness = pitem[4];
|
||||||
|
if (objectness < confidence_threshold) return;
|
||||||
|
|
||||||
|
float *class_confidence = pitem + 5;
|
||||||
|
float confidence = *class_confidence++;
|
||||||
|
int label = 0;
|
||||||
|
for (int i = 1; i < num_classes; ++i, ++class_confidence) {
|
||||||
|
if (*class_confidence > confidence) {
|
||||||
|
confidence = *class_confidence;
|
||||||
|
label = i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
confidence *= objectness;
|
||||||
|
if (confidence < confidence_threshold) return;
|
||||||
|
|
||||||
|
int index = atomicAdd(parray, 1);
|
||||||
|
if (index >= MAX_IMAGE_BOXES) return;
|
||||||
|
|
||||||
|
float cx = *pitem++;
|
||||||
|
float cy = *pitem++;
|
||||||
|
float width = *pitem++;
|
||||||
|
float height = *pitem++;
|
||||||
|
float left = cx - width * 0.5f;
|
||||||
|
float top = cy - height * 0.5f;
|
||||||
|
float right = cx + width * 0.5f;
|
||||||
|
float bottom = cy + height * 0.5f;
|
||||||
|
affine_project(invert_affine_matrix, left, top, &left, &top);
|
||||||
|
affine_project(invert_affine_matrix, right, bottom, &right, &bottom);
|
||||||
|
if(left < 0) left = 0;
|
||||||
|
if(top < 0) top = 0;
|
||||||
|
float *pout_item = parray + 1 + index * NUM_BOX_ELEMENT;
|
||||||
|
*pout_item++ = left;
|
||||||
|
*pout_item++ = top;
|
||||||
|
*pout_item++ = right;
|
||||||
|
*pout_item++ = bottom;
|
||||||
|
*pout_item++ = confidence;
|
||||||
|
*pout_item++ = label;
|
||||||
|
*pout_item++ = 1; // 1 = keep, 0 = ignore
|
||||||
|
}
|
||||||
|
|
||||||
|
static __global__ void decode_kernel_v8(float *predict, int num_bboxes, int num_classes,
|
||||||
|
int output_cdim, float confidence_threshold,
|
||||||
|
float *invert_affine_matrix, float *parray,
|
||||||
|
int MAX_IMAGE_BOXES) {
|
||||||
|
int position = blockDim.x * blockIdx.x + threadIdx.x;
|
||||||
|
if (position >= num_bboxes) return;
|
||||||
|
|
||||||
|
float *pitem = predict + output_cdim * position;
|
||||||
|
float *class_confidence = pitem + 4;
|
||||||
|
float confidence = *class_confidence++;
|
||||||
|
int label = 0;
|
||||||
|
for (int i = 1; i < num_classes; ++i, ++class_confidence) {
|
||||||
|
if (*class_confidence > confidence) {
|
||||||
|
confidence = *class_confidence;
|
||||||
|
label = i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (confidence < confidence_threshold) return;
|
||||||
|
|
||||||
|
int index = atomicAdd(parray, 1);
|
||||||
|
if (index >= MAX_IMAGE_BOXES) return;
|
||||||
|
|
||||||
|
float cx = *pitem++;
|
||||||
|
float cy = *pitem++;
|
||||||
|
float width = *pitem++;
|
||||||
|
float height = *pitem++;
|
||||||
|
float left = cx - width * 0.5f;
|
||||||
|
float top = cy - height * 0.5f;
|
||||||
|
float right = cx + width * 0.5f;
|
||||||
|
float bottom = cy + height * 0.5f;
|
||||||
|
affine_project(invert_affine_matrix, left, top, &left, &top);
|
||||||
|
affine_project(invert_affine_matrix, right, bottom, &right, &bottom);
|
||||||
|
|
||||||
|
if(left < 0) left = 0;
|
||||||
|
if(top < 0) top = 0;
|
||||||
|
float *pout_item = parray + 1 + index * NUM_BOX_ELEMENT;
|
||||||
|
*pout_item++ = left;
|
||||||
|
*pout_item++ = top;
|
||||||
|
*pout_item++ = right;
|
||||||
|
*pout_item++ = bottom;
|
||||||
|
*pout_item++ = confidence;
|
||||||
|
*pout_item++ = label;
|
||||||
|
*pout_item++ = 1; // 1 = keep, 0 = ignore
|
||||||
|
*pout_item++ = position;
|
||||||
|
}
|
||||||
|
|
||||||
|
static __device__ float box_iou(float aleft, float atop, float aright, float abottom, float bleft,
|
||||||
|
float btop, float bright, float bbottom) {
|
||||||
|
float cleft = max(aleft, bleft);
|
||||||
|
float ctop = max(atop, btop);
|
||||||
|
float cright = min(aright, bright);
|
||||||
|
float cbottom = min(abottom, bbottom);
|
||||||
|
|
||||||
|
float c_area = max(cright - cleft, 0.0f) * max(cbottom - ctop, 0.0f);
|
||||||
|
if (c_area == 0.0f) return 0.0f;
|
||||||
|
|
||||||
|
float a_area = max(0.0f, aright - aleft) * max(0.0f, abottom - atop);
|
||||||
|
float b_area = max(0.0f, bright - bleft) * max(0.0f, bbottom - btop);
|
||||||
|
return c_area / (a_area + b_area - c_area);
|
||||||
|
}
|
||||||
|
|
||||||
|
static __global__ void fast_nms_kernel(float *bboxes, int MAX_IMAGE_BOXES, float threshold) {
|
||||||
|
int position = (blockDim.x * blockIdx.x + threadIdx.x);
|
||||||
|
int count = min((int)*bboxes, MAX_IMAGE_BOXES);
|
||||||
|
if (position >= count) return;
|
||||||
|
|
||||||
|
// left, top, right, bottom, confidence, class, keepflag
|
||||||
|
float *pcurrent = bboxes + 1 + position * NUM_BOX_ELEMENT;
|
||||||
|
for (int i = 0; i < count; ++i) {
|
||||||
|
float *pitem = bboxes + 1 + i * NUM_BOX_ELEMENT;
|
||||||
|
if (i == position || pcurrent[5] != pitem[5]) continue;
|
||||||
|
|
||||||
|
if (pitem[4] >= pcurrent[4]) {
|
||||||
|
if (pitem[4] == pcurrent[4] && i < position) continue;
|
||||||
|
|
||||||
|
float iou = box_iou(pcurrent[0], pcurrent[1], pcurrent[2], pcurrent[3], pitem[0], pitem[1],
|
||||||
|
pitem[2], pitem[3]);
|
||||||
|
|
||||||
|
if (iou > threshold) {
|
||||||
|
pcurrent[6] = 0; // 1=keep, 0=ignore
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static dim3 grid_dims(int numJobs) {
|
||||||
|
int numBlockThreads = numJobs < GPU_BLOCK_THREADS ? numJobs : GPU_BLOCK_THREADS;
|
||||||
|
return dim3(((numJobs + numBlockThreads - 1) / (float)numBlockThreads));
|
||||||
|
}
|
||||||
|
|
||||||
|
static dim3 block_dims(int numJobs) {
|
||||||
|
return numJobs < GPU_BLOCK_THREADS ? numJobs : GPU_BLOCK_THREADS;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void decode_kernel_invoker(float *predict, int num_bboxes, int num_classes, int output_cdim,
|
||||||
|
float confidence_threshold, float nms_threshold,
|
||||||
|
float *invert_affine_matrix, float *parray, int MAX_IMAGE_BOXES,
|
||||||
|
Type type, cudaStream_t stream) {
|
||||||
|
auto grid = grid_dims(num_bboxes);
|
||||||
|
auto block = block_dims(num_bboxes);
|
||||||
|
|
||||||
|
if (type == Type::V8 || type == Type::V8Seg) {
|
||||||
|
checkKernel(decode_kernel_v8<<<grid, block, 0, stream>>>(
|
||||||
|
predict, num_bboxes, num_classes, output_cdim, confidence_threshold, invert_affine_matrix,
|
||||||
|
parray, MAX_IMAGE_BOXES));
|
||||||
|
} else {
|
||||||
|
checkKernel(decode_kernel_common<<<grid, block, 0, stream>>>(
|
||||||
|
predict, num_bboxes, num_classes, output_cdim, confidence_threshold, invert_affine_matrix,
|
||||||
|
parray, MAX_IMAGE_BOXES));
|
||||||
|
}
|
||||||
|
|
||||||
|
grid = grid_dims(MAX_IMAGE_BOXES);
|
||||||
|
block = block_dims(MAX_IMAGE_BOXES);
|
||||||
|
checkKernel(fast_nms_kernel<<<grid, block, 0, stream>>>(parray, MAX_IMAGE_BOXES, nms_threshold));
|
||||||
|
}
|
||||||
|
|
||||||
|
static __global__ void warp_affine_bilinear_and_normalize_plane_kernel(
|
||||||
|
uint8_t *src, int src_line_size, int src_width, int src_height, float *dst, int dst_width,
|
||||||
|
int dst_height, uint8_t const_value_st, float *warp_affine_matrix_2_3, Norm norm) {
|
||||||
|
int dx = blockDim.x * blockIdx.x + threadIdx.x;
|
||||||
|
int dy = blockDim.y * blockIdx.y + threadIdx.y;
|
||||||
|
if (dx >= dst_width || dy >= dst_height) return;
|
||||||
|
|
||||||
|
float m_x1 = warp_affine_matrix_2_3[0];
|
||||||
|
float m_y1 = warp_affine_matrix_2_3[1];
|
||||||
|
float m_z1 = warp_affine_matrix_2_3[2];
|
||||||
|
float m_x2 = warp_affine_matrix_2_3[3];
|
||||||
|
float m_y2 = warp_affine_matrix_2_3[4];
|
||||||
|
float m_z2 = warp_affine_matrix_2_3[5];
|
||||||
|
|
||||||
|
float src_x = m_x1 * dx + m_y1 * dy + m_z1;
|
||||||
|
float src_y = m_x2 * dx + m_y2 * dy + m_z2;
|
||||||
|
float c0, c1, c2;
|
||||||
|
|
||||||
|
if (src_x <= -1 || src_x >= src_width || src_y <= -1 || src_y >= src_height) {
|
||||||
|
// out of range
|
||||||
|
c0 = const_value_st;
|
||||||
|
c1 = const_value_st;
|
||||||
|
c2 = const_value_st;
|
||||||
|
} else {
|
||||||
|
int y_low = floorf(src_y);
|
||||||
|
int x_low = floorf(src_x);
|
||||||
|
int y_high = y_low + 1;
|
||||||
|
int x_high = x_low + 1;
|
||||||
|
|
||||||
|
uint8_t const_value[] = {const_value_st, const_value_st, const_value_st};
|
||||||
|
float ly = src_y - y_low;
|
||||||
|
float lx = src_x - x_low;
|
||||||
|
float hy = 1 - ly;
|
||||||
|
float hx = 1 - lx;
|
||||||
|
float w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;
|
||||||
|
uint8_t *v1 = const_value;
|
||||||
|
uint8_t *v2 = const_value;
|
||||||
|
uint8_t *v3 = const_value;
|
||||||
|
uint8_t *v4 = const_value;
|
||||||
|
if (y_low >= 0) {
|
||||||
|
if (x_low >= 0) v1 = src + y_low * src_line_size + x_low * 3;
|
||||||
|
|
||||||
|
if (x_high < src_width) v2 = src + y_low * src_line_size + x_high * 3;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (y_high < src_height) {
|
||||||
|
if (x_low >= 0) v3 = src + y_high * src_line_size + x_low * 3;
|
||||||
|
|
||||||
|
if (x_high < src_width) v4 = src + y_high * src_line_size + x_high * 3;
|
||||||
|
}
|
||||||
|
|
||||||
|
// same to opencv
|
||||||
|
c0 = floorf(w1 * v1[0] + w2 * v2[0] + w3 * v3[0] + w4 * v4[0] + 0.5f);
|
||||||
|
c1 = floorf(w1 * v1[1] + w2 * v2[1] + w3 * v3[1] + w4 * v4[1] + 0.5f);
|
||||||
|
c2 = floorf(w1 * v1[2] + w2 * v2[2] + w3 * v3[2] + w4 * v4[2] + 0.5f);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (norm.channel_type == ChannelType::SwapRB) {
|
||||||
|
float t = c2;
|
||||||
|
c2 = c0;
|
||||||
|
c0 = t;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (norm.type == NormType::MeanStd) {
|
||||||
|
c0 = (c0 * norm.alpha - norm.mean[0]) / norm.std[0];
|
||||||
|
c1 = (c1 * norm.alpha - norm.mean[1]) / norm.std[1];
|
||||||
|
c2 = (c2 * norm.alpha - norm.mean[2]) / norm.std[2];
|
||||||
|
} else if (norm.type == NormType::AlphaBeta) {
|
||||||
|
c0 = c0 * norm.alpha + norm.beta;
|
||||||
|
c1 = c1 * norm.alpha + norm.beta;
|
||||||
|
c2 = c2 * norm.alpha + norm.beta;
|
||||||
|
}
|
||||||
|
|
||||||
|
int area = dst_width * dst_height;
|
||||||
|
float *pdst_c0 = dst + dy * dst_width + dx;
|
||||||
|
float *pdst_c1 = pdst_c0 + area;
|
||||||
|
float *pdst_c2 = pdst_c1 + area;
|
||||||
|
*pdst_c0 = c0;
|
||||||
|
*pdst_c1 = c1;
|
||||||
|
*pdst_c2 = c2;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void warp_affine_bilinear_and_normalize_plane(uint8_t *src, int src_line_size, int src_width,
|
||||||
|
int src_height, float *dst, int dst_width,
|
||||||
|
int dst_height, float *matrix_2_3,
|
||||||
|
uint8_t const_value, const Norm &norm,
|
||||||
|
cudaStream_t stream) {
|
||||||
|
dim3 grid((dst_width + 31) / 32, (dst_height + 31) / 32);
|
||||||
|
dim3 block(32, 32);
|
||||||
|
|
||||||
|
checkKernel(warp_affine_bilinear_and_normalize_plane_kernel<<<grid, block, 0, stream>>>(
|
||||||
|
src, src_line_size, src_width, src_height, dst, dst_width, dst_height, const_value,
|
||||||
|
matrix_2_3, norm));
|
||||||
|
}
|
||||||
|
|
||||||
|
static __global__ void decode_single_mask_kernel(int left, int top, float *mask_weights,
|
||||||
|
float *mask_predict, int mask_width,
|
||||||
|
int mask_height, unsigned char *mask_out,
|
||||||
|
int mask_dim, int out_width, int out_height) {
|
||||||
|
// mask_predict to mask_out
|
||||||
|
// mask_weights @ mask_predict
|
||||||
|
int dx = blockDim.x * blockIdx.x + threadIdx.x;
|
||||||
|
int dy = blockDim.y * blockIdx.y + threadIdx.y;
|
||||||
|
if (dx >= out_width || dy >= out_height) return;
|
||||||
|
|
||||||
|
int sx = left + dx;
|
||||||
|
int sy = top + dy;
|
||||||
|
if (sx < 0 || sx >= mask_width || sy < 0 || sy >= mask_height) {
|
||||||
|
mask_out[dy * out_width + dx] = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
float cumprod = 0;
|
||||||
|
for (int ic = 0; ic < mask_dim; ++ic) {
|
||||||
|
float cval = mask_predict[(ic * mask_height + sy) * mask_width + sx];
|
||||||
|
float wval = mask_weights[ic];
|
||||||
|
cumprod += cval * wval;
|
||||||
|
}
|
||||||
|
|
||||||
|
float alpha = 1.0f / (1.0f + exp(-cumprod));
|
||||||
|
mask_out[dy * out_width + dx] = alpha * 255;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void decode_single_mask(float left, float top, float *mask_weights, float *mask_predict,
|
||||||
|
int mask_width, int mask_height, unsigned char *mask_out,
|
||||||
|
int mask_dim, int out_width, int out_height, cudaStream_t stream) {
|
||||||
|
// mask_weights is mask_dim(32 element) gpu pointer
|
||||||
|
dim3 grid((out_width + 31) / 32, (out_height + 31) / 32);
|
||||||
|
dim3 block(32, 32);
|
||||||
|
|
||||||
|
checkKernel(decode_single_mask_kernel<<<grid, block, 0, stream>>>(
|
||||||
|
left, top, mask_weights, mask_predict, mask_width, mask_height, mask_out, mask_dim, out_width,
|
||||||
|
out_height));
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *type_name(Type type) {
|
||||||
|
switch (type) {
|
||||||
|
case Type::V5:
|
||||||
|
return "YoloV5";
|
||||||
|
case Type::V3:
|
||||||
|
return "YoloV3";
|
||||||
|
case Type::V7:
|
||||||
|
return "YoloV7";
|
||||||
|
case Type::X:
|
||||||
|
return "YoloX";
|
||||||
|
case Type::V8:
|
||||||
|
return "YoloV8";
|
||||||
|
default:
|
||||||
|
return "Unknow";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
struct AffineMatrix {
|
||||||
|
float i2d[6]; // image to dst(network), 2x3 matrix
|
||||||
|
float d2i[6]; // dst to image, 2x3 matrix
|
||||||
|
|
||||||
|
void compute(const std::tuple<int, int> &from, const std::tuple<int, int> &to) {
|
||||||
|
float scale_x = get<0>(to) / (float)get<0>(from);
|
||||||
|
float scale_y = get<1>(to) / (float)get<1>(from);
|
||||||
|
float scale = std::min(scale_x, scale_y);
|
||||||
|
i2d[0] = scale;
|
||||||
|
i2d[1] = 0;
|
||||||
|
i2d[2] = -scale * get<0>(from) * 0.5 + get<0>(to) * 0.5 + scale * 0.5 - 0.5;
|
||||||
|
i2d[3] = 0;
|
||||||
|
i2d[4] = scale;
|
||||||
|
i2d[5] = -scale * get<1>(from) * 0.5 + get<1>(to) * 0.5 + scale * 0.5 - 0.5;
|
||||||
|
|
||||||
|
double D = i2d[0] * i2d[4] - i2d[1] * i2d[3];
|
||||||
|
D = D != 0. ? double(1.) / D : double(0.);
|
||||||
|
double A11 = i2d[4] * D, A22 = i2d[0] * D, A12 = -i2d[1] * D, A21 = -i2d[3] * D;
|
||||||
|
double b1 = -A11 * i2d[2] - A12 * i2d[5];
|
||||||
|
double b2 = -A21 * i2d[2] - A22 * i2d[5];
|
||||||
|
|
||||||
|
d2i[0] = A11;
|
||||||
|
d2i[1] = A12;
|
||||||
|
d2i[2] = b1;
|
||||||
|
d2i[3] = A21;
|
||||||
|
d2i[4] = A22;
|
||||||
|
d2i[5] = b2;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
InstanceSegmentMap::InstanceSegmentMap(int width, int height) {
|
||||||
|
this->width = width;
|
||||||
|
this->height = height;
|
||||||
|
checkRuntime(cudaMallocHost(&this->data, width * height));
|
||||||
|
}
|
||||||
|
|
||||||
|
InstanceSegmentMap::~InstanceSegmentMap() {
|
||||||
|
if (this->data) {
|
||||||
|
checkRuntime(cudaFreeHost(this->data));
|
||||||
|
this->data = nullptr;
|
||||||
|
}
|
||||||
|
this->width = 0;
|
||||||
|
this->height = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
class InferImpl : public Infer {
|
||||||
|
public:
|
||||||
|
shared_ptr<trt::Infer> trt_;
|
||||||
|
string engine_file_;
|
||||||
|
Type type_;
|
||||||
|
float confidence_threshold_;
|
||||||
|
float nms_threshold_;
|
||||||
|
vector<shared_ptr<trt::Memory<unsigned char>>> preprocess_buffers_;
|
||||||
|
trt::Memory<float> input_buffer_, bbox_predict_, output_boxarray_;
|
||||||
|
trt::Memory<float> segment_predict_;
|
||||||
|
int network_input_width_, network_input_height_;
|
||||||
|
Norm normalize_;
|
||||||
|
vector<int> bbox_head_dims_;
|
||||||
|
vector<int> segment_head_dims_;
|
||||||
|
int num_classes_ = 0;
|
||||||
|
bool has_segment_ = false;
|
||||||
|
bool isdynamic_model_ = false;
|
||||||
|
vector<shared_ptr<trt::Memory<unsigned char>>> box_segment_cache_;
|
||||||
|
|
||||||
|
virtual ~InferImpl() = default;
|
||||||
|
|
||||||
|
void adjust_memory(int batch_size) {
|
||||||
|
// the inference batch_size
|
||||||
|
size_t input_numel = network_input_width_ * network_input_height_ * 3;
|
||||||
|
input_buffer_.gpu(batch_size * input_numel);
|
||||||
|
bbox_predict_.gpu(batch_size * bbox_head_dims_[1] * bbox_head_dims_[2]);
|
||||||
|
output_boxarray_.gpu(batch_size * (32 + MAX_IMAGE_BOXES * NUM_BOX_ELEMENT));
|
||||||
|
output_boxarray_.cpu(batch_size * (32 + MAX_IMAGE_BOXES * NUM_BOX_ELEMENT));
|
||||||
|
|
||||||
|
if (has_segment_)
|
||||||
|
segment_predict_.gpu(batch_size * segment_head_dims_[1] * segment_head_dims_[2] *
|
||||||
|
segment_head_dims_[3]);
|
||||||
|
|
||||||
|
if ((int)preprocess_buffers_.size() < batch_size) {
|
||||||
|
for (int i = preprocess_buffers_.size(); i < batch_size; ++i)
|
||||||
|
preprocess_buffers_.push_back(make_shared<trt::Memory<unsigned char>>());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void preprocess(int ibatch, const Image &image,
|
||||||
|
shared_ptr<trt::Memory<unsigned char>> preprocess_buffer, AffineMatrix &affine,
|
||||||
|
void *stream = nullptr) {
|
||||||
|
affine.compute(make_tuple(image.width, image.height),
|
||||||
|
make_tuple(network_input_width_, network_input_height_));
|
||||||
|
|
||||||
|
size_t input_numel = network_input_width_ * network_input_height_ * 3;
|
||||||
|
float *input_device = input_buffer_.gpu() + ibatch * input_numel;
|
||||||
|
size_t size_image = image.width * image.height * 3;
|
||||||
|
size_t size_matrix = upbound(sizeof(affine.d2i), 32);
|
||||||
|
uint8_t *gpu_workspace = preprocess_buffer->gpu(size_matrix + size_image);
|
||||||
|
float *affine_matrix_device = (float *)gpu_workspace;
|
||||||
|
uint8_t *image_device = gpu_workspace + size_matrix;
|
||||||
|
|
||||||
|
uint8_t *cpu_workspace = preprocess_buffer->cpu(size_matrix + size_image);
|
||||||
|
float *affine_matrix_host = (float *)cpu_workspace;
|
||||||
|
uint8_t *image_host = cpu_workspace + size_matrix;
|
||||||
|
|
||||||
|
// speed up
|
||||||
|
cudaStream_t stream_ = (cudaStream_t)stream;
|
||||||
|
memcpy(image_host, image.bgrptr, size_image);
|
||||||
|
memcpy(affine_matrix_host, affine.d2i, sizeof(affine.d2i));
|
||||||
|
checkRuntime(
|
||||||
|
cudaMemcpyAsync(image_device, image_host, size_image, cudaMemcpyHostToDevice, stream_));
|
||||||
|
checkRuntime(cudaMemcpyAsync(affine_matrix_device, affine_matrix_host, sizeof(affine.d2i),
|
||||||
|
cudaMemcpyHostToDevice, stream_));
|
||||||
|
|
||||||
|
warp_affine_bilinear_and_normalize_plane(image_device, image.width * 3, image.width,
|
||||||
|
image.height, input_device, network_input_width_,
|
||||||
|
network_input_height_, affine_matrix_device, 114,
|
||||||
|
normalize_, stream_);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool load(const string &engine_file, Type type, float confidence_threshold, float nms_threshold) {
|
||||||
|
trt_ = trt::load(engine_file);
|
||||||
|
if (trt_ == nullptr) return false;
|
||||||
|
|
||||||
|
trt_->print();
|
||||||
|
|
||||||
|
this->type_ = type;
|
||||||
|
this->confidence_threshold_ = confidence_threshold;
|
||||||
|
this->nms_threshold_ = nms_threshold;
|
||||||
|
|
||||||
|
auto input_dim = trt_->static_dims(0);
|
||||||
|
bbox_head_dims_ = trt_->static_dims(1);
|
||||||
|
has_segment_ = type == Type::V8Seg;
|
||||||
|
if (has_segment_) {
|
||||||
|
bbox_head_dims_ = trt_->static_dims(2);
|
||||||
|
segment_head_dims_ = trt_->static_dims(1);
|
||||||
|
}
|
||||||
|
network_input_width_ = input_dim[3];
|
||||||
|
network_input_height_ = input_dim[2];
|
||||||
|
isdynamic_model_ = trt_->has_dynamic_dim();
|
||||||
|
|
||||||
|
if (type == Type::V5 || type == Type::V3 || type == Type::V7) {
|
||||||
|
normalize_ = Norm::alpha_beta(1 / 255.0f, 0.0f, ChannelType::SwapRB);
|
||||||
|
num_classes_ = bbox_head_dims_[2] - 5;
|
||||||
|
} else if (type == Type::V8) {
|
||||||
|
normalize_ = Norm::alpha_beta(1 / 255.0f, 0.0f, ChannelType::SwapRB);
|
||||||
|
num_classes_ = bbox_head_dims_[2] - 4;
|
||||||
|
} else if (type == Type::V8Seg) {
|
||||||
|
normalize_ = Norm::alpha_beta(1 / 255.0f, 0.0f, ChannelType::SwapRB);
|
||||||
|
num_classes_ = bbox_head_dims_[2] - 4 - segment_head_dims_[1];
|
||||||
|
} else if (type == Type::X) {
|
||||||
|
// float mean[] = {0.485, 0.456, 0.406};
|
||||||
|
// float std[] = {0.229, 0.224, 0.225};
|
||||||
|
// normalize_ = Norm::mean_std(mean, std, 1/255.0f, ChannelType::SwapRB);
|
||||||
|
normalize_ = Norm::None();
|
||||||
|
num_classes_ = bbox_head_dims_[2] - 5;
|
||||||
|
} else {
|
||||||
|
INFO("Unsupport type %d", type);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual BoxArray forward(const Image &image, void *stream = nullptr) override {
|
||||||
|
auto output = forwards({image}, stream);
|
||||||
|
if (output.empty()) return {};
|
||||||
|
return output[0];
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual vector<BoxArray> forwards(const vector<Image> &images, void *stream = nullptr) override {
|
||||||
|
int num_image = images.size();
|
||||||
|
if (num_image == 0) return {};
|
||||||
|
|
||||||
|
auto input_dims = trt_->static_dims(0);
|
||||||
|
int infer_batch_size = input_dims[0];
|
||||||
|
if (infer_batch_size != num_image) {
|
||||||
|
if (isdynamic_model_) {
|
||||||
|
infer_batch_size = num_image;
|
||||||
|
input_dims[0] = num_image;
|
||||||
|
if (!trt_->set_run_dims(0, input_dims)) return {};
|
||||||
|
} else {
|
||||||
|
if (infer_batch_size < num_image) {
|
||||||
|
INFO(
|
||||||
|
"When using static shape model, number of images[%d] must be "
|
||||||
|
"less than or equal to the maximum batch[%d].",
|
||||||
|
num_image, infer_batch_size);
|
||||||
|
return {};
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
adjust_memory(infer_batch_size);
|
||||||
|
|
||||||
|
vector<AffineMatrix> affine_matrixs(num_image);
|
||||||
|
cudaStream_t stream_ = (cudaStream_t)stream;
|
||||||
|
for (int i = 0; i < num_image; ++i)
|
||||||
|
preprocess(i, images[i], preprocess_buffers_[i], affine_matrixs[i], stream);
|
||||||
|
|
||||||
|
float *bbox_output_device = bbox_predict_.gpu();
|
||||||
|
vector<void *> bindings{input_buffer_.gpu(), bbox_output_device};
|
||||||
|
|
||||||
|
if (has_segment_) {
|
||||||
|
bindings = {input_buffer_.gpu(), segment_predict_.gpu(), bbox_output_device};
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!trt_->forward(bindings, stream)) {
|
||||||
|
INFO("Failed to tensorRT forward.");
|
||||||
|
return {};
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int ib = 0; ib < num_image; ++ib) {
|
||||||
|
float *boxarray_device =
|
||||||
|
output_boxarray_.gpu() + ib * (32 + MAX_IMAGE_BOXES * NUM_BOX_ELEMENT);
|
||||||
|
float *affine_matrix_device = (float *)preprocess_buffers_[ib]->gpu();
|
||||||
|
float *image_based_bbox_output =
|
||||||
|
bbox_output_device + ib * (bbox_head_dims_[1] * bbox_head_dims_[2]);
|
||||||
|
checkRuntime(cudaMemsetAsync(boxarray_device, 0, sizeof(int), stream_));
|
||||||
|
decode_kernel_invoker(image_based_bbox_output, bbox_head_dims_[1], num_classes_,
|
||||||
|
bbox_head_dims_[2], confidence_threshold_, nms_threshold_,
|
||||||
|
affine_matrix_device, boxarray_device, MAX_IMAGE_BOXES, type_, stream_);
|
||||||
|
}
|
||||||
|
checkRuntime(cudaMemcpyAsync(output_boxarray_.cpu(), output_boxarray_.gpu(),
|
||||||
|
output_boxarray_.gpu_bytes(), cudaMemcpyDeviceToHost, stream_));
|
||||||
|
checkRuntime(cudaStreamSynchronize(stream_));
|
||||||
|
|
||||||
|
vector<BoxArray> arrout(num_image);
|
||||||
|
int imemory = 0;
|
||||||
|
for (int ib = 0; ib < num_image; ++ib) {
|
||||||
|
float *parray = output_boxarray_.cpu() + ib * (32 + MAX_IMAGE_BOXES * NUM_BOX_ELEMENT);
|
||||||
|
int count = min(MAX_IMAGE_BOXES, (int)*parray);
|
||||||
|
BoxArray &output = arrout[ib];
|
||||||
|
output.reserve(count);
|
||||||
|
for (int i = 0; i < count; ++i) {
|
||||||
|
float *pbox = parray + 1 + i * NUM_BOX_ELEMENT;
|
||||||
|
int label = pbox[5];
|
||||||
|
int keepflag = pbox[6];
|
||||||
|
if (keepflag == 1) {
|
||||||
|
Box result_object_box(pbox[0], pbox[1], pbox[2], pbox[3], pbox[4], label);
|
||||||
|
if (has_segment_) {
|
||||||
|
int row_index = pbox[7];
|
||||||
|
int mask_dim = segment_head_dims_[1];
|
||||||
|
float *mask_weights = bbox_output_device +
|
||||||
|
(ib * bbox_head_dims_[1] + row_index) * bbox_head_dims_[2] +
|
||||||
|
num_classes_ + 4;
|
||||||
|
|
||||||
|
float *mask_head_predict = segment_predict_.gpu();
|
||||||
|
float left, top, right, bottom;
|
||||||
|
float *i2d = affine_matrixs[ib].i2d;
|
||||||
|
affine_project(i2d, pbox[0], pbox[1], &left, &top);
|
||||||
|
affine_project(i2d, pbox[2], pbox[3], &right, &bottom);
|
||||||
|
if(left < 0) left = 0;
|
||||||
|
if(top < 0) top = 0;
|
||||||
|
|
||||||
|
float box_width = right - left;
|
||||||
|
float box_height = bottom - top;
|
||||||
|
|
||||||
|
float scale_to_predict_x = segment_head_dims_[3] / (float)network_input_width_;
|
||||||
|
float scale_to_predict_y = segment_head_dims_[2] / (float)network_input_height_;
|
||||||
|
int mask_out_width = box_width * scale_to_predict_x + 0.5f;
|
||||||
|
int mask_out_height = box_height * scale_to_predict_y + 0.5f;
|
||||||
|
|
||||||
|
if (mask_out_width > 0 && mask_out_height > 0) {
|
||||||
|
if (imemory >= (int)box_segment_cache_.size()) {
|
||||||
|
box_segment_cache_.push_back(std::make_shared<trt::Memory<unsigned char>>());
|
||||||
|
}
|
||||||
|
|
||||||
|
int bytes_of_mask_out = mask_out_width * mask_out_height;
|
||||||
|
auto box_segment_output_memory = box_segment_cache_[imemory];
|
||||||
|
result_object_box.seg =
|
||||||
|
make_shared<InstanceSegmentMap>(mask_out_width, mask_out_height);
|
||||||
|
|
||||||
|
unsigned char *mask_out_device = box_segment_output_memory->gpu(bytes_of_mask_out);
|
||||||
|
unsigned char *mask_out_host = result_object_box.seg->data;
|
||||||
|
decode_single_mask(left * scale_to_predict_x, top * scale_to_predict_y, mask_weights,
|
||||||
|
mask_head_predict + ib * segment_head_dims_[1] *
|
||||||
|
segment_head_dims_[2] *
|
||||||
|
segment_head_dims_[3],
|
||||||
|
segment_head_dims_[3], segment_head_dims_[2], mask_out_device,
|
||||||
|
mask_dim, mask_out_width, mask_out_height, stream_);
|
||||||
|
checkRuntime(cudaMemcpyAsync(mask_out_host, mask_out_device,
|
||||||
|
box_segment_output_memory->gpu_bytes(),
|
||||||
|
cudaMemcpyDeviceToHost, stream_));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
output.emplace_back(result_object_box);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (has_segment_) checkRuntime(cudaStreamSynchronize(stream_));
|
||||||
|
|
||||||
|
return arrout;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
Infer *loadraw(const std::string &engine_file, Type type, float confidence_threshold,
|
||||||
|
float nms_threshold) {
|
||||||
|
InferImpl *impl = new InferImpl();
|
||||||
|
if (!impl->load(engine_file, type, confidence_threshold, nms_threshold)) {
|
||||||
|
delete impl;
|
||||||
|
impl = nullptr;
|
||||||
|
}
|
||||||
|
return impl;
|
||||||
|
}
|
||||||
|
|
||||||
|
shared_ptr<Infer> load(const string &engine_file, Type type, float confidence_threshold,
|
||||||
|
float nms_threshold) {
|
||||||
|
return std::shared_ptr<InferImpl>(
|
||||||
|
(InferImpl *)loadraw(engine_file, type, confidence_threshold, nms_threshold));
|
||||||
|
}
|
||||||
|
|
||||||
|
std::tuple<uint8_t, uint8_t, uint8_t> hsv2bgr(float h, float s, float v) {
|
||||||
|
const int h_i = static_cast<int>(h * 6);
|
||||||
|
const float f = h * 6 - h_i;
|
||||||
|
const float p = v * (1 - s);
|
||||||
|
const float q = v * (1 - f * s);
|
||||||
|
const float t = v * (1 - (1 - f) * s);
|
||||||
|
float r, g, b;
|
||||||
|
switch (h_i) {
|
||||||
|
case 0:
|
||||||
|
r = v, g = t, b = p;
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
r = q, g = v, b = p;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
r = p, g = v, b = t;
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
r = p, g = q, b = v;
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
r = t, g = p, b = v;
|
||||||
|
break;
|
||||||
|
case 5:
|
||||||
|
r = v, g = p, b = q;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
r = 1, g = 1, b = 1;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
return make_tuple(static_cast<uint8_t>(b * 255), static_cast<uint8_t>(g * 255),
|
||||||
|
static_cast<uint8_t>(r * 255));
|
||||||
|
}
|
||||||
|
|
||||||
|
std::tuple<uint8_t, uint8_t, uint8_t> random_color(int id) {
|
||||||
|
float h_plane = ((((unsigned int)id << 2) ^ 0x937151) % 100) / 100.0f;
|
||||||
|
float s_plane = ((((unsigned int)id << 3) ^ 0x315793) % 100) / 100.0f;
|
||||||
|
return hsv2bgr(h_plane, s_plane, 1);
|
||||||
|
}
|
|
@ -0,0 +1,32 @@
|
||||||
|
string(REPLACE ${PROJECT_SOURCE_DIR}/ "" _rel_path ${CMAKE_CURRENT_LIST_DIR})
|
||||||
|
|
||||||
|
# Add additional include directories to allow file to include rosbag headers
|
||||||
|
include(${_rel_path}/realsense-file/config.cmake)
|
||||||
|
|
||||||
|
include(${_rel_path}/sqlite/CMakeLists.txt)
|
||||||
|
|
||||||
|
if(BUILD_EASYLOGGINGPP)
|
||||||
|
include(${_rel_path}/easyloggingpp/CMakeLists.txt)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
add_subdirectory(${_rel_path}/realsense-file)
|
||||||
|
|
||||||
|
if(BUILD_NETWORK_DEVICE)
|
||||||
|
|
||||||
|
add_subdirectory(${_rel_path}/live555)
|
||||||
|
|
||||||
|
include(ExternalProject)
|
||||||
|
|
||||||
|
### libjpeg-turbo ###################################################
|
||||||
|
ExternalProject_Add (libjpeg-turbo
|
||||||
|
PREFIX libjpeg-turbo
|
||||||
|
GIT_REPOSITORY "https://github.com/libjpeg-turbo/libjpeg-turbo.git"
|
||||||
|
GIT_TAG "main"
|
||||||
|
SOURCE_DIR "${CMAKE_BINARY_DIR}/third-party/libjpeg-turbo"
|
||||||
|
CMAKE_ARGS "-DCMAKE_INSTALL_PREFIX=${CMAKE_BINARY_DIR}/libjpeg-turbo"
|
||||||
|
"-DCMAKE_GENERATOR=${CMAKE_GENERATOR}"
|
||||||
|
"-DCMAKE_POSITION_INDEPENDENT_CODE=ON"
|
||||||
|
"-DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE}"
|
||||||
|
)
|
||||||
|
|
||||||
|
endif()
|
|
@ -0,0 +1,504 @@
|
||||||
|
#ifndef ARCBALL_CAMERA_H
|
||||||
|
#define ARCBALL_CAMERA_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif // __cplusplus
|
||||||
|
|
||||||
|
// Flags for tweaking the view matrix
|
||||||
|
#define ARCBALL_CAMERA_LEFT_HANDED_BIT 1
|
||||||
|
|
||||||
|
// * eye:
|
||||||
|
// * Current eye position. Will be updated to new eye position.
|
||||||
|
// * target:
|
||||||
|
// * Current look target position. Will be updated to new position.
|
||||||
|
// * up:
|
||||||
|
// * Camera's "up" direction. Will be updated to new up vector.
|
||||||
|
// * view (optional):
|
||||||
|
// * The matrix that will be updated with the new view transform. Previous contents don't matter.
|
||||||
|
// * delta_time_seconds:
|
||||||
|
// * Amount of seconds passed since last update.
|
||||||
|
// * zoom_per_tick:
|
||||||
|
// * How much the camera should zoom with every scroll wheel tick.
|
||||||
|
// * pan_speed:
|
||||||
|
// * How fast the camera should pan when holding middle click.
|
||||||
|
// * rotation_multiplier:
|
||||||
|
// * For amplifying the rotation speed. 1.0 means 1-1 mapping between arcball rotation and camera rotation.
|
||||||
|
// * screen_width/screen_height:
|
||||||
|
// * Dimensions of the screen the camera is being used in (the window size).
|
||||||
|
// * x0, x1:
|
||||||
|
// * Previous and current x coordinate of the mouse, respectively.
|
||||||
|
// * y0, y1:
|
||||||
|
// * Previous and current y coordinate of the mouse, respectively.
|
||||||
|
// * midclick_held:
|
||||||
|
// * Whether the middle click button is currently held or not.
|
||||||
|
// * rclick_held:
|
||||||
|
// * Whether the right click button is currently held or not.
|
||||||
|
// * delta_scroll_ticks:
|
||||||
|
// * How many scroll wheel ticks passed since the last update (signed number)
|
||||||
|
// * flags:
|
||||||
|
// * For producing a different view matrix depending on your conventions.
|
||||||
|
void arcball_camera_update(
|
||||||
|
float eye[3],
|
||||||
|
float target[3],
|
||||||
|
float up[3],
|
||||||
|
float view[16],
|
||||||
|
float delta_time_seconds,
|
||||||
|
float zoom_per_tick,
|
||||||
|
float pan_speed,
|
||||||
|
float rotation_multiplier,
|
||||||
|
int screen_width, int screen_height,
|
||||||
|
int x0, int x1,
|
||||||
|
int y0, int y1,
|
||||||
|
int midclick_held,
|
||||||
|
int rclick_held,
|
||||||
|
int delta_scroll_ticks,
|
||||||
|
unsigned int flags);
|
||||||
|
|
||||||
|
// Utility for producing a look-to matrix without having to update a camera.
|
||||||
|
void arcball_camera_look_to(
|
||||||
|
const float eye[3],
|
||||||
|
const float look[3],
|
||||||
|
const float up[3],
|
||||||
|
float view[16],
|
||||||
|
unsigned int flags);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif // __cplusplus
|
||||||
|
|
||||||
|
#endif // ARCBALL_CAMERA_H
|
||||||
|
|
||||||
|
#ifdef ARCBALL_CAMERA_IMPLEMENTATION
|
||||||
|
|
||||||
|
#include <math.h>
|
||||||
|
#include <assert.h>
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif // __cplusplus
|
||||||
|
|
||||||
|
void arcball_camera_update(
|
||||||
|
float eye[3],
|
||||||
|
float target[3],
|
||||||
|
float up[3],
|
||||||
|
float view[16],
|
||||||
|
float delta_time_seconds,
|
||||||
|
float zoom_per_tick,
|
||||||
|
float pan_speed,
|
||||||
|
float rotation_multiplier,
|
||||||
|
int screen_width, int screen_height,
|
||||||
|
int px_x0, int px_x1,
|
||||||
|
int px_y0, int px_y1,
|
||||||
|
int midclick_held,
|
||||||
|
int rclick_held,
|
||||||
|
int delta_scroll_ticks,
|
||||||
|
unsigned int flags)
|
||||||
|
{
|
||||||
|
// check preconditions
|
||||||
|
{
|
||||||
|
float up_len = sqrtf(up[0] * up[0] + up[1] * up[1] + up[2] * up[2]);
|
||||||
|
assert(fabsf(up_len - 1.0f) < 0.000001f);
|
||||||
|
|
||||||
|
float to_target[3] = {
|
||||||
|
target[0] - eye[0],
|
||||||
|
target[1] - eye[1],
|
||||||
|
target[2] - eye[2],
|
||||||
|
};
|
||||||
|
float to_target_len = sqrtf(to_target[0] * to_target[0] + to_target[1] * to_target[1] + to_target[2] * to_target[2]);
|
||||||
|
assert(to_target_len > 1e-6);
|
||||||
|
}
|
||||||
|
|
||||||
|
// right click is held, then mouse movements implement rotation.
|
||||||
|
if (rclick_held)
|
||||||
|
{
|
||||||
|
float x0 = (float)(px_x0 - screen_width / 2);
|
||||||
|
float x1 = (float)(px_x1 - screen_width / 2);
|
||||||
|
float y0 = (float)((screen_height - px_y0 - 1) - screen_height / 2);
|
||||||
|
float y1 = (float)((screen_height - px_y1 - 1) - screen_height / 2);
|
||||||
|
float arcball_radius = (float)(screen_width > screen_height ? screen_width : screen_height);
|
||||||
|
|
||||||
|
// distances to center of arcball
|
||||||
|
float dist0 = sqrtf(x0 * x0 + y0 * y0);
|
||||||
|
float dist1 = sqrtf(x1 * x1 + y1 * y1);
|
||||||
|
|
||||||
|
float z0;
|
||||||
|
if (dist0 > arcball_radius)
|
||||||
|
{
|
||||||
|
// initial click was not on the arcball, so just do nothing.
|
||||||
|
goto end_rotate;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// compute depth of intersection using good old pythagoras
|
||||||
|
z0 = sqrtf(arcball_radius * arcball_radius - x0 * x0 - y0 * y0);
|
||||||
|
}
|
||||||
|
|
||||||
|
float z1;
|
||||||
|
if (dist1 > arcball_radius)
|
||||||
|
{
|
||||||
|
// started inside the ball but went outside, so clamp it.
|
||||||
|
x1 = (x1 / dist1) * arcball_radius;
|
||||||
|
y1 = (y1 / dist1) * arcball_radius;
|
||||||
|
dist1 = arcball_radius;
|
||||||
|
z1 = 0.0f;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// compute depth of intersection using good old pythagoras
|
||||||
|
z1 = sqrtf(arcball_radius * arcball_radius - x1 * x1 - y1 * y1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// rotate intersection points according to where the eye is
|
||||||
|
{
|
||||||
|
float to_eye_unorm[3] = {
|
||||||
|
eye[0] - target[0],
|
||||||
|
eye[1] - target[1],
|
||||||
|
eye[2] - target[2]
|
||||||
|
};
|
||||||
|
float to_eye_len = sqrtf(to_eye_unorm[0] * to_eye_unorm[0] + to_eye_unorm[1] * to_eye_unorm[1] + to_eye_unorm[2] * to_eye_unorm[2]);
|
||||||
|
float to_eye[3] = {
|
||||||
|
to_eye_unorm[0] / to_eye_len,
|
||||||
|
to_eye_unorm[1] / to_eye_len,
|
||||||
|
to_eye_unorm[2] / to_eye_len
|
||||||
|
};
|
||||||
|
|
||||||
|
float across[3] = {
|
||||||
|
-(to_eye[1] * up[2] - to_eye[2] * up[1]),
|
||||||
|
-(to_eye[2] * up[0] - to_eye[0] * up[2]),
|
||||||
|
-(to_eye[0] * up[1] - to_eye[1] * up[0])
|
||||||
|
};
|
||||||
|
|
||||||
|
// matrix that transforms standard coordinates to be relative to the eye
|
||||||
|
float eye_m[9] = {
|
||||||
|
across[0], across[1], across[2],
|
||||||
|
up[0], up[1], up[2],
|
||||||
|
to_eye[0], to_eye[1], to_eye[2]
|
||||||
|
};
|
||||||
|
|
||||||
|
float new_p0[3] = {
|
||||||
|
eye_m[0] * x0 + eye_m[3] * y0 + eye_m[6] * z0,
|
||||||
|
eye_m[1] * x0 + eye_m[4] * y0 + eye_m[7] * z0,
|
||||||
|
eye_m[2] * x0 + eye_m[5] * y0 + eye_m[8] * z0,
|
||||||
|
};
|
||||||
|
|
||||||
|
float new_p1[3] = {
|
||||||
|
eye_m[0] * x1 + eye_m[3] * y1 + eye_m[6] * z1,
|
||||||
|
eye_m[1] * x1 + eye_m[4] * y1 + eye_m[7] * z1,
|
||||||
|
eye_m[2] * x1 + eye_m[5] * y1 + eye_m[8] * z1,
|
||||||
|
};
|
||||||
|
|
||||||
|
x0 = new_p0[0];
|
||||||
|
y0 = new_p0[1];
|
||||||
|
z0 = new_p0[2];
|
||||||
|
|
||||||
|
x1 = new_p1[0];
|
||||||
|
y1 = new_p1[1];
|
||||||
|
z1 = new_p1[2];
|
||||||
|
}
|
||||||
|
|
||||||
|
// compute quaternion between the two vectors (http://lolengine.net/blog/2014/02/24/quaternion-from-two-vectors-final)
|
||||||
|
float qw, qx, qy, qz;
|
||||||
|
{
|
||||||
|
float norm_u_norm_v = sqrtf((x0 * x0 + y0 * y0 + z0 * z0) * (x1 * x1 + y1 * y1 + z1 * z1));
|
||||||
|
qw = norm_u_norm_v + (x0 * x1 + y0 * y1 + z0 * z1);
|
||||||
|
|
||||||
|
if (qw < 1.e-6f * norm_u_norm_v)
|
||||||
|
{
|
||||||
|
/* If u and v are exactly opposite, rotate 180 degrees
|
||||||
|
* around an arbitrary orthogonal axis. Axis normalisation
|
||||||
|
* can happen later, when we normalise the quaternion. */
|
||||||
|
qw = 0.0f;
|
||||||
|
if (fabsf(x0) > fabsf(z0))
|
||||||
|
{
|
||||||
|
qx = -y0;
|
||||||
|
qy = x0;
|
||||||
|
qz = 0.0f;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
qx = 0.0f;
|
||||||
|
qy = -z0;
|
||||||
|
qz = y0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
/* Otherwise, build quaternion the standard way. */
|
||||||
|
qx = y0 * z1 - z0 * y1;
|
||||||
|
qy = z0 * x1 - x0 * z1;
|
||||||
|
qz = x0 * y1 - y0 * x1;
|
||||||
|
}
|
||||||
|
|
||||||
|
float q_len = sqrtf(qx * qx + qy * qy + qz * qz + qw * qw);
|
||||||
|
qx /= q_len;
|
||||||
|
qy /= q_len;
|
||||||
|
qz /= q_len;
|
||||||
|
qw /= q_len;
|
||||||
|
}
|
||||||
|
|
||||||
|
// amplify the quaternion's rotation by the multiplier
|
||||||
|
// this is done by slerp(Quaternion.identity, q, multiplier)
|
||||||
|
// math from http://number-none.com/product/Understanding%20Slerp,%20Then%20Not%20Using%20It/
|
||||||
|
{
|
||||||
|
// cos(angle) of the quaternion
|
||||||
|
float c = qw;
|
||||||
|
if (c > 0.9995f)
|
||||||
|
{
|
||||||
|
// if the angle is small, linearly interpolate and normalize.
|
||||||
|
qx = rotation_multiplier * qx;
|
||||||
|
qy = rotation_multiplier * qy;
|
||||||
|
qz = rotation_multiplier * qz;
|
||||||
|
qw = 1.0f + rotation_multiplier * (qw - 1.0f);
|
||||||
|
float q_len = sqrtf(qx * qx + qy * qy + qz * qz + qw * qw);
|
||||||
|
qx /= q_len;
|
||||||
|
qy /= q_len;
|
||||||
|
qz /= q_len;
|
||||||
|
qw /= q_len;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// clamp to domain of acos for robustness
|
||||||
|
if (c < -1.0f)
|
||||||
|
c = -1.0f;
|
||||||
|
else if (c > 1.0f)
|
||||||
|
c = 1.0f;
|
||||||
|
// angle of the initial rotation
|
||||||
|
float theta_0 = acosf(c);
|
||||||
|
// apply multiplier to rotation
|
||||||
|
float theta = theta_0 * rotation_multiplier;
|
||||||
|
|
||||||
|
// compute the quaternion normalized difference
|
||||||
|
float qx2 = qx;
|
||||||
|
float qy2 = qy;
|
||||||
|
float qz2 = qz;
|
||||||
|
float qw2 = qw - c;
|
||||||
|
float q2_len = sqrtf(qx2 * qx2 + qy2 * qy2 + qz2 * qz2 + qw2 * qw2);
|
||||||
|
qx2 /= q2_len;
|
||||||
|
qy2 /= q2_len;
|
||||||
|
qz2 /= q2_len;
|
||||||
|
qw2 /= q2_len;
|
||||||
|
|
||||||
|
// do the slerp
|
||||||
|
qx = qx2 * sinf(theta);
|
||||||
|
qy = qy2 * sinf(theta);
|
||||||
|
qz = qz2 * sinf(theta);
|
||||||
|
qw = cosf(theta) + qw2 * sinf(theta);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// vector from the target to the eye, which will be rotated according to the arcball's arc.
|
||||||
|
float to_eye[3] = { eye[0] - target[0], eye[1] - target[1], eye[2] - target[2] };
|
||||||
|
|
||||||
|
// convert quaternion to matrix (note: row major)
|
||||||
|
float qmat[9] = {
|
||||||
|
(1.0f - 2.0f * qy * qy - 2.0f * qz * qz), 2.0f * (qx * qy + qw * qz), 2.0f * (qx * qz - qw * qy),
|
||||||
|
2.0f * (qx * qy - qw * qz), (1.0f - 2.0f * qx * qx - 2.0f * qz * qz), 2.0f * (qy * qz + qw * qx),
|
||||||
|
2.0f * (qx * qz + qw * qy), 2.0f * (qy * qz - qw * qx), (1.0f - 2.0f * qx * qx - 2.0f * qy * qy)
|
||||||
|
};
|
||||||
|
|
||||||
|
// compute rotated vector
|
||||||
|
float to_eye2[3] = {
|
||||||
|
to_eye[0] * qmat[0] + to_eye[1] * qmat[1] + to_eye[2] * qmat[2],
|
||||||
|
to_eye[0] * qmat[3] + to_eye[1] * qmat[4] + to_eye[2] * qmat[5],
|
||||||
|
to_eye[0] * qmat[6] + to_eye[1] * qmat[7] + to_eye[2] * qmat[8]
|
||||||
|
};
|
||||||
|
|
||||||
|
// compute rotated up vector
|
||||||
|
float up2[3] = {
|
||||||
|
up[0] * qmat[0] + up[1] * qmat[1] + up[2] * qmat[2],
|
||||||
|
up[0] * qmat[3] + up[1] * qmat[4] + up[2] * qmat[5],
|
||||||
|
up[0] * qmat[6] + up[1] * qmat[7] + up[2] * qmat[8]
|
||||||
|
};
|
||||||
|
|
||||||
|
float up2_len = sqrtf(up2[0] * up2[0] + up2[1] * up2[1] + up2[2] * up2[2]);
|
||||||
|
up2[0] /= up2_len;
|
||||||
|
up2[1] /= up2_len;
|
||||||
|
up2[2] /= up2_len;
|
||||||
|
|
||||||
|
// update eye position
|
||||||
|
eye[0] = target[0] + to_eye2[0];
|
||||||
|
eye[1] = target[1] + to_eye2[1];
|
||||||
|
eye[2] = target[2] + to_eye2[2];
|
||||||
|
|
||||||
|
// update up vector
|
||||||
|
up[0] = up2[0];
|
||||||
|
up[1] = up2[1];
|
||||||
|
up[2] = up2[2];
|
||||||
|
}
|
||||||
|
end_rotate:
|
||||||
|
|
||||||
|
// if midclick is held, then mouse movements implement translation
|
||||||
|
if (midclick_held)
|
||||||
|
{
|
||||||
|
int dx = -(px_x0 - px_x1);
|
||||||
|
int dy = (px_y0 - px_y1);
|
||||||
|
|
||||||
|
float to_eye_unorm[3] = {
|
||||||
|
eye[0] - target[0],
|
||||||
|
eye[1] - target[1],
|
||||||
|
eye[2] - target[2]
|
||||||
|
};
|
||||||
|
float to_eye_len = sqrtf(to_eye_unorm[0] * to_eye_unorm[0] + to_eye_unorm[1] * to_eye_unorm[1] + to_eye_unorm[2] * to_eye_unorm[2]);
|
||||||
|
float to_eye[3] = {
|
||||||
|
to_eye_unorm[0] / to_eye_len,
|
||||||
|
to_eye_unorm[1] / to_eye_len,
|
||||||
|
to_eye_unorm[2] / to_eye_len
|
||||||
|
};
|
||||||
|
|
||||||
|
float across[3] = {
|
||||||
|
-(to_eye[1] * up[2] - to_eye[2] * up[1]),
|
||||||
|
-(to_eye[2] * up[0] - to_eye[0] * up[2]),
|
||||||
|
-(to_eye[0] * up[1] - to_eye[1] * up[0])
|
||||||
|
};
|
||||||
|
|
||||||
|
float pan_delta[3] = {
|
||||||
|
delta_time_seconds * pan_speed * (dx * across[0] + dy * up[0]),
|
||||||
|
delta_time_seconds * pan_speed * (dx * across[1] + dy * up[1]),
|
||||||
|
delta_time_seconds * pan_speed * (dx * across[2] + dy * up[2]),
|
||||||
|
};
|
||||||
|
|
||||||
|
eye[0] += pan_delta[0];
|
||||||
|
eye[1] += pan_delta[1];
|
||||||
|
eye[2] += pan_delta[2];
|
||||||
|
|
||||||
|
target[0] += pan_delta[0];
|
||||||
|
target[1] += pan_delta[1];
|
||||||
|
target[2] += pan_delta[2];
|
||||||
|
}
|
||||||
|
|
||||||
|
// compute how much scrolling happened
|
||||||
|
float zoom_dist = zoom_per_tick * delta_scroll_ticks;
|
||||||
|
|
||||||
|
// the direction that the eye will move when zoomed
|
||||||
|
float to_target[3] = {
|
||||||
|
target[0] - eye[0],
|
||||||
|
target[1] - eye[1],
|
||||||
|
target[2] - eye[2],
|
||||||
|
};
|
||||||
|
|
||||||
|
float to_target_len = sqrtf(to_target[0] * to_target[0] + to_target[1] * to_target[1] + to_target[2] * to_target[2]);
|
||||||
|
|
||||||
|
// if the zoom would get you too close, clamp it.
|
||||||
|
if (!rclick_held)
|
||||||
|
{
|
||||||
|
if (zoom_dist >= to_target_len - 0.00001f)
|
||||||
|
{
|
||||||
|
zoom_dist = to_target_len - 0.00001f;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// normalize the zoom direction
|
||||||
|
float look[3] = {
|
||||||
|
to_target[0] / to_target_len,
|
||||||
|
to_target[1] / to_target_len,
|
||||||
|
to_target[2] / to_target_len,
|
||||||
|
};
|
||||||
|
|
||||||
|
float eye_zoom[3] = {
|
||||||
|
look[0] * zoom_dist,
|
||||||
|
look[1] * zoom_dist,
|
||||||
|
look[2] * zoom_dist
|
||||||
|
};
|
||||||
|
|
||||||
|
eye[0] += eye_zoom[0];
|
||||||
|
eye[1] += eye_zoom[1];
|
||||||
|
eye[2] += eye_zoom[2];
|
||||||
|
|
||||||
|
if (rclick_held)
|
||||||
|
{
|
||||||
|
// affect target too if right click is held
|
||||||
|
// this allows you to move forward and backward (as opposed to zoom)
|
||||||
|
target[0] += eye_zoom[0];
|
||||||
|
target[1] += eye_zoom[1];
|
||||||
|
target[2] += eye_zoom[2];
|
||||||
|
}
|
||||||
|
|
||||||
|
arcball_camera_look_to(eye, look, up, view, flags);
|
||||||
|
}
|
||||||
|
|
||||||
|
void arcball_camera_look_to(
|
||||||
|
const float eye[3],
|
||||||
|
const float look[3],
|
||||||
|
const float up[3],
|
||||||
|
float view[16],
|
||||||
|
unsigned int flags)
|
||||||
|
{
|
||||||
|
if (!view)
|
||||||
|
return;
|
||||||
|
|
||||||
|
float look_len = sqrtf(look[0] * look[0] + look[1] * look[1] + look[2] * look[2]);
|
||||||
|
float up_len = sqrtf(up[0] * up[0] + up[1] * up[1] + up[2] * up[2]);
|
||||||
|
|
||||||
|
assert(fabsf(look_len - 1.0f) < 0.000001f);
|
||||||
|
assert(fabsf(up_len - 1.0f) < 0.000001f);
|
||||||
|
|
||||||
|
// up'' = normalize(up)
|
||||||
|
float up_norm[3] = { up[0] / up_len, up[1] / up_len, up[2] / up_len };
|
||||||
|
|
||||||
|
// f = normalize(look)
|
||||||
|
float f[3] = { look[0] / look_len, look[1] / look_len, look[2] / look_len };
|
||||||
|
|
||||||
|
// s = normalize(cross(f, up2))
|
||||||
|
float s[3] = {
|
||||||
|
f[1] * up_norm[2] - f[2] * up_norm[1],
|
||||||
|
f[2] * up_norm[0] - f[0] * up_norm[2],
|
||||||
|
f[0] * up_norm[1] - f[1] * up_norm[0]
|
||||||
|
};
|
||||||
|
float s_len = sqrtf(s[0] * s[0] + s[1] * s[1] + s[2] * s[2]);
|
||||||
|
s[0] /= s_len;
|
||||||
|
s[1] /= s_len;
|
||||||
|
s[2] /= s_len;
|
||||||
|
|
||||||
|
// u = normalize(cross(normalize(s), f))
|
||||||
|
float u[3] = {
|
||||||
|
s[1] * f[2] - s[2] * f[1],
|
||||||
|
s[2] * f[0] - s[0] * f[2],
|
||||||
|
s[0] * f[1] - s[1] * f[0]
|
||||||
|
};
|
||||||
|
float u_len = sqrtf(u[0] * u[0] + u[1] * u[1] + u[2] * u[2]);
|
||||||
|
u[0] /= u_len;
|
||||||
|
u[1] /= u_len;
|
||||||
|
u[2] /= u_len;
|
||||||
|
|
||||||
|
if (!(flags & ARCBALL_CAMERA_LEFT_HANDED_BIT))
|
||||||
|
{
|
||||||
|
// in a right-handed coordinate system, the camera's z looks away from the look direction.
|
||||||
|
// this gets flipped again later when you multiply by a right-handed projection matrix
|
||||||
|
// (notice the last row of gluPerspective, which makes it back into a left-handed system after perspective division)
|
||||||
|
f[0] = -f[0];
|
||||||
|
f[1] = -f[1];
|
||||||
|
f[2] = -f[2];
|
||||||
|
}
|
||||||
|
|
||||||
|
// t = [s;u;f] * -eye
|
||||||
|
float t[3] = {
|
||||||
|
s[0] * -eye[0] + s[1] * -eye[1] + s[2] * -eye[2],
|
||||||
|
u[0] * -eye[0] + u[1] * -eye[1] + u[2] * -eye[2],
|
||||||
|
f[0] * -eye[0] + f[1] * -eye[1] + f[2] * -eye[2]
|
||||||
|
};
|
||||||
|
|
||||||
|
// m = [s,t[0]; u,t[1]; -f,t[2]];
|
||||||
|
view[0] = s[0];
|
||||||
|
view[1] = u[0];
|
||||||
|
view[2] = f[0];
|
||||||
|
view[3] = 0.0f;
|
||||||
|
view[4] = s[1];
|
||||||
|
view[5] = u[1];
|
||||||
|
view[6] = f[1];
|
||||||
|
view[7] = 0.0f;
|
||||||
|
view[8] = s[2];
|
||||||
|
view[9] = u[2];
|
||||||
|
view[10] = f[2];
|
||||||
|
view[11] = 0.0f;
|
||||||
|
view[12] = t[0];
|
||||||
|
view[13] = t[1];
|
||||||
|
view[14] = t[2];
|
||||||
|
view[15] = 1.0f;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif // __cplusplus
|
||||||
|
|
||||||
|
#endif // ARCBALL_CAMERA_IMPLEMENTATION
|
|
@ -0,0 +1,23 @@
|
||||||
|
branches:
|
||||||
|
only:
|
||||||
|
- ci
|
||||||
|
- master
|
||||||
|
skip_tags: true
|
||||||
|
environment:
|
||||||
|
CFLAGS: /WX
|
||||||
|
matrix:
|
||||||
|
- BUILD_SHARED_LIBS: ON
|
||||||
|
- BUILD_SHARED_LIBS: OFF
|
||||||
|
matrix:
|
||||||
|
fast_finish: true
|
||||||
|
build_script:
|
||||||
|
- mkdir build
|
||||||
|
- cd build
|
||||||
|
- cmake -DCMAKE_VERBOSE_MAKEFILE=ON -DBUILD_SHARED_LIBS=%BUILD_SHARED_LIBS% ..
|
||||||
|
- cmake --build .
|
||||||
|
notifications:
|
||||||
|
- provider: Email
|
||||||
|
to:
|
||||||
|
- ci@glfw.org
|
||||||
|
on_build_failure: true
|
||||||
|
on_build_success: false
|
|
@ -0,0 +1 @@
|
||||||
|
*.m linguist-language=Objective-C
|
|
@ -0,0 +1,84 @@
|
||||||
|
# External junk
|
||||||
|
.DS_Store
|
||||||
|
_ReSharper*
|
||||||
|
*.opensdf
|
||||||
|
*.sdf
|
||||||
|
*.suo
|
||||||
|
*.dir
|
||||||
|
*.vcxproj*
|
||||||
|
*.sln
|
||||||
|
Win32
|
||||||
|
x64
|
||||||
|
Debug
|
||||||
|
Release
|
||||||
|
MinSizeRel
|
||||||
|
RelWithDebInfo
|
||||||
|
*.xcodeproj
|
||||||
|
|
||||||
|
# CMake files
|
||||||
|
Makefile
|
||||||
|
CMakeCache.txt
|
||||||
|
CMakeFiles
|
||||||
|
CMakeScripts
|
||||||
|
cmake_install.cmake
|
||||||
|
cmake_uninstall.cmake
|
||||||
|
|
||||||
|
# Generated files
|
||||||
|
docs/Doxyfile
|
||||||
|
docs/html
|
||||||
|
docs/warnings.txt
|
||||||
|
docs/doxygen_sqlite3.db
|
||||||
|
src/glfw_config.h
|
||||||
|
src/glfw3.pc
|
||||||
|
src/glfw3Config.cmake
|
||||||
|
src/glfw3ConfigVersion.cmake
|
||||||
|
src/wayland-pointer-constraints-unstable-v1-client-protocol.h
|
||||||
|
src/wayland-pointer-constraints-unstable-v1-protocol.c
|
||||||
|
src/wayland-relative-pointer-unstable-v1-client-protocol.h
|
||||||
|
src/wayland-relative-pointer-unstable-v1-protocol.c
|
||||||
|
|
||||||
|
# Compiled binaries
|
||||||
|
src/libglfw.so
|
||||||
|
src/libglfw.so.3
|
||||||
|
src/libglfw.so.3.3
|
||||||
|
src/libglfw.dylib
|
||||||
|
src/libglfw.dylib
|
||||||
|
src/libglfw.3.dylib
|
||||||
|
src/libglfw.3.3.dylib
|
||||||
|
src/libglfw3.a
|
||||||
|
src/glfw3.lib
|
||||||
|
src/glfw3.dll
|
||||||
|
src/glfw3dll.lib
|
||||||
|
src/libglfw3dll.a
|
||||||
|
examples/*.app
|
||||||
|
examples/*.exe
|
||||||
|
examples/boing
|
||||||
|
examples/gears
|
||||||
|
examples/heightmap
|
||||||
|
examples/offscreen
|
||||||
|
examples/particles
|
||||||
|
examples/splitview
|
||||||
|
examples/sharing
|
||||||
|
examples/simple
|
||||||
|
examples/wave
|
||||||
|
tests/*.app
|
||||||
|
tests/*.exe
|
||||||
|
tests/clipboard
|
||||||
|
tests/cursor
|
||||||
|
tests/empty
|
||||||
|
tests/events
|
||||||
|
tests/gamma
|
||||||
|
tests/glfwinfo
|
||||||
|
tests/icon
|
||||||
|
tests/iconify
|
||||||
|
tests/joysticks
|
||||||
|
tests/monitors
|
||||||
|
tests/msaa
|
||||||
|
tests/reopen
|
||||||
|
tests/tearing
|
||||||
|
tests/threads
|
||||||
|
tests/timeout
|
||||||
|
tests/title
|
||||||
|
tests/vulkan
|
||||||
|
tests/windows
|
||||||
|
|
|
@ -0,0 +1,78 @@
|
||||||
|
language: c
|
||||||
|
compiler: clang
|
||||||
|
branches:
|
||||||
|
only:
|
||||||
|
- ci
|
||||||
|
- master
|
||||||
|
sudo: false
|
||||||
|
dist: trusty
|
||||||
|
addons:
|
||||||
|
apt:
|
||||||
|
packages:
|
||||||
|
- cmake
|
||||||
|
- libxrandr-dev
|
||||||
|
- libxinerama-dev
|
||||||
|
- libxcursor-dev
|
||||||
|
- libxi-dev
|
||||||
|
matrix:
|
||||||
|
include:
|
||||||
|
- os: linux
|
||||||
|
env:
|
||||||
|
- BUILD_SHARED_LIBS=ON
|
||||||
|
- CFLAGS=-Werror
|
||||||
|
- os: linux
|
||||||
|
env:
|
||||||
|
- BUILD_SHARED_LIBS=OFF
|
||||||
|
- CFLAGS=-Werror
|
||||||
|
- os: linux
|
||||||
|
sudo: required
|
||||||
|
addons:
|
||||||
|
apt:
|
||||||
|
packages:
|
||||||
|
- libwayland-dev
|
||||||
|
- libxkbcommon-dev
|
||||||
|
- libegl1-mesa-dev
|
||||||
|
env:
|
||||||
|
- USE_WAYLAND=ON
|
||||||
|
- BUILD_SHARED_LIBS=ON
|
||||||
|
- CFLAGS=-Werror
|
||||||
|
- os: linux
|
||||||
|
sudo: required
|
||||||
|
addons:
|
||||||
|
apt:
|
||||||
|
packages:
|
||||||
|
- libwayland-dev
|
||||||
|
- libxkbcommon-dev
|
||||||
|
- libegl1-mesa-dev
|
||||||
|
env:
|
||||||
|
- USE_WAYLAND=ON
|
||||||
|
- BUILD_SHARED_LIBS=OFF
|
||||||
|
- CFLAGS=-Werror
|
||||||
|
- os: osx
|
||||||
|
env:
|
||||||
|
- BUILD_SHARED_LIBS=ON
|
||||||
|
- CFLAGS=-Werror
|
||||||
|
- os: osx
|
||||||
|
env:
|
||||||
|
- BUILD_SHARED_LIBS=OFF
|
||||||
|
- CFLAGS=-Werror
|
||||||
|
script:
|
||||||
|
- if grep -Inr '\s$' src include docs tests examples CMake *.md .gitattributes .gitignore; then echo Trailing whitespace found, aborting.; exit 1; fi
|
||||||
|
- mkdir build
|
||||||
|
- cd build
|
||||||
|
- if test -n "${USE_WAYLAND}";
|
||||||
|
then wget https://mirrors.kernel.org/ubuntu/pool/universe/e/extra-cmake-modules/extra-cmake-modules_5.38.0a-0ubuntu1_amd64.deb;
|
||||||
|
sudo dpkg -i extra-cmake-modules_5.38.0a-0ubuntu1_amd64.deb;
|
||||||
|
git clone git://anongit.freedesktop.org/wayland/wayland-protocols;
|
||||||
|
pushd wayland-protocols;
|
||||||
|
git checkout 1.15 && ./autogen.sh --prefix=/usr && make && sudo make install;
|
||||||
|
popd;
|
||||||
|
fi
|
||||||
|
- cmake -DCMAKE_VERBOSE_MAKEFILE=ON -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} -DGLFW_USE_WAYLAND=${USE_WAYLAND} ..
|
||||||
|
- cmake --build .
|
||||||
|
notifications:
|
||||||
|
email:
|
||||||
|
recipients:
|
||||||
|
- ci@glfw.org
|
||||||
|
on_success: never
|
||||||
|
on_failure: always
|
|
@ -0,0 +1,33 @@
|
||||||
|
# Usage:
|
||||||
|
# cmake -P GenerateMappings.cmake <path/to/mappings.h.in> <path/to/mappings.h>
|
||||||
|
|
||||||
|
set(source_url "https://raw.githubusercontent.com/gabomdq/SDL_GameControllerDB/master/gamecontrollerdb.txt")
|
||||||
|
set(source_path "${CMAKE_CURRENT_BINARY_DIR}/gamecontrollerdb.txt")
|
||||||
|
set(template_path "${CMAKE_ARGV3}")
|
||||||
|
set(target_path "${CMAKE_ARGV4}")
|
||||||
|
|
||||||
|
if (NOT EXISTS "${template_path}")
|
||||||
|
message(FATAL_ERROR "Failed to find template file ${template_path}")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
file(DOWNLOAD "${source_url}" "${source_path}"
|
||||||
|
STATUS download_status
|
||||||
|
TLS_VERIFY on)
|
||||||
|
|
||||||
|
list(GET download_status 0 status_code)
|
||||||
|
list(GET download_status 1 status_message)
|
||||||
|
|
||||||
|
if (status_code)
|
||||||
|
message(FATAL_ERROR "Failed to download ${source_url}: ${status_message}")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
file(STRINGS "${source_path}" lines)
|
||||||
|
foreach(line ${lines})
|
||||||
|
if ("${line}" MATCHES "^[0-9a-fA-F].*$")
|
||||||
|
set(GLFW_GAMEPAD_MAPPINGS "${GLFW_GAMEPAD_MAPPINGS}\"${line}\",\n")
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
configure_file("${template_path}" "${target_path}" @ONLY NEWLINE_STYLE UNIX)
|
||||||
|
file(REMOVE "${source_path}")
|
||||||
|
|
|
@ -0,0 +1,38 @@
|
||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
|
||||||
|
<plist version="1.0">
|
||||||
|
<dict>
|
||||||
|
<key>CFBundleDevelopmentRegion</key>
|
||||||
|
<string>English</string>
|
||||||
|
<key>CFBundleExecutable</key>
|
||||||
|
<string>${MACOSX_BUNDLE_EXECUTABLE_NAME}</string>
|
||||||
|
<key>CFBundleGetInfoString</key>
|
||||||
|
<string>${MACOSX_BUNDLE_INFO_STRING}</string>
|
||||||
|
<key>CFBundleIconFile</key>
|
||||||
|
<string>${MACOSX_BUNDLE_ICON_FILE}</string>
|
||||||
|
<key>CFBundleIdentifier</key>
|
||||||
|
<string>${MACOSX_BUNDLE_GUI_IDENTIFIER}</string>
|
||||||
|
<key>CFBundleInfoDictionaryVersion</key>
|
||||||
|
<string>6.0</string>
|
||||||
|
<key>CFBundleLongVersionString</key>
|
||||||
|
<string>${MACOSX_BUNDLE_LONG_VERSION_STRING}</string>
|
||||||
|
<key>CFBundleName</key>
|
||||||
|
<string>${MACOSX_BUNDLE_BUNDLE_NAME}</string>
|
||||||
|
<key>CFBundlePackageType</key>
|
||||||
|
<string>APPL</string>
|
||||||
|
<key>CFBundleShortVersionString</key>
|
||||||
|
<string>${MACOSX_BUNDLE_SHORT_VERSION_STRING}</string>
|
||||||
|
<key>CFBundleSignature</key>
|
||||||
|
<string>????</string>
|
||||||
|
<key>CFBundleVersion</key>
|
||||||
|
<string>${MACOSX_BUNDLE_BUNDLE_VERSION}</string>
|
||||||
|
<key>CSResourcesFileMapped</key>
|
||||||
|
<true/>
|
||||||
|
<key>LSRequiresCarbon</key>
|
||||||
|
<true/>
|
||||||
|
<key>NSHumanReadableCopyright</key>
|
||||||
|
<string>${MACOSX_BUNDLE_COPYRIGHT}</string>
|
||||||
|
<key>NSHighResolutionCapable</key>
|
||||||
|
<true/>
|
||||||
|
</dict>
|
||||||
|
</plist>
|
|
@ -0,0 +1,13 @@
|
||||||
|
# Define the environment for cross compiling from Linux to Win64
|
||||||
|
SET(CMAKE_SYSTEM_NAME Windows)
|
||||||
|
SET(CMAKE_SYSTEM_VERSION 1)
|
||||||
|
SET(CMAKE_C_COMPILER "amd64-mingw32msvc-gcc")
|
||||||
|
SET(CMAKE_CXX_COMPILER "amd64-mingw32msvc-g++")
|
||||||
|
SET(CMAKE_RC_COMPILER "amd64-mingw32msvc-windres")
|
||||||
|
SET(CMAKE_RANLIB "amd64-mingw32msvc-ranlib")
|
||||||
|
|
||||||
|
# Configure the behaviour of the find commands
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH "/usr/amd64-mingw32msvc")
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
|
|
@ -0,0 +1,13 @@
|
||||||
|
# Define the environment for cross compiling from Linux to Win32
|
||||||
|
SET(CMAKE_SYSTEM_NAME Windows)
|
||||||
|
SET(CMAKE_SYSTEM_VERSION 1)
|
||||||
|
SET(CMAKE_C_COMPILER "i586-mingw32msvc-gcc")
|
||||||
|
SET(CMAKE_CXX_COMPILER "i586-mingw32msvc-g++")
|
||||||
|
SET(CMAKE_RC_COMPILER "i586-mingw32msvc-windres")
|
||||||
|
SET(CMAKE_RANLIB "i586-mingw32msvc-ranlib")
|
||||||
|
|
||||||
|
# Configure the behaviour of the find commands
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH "/usr/i586-mingw32msvc")
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
|
|
@ -0,0 +1,13 @@
|
||||||
|
# Define the environment for cross compiling from Linux to Win32
|
||||||
|
SET(CMAKE_SYSTEM_NAME Windows) # Target system name
|
||||||
|
SET(CMAKE_SYSTEM_VERSION 1)
|
||||||
|
SET(CMAKE_C_COMPILER "i686-pc-mingw32-gcc")
|
||||||
|
SET(CMAKE_CXX_COMPILER "i686-pc-mingw32-g++")
|
||||||
|
SET(CMAKE_RC_COMPILER "i686-pc-mingw32-windres")
|
||||||
|
SET(CMAKE_RANLIB "i686-pc-mingw32-ranlib")
|
||||||
|
|
||||||
|
#Configure the behaviour of the find commands
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH "/opt/mingw/usr/i686-pc-mingw32")
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
|
|
@ -0,0 +1,13 @@
|
||||||
|
# Define the environment for cross compiling from Linux to Win32
|
||||||
|
SET(CMAKE_SYSTEM_NAME Windows) # Target system name
|
||||||
|
SET(CMAKE_SYSTEM_VERSION 1)
|
||||||
|
SET(CMAKE_C_COMPILER "i686-w64-mingw32-gcc")
|
||||||
|
SET(CMAKE_CXX_COMPILER "i686-w64-mingw32-g++")
|
||||||
|
SET(CMAKE_RC_COMPILER "i686-w64-mingw32-windres")
|
||||||
|
SET(CMAKE_RANLIB "i686-w64-mingw32-ranlib")
|
||||||
|
|
||||||
|
# Configure the behaviour of the find commands
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH "/usr/i686-w64-mingw32")
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
|
|
@ -0,0 +1,17 @@
|
||||||
|
# Find EpollShim
|
||||||
|
# Once done, this will define
|
||||||
|
#
|
||||||
|
# EPOLLSHIM_FOUND - System has EpollShim
|
||||||
|
# EPOLLSHIM_INCLUDE_DIRS - The EpollShim include directories
|
||||||
|
# EPOLLSHIM_LIBRARIES - The libraries needed to use EpollShim
|
||||||
|
|
||||||
|
find_path(EPOLLSHIM_INCLUDE_DIRS NAMES sys/epoll.h sys/timerfd.h HINTS /usr/local/include/libepoll-shim)
|
||||||
|
find_library(EPOLLSHIM_LIBRARIES NAMES epoll-shim libepoll-shim HINTS /usr/local/lib)
|
||||||
|
|
||||||
|
if (EPOLLSHIM_INCLUDE_DIRS AND EPOLLSHIM_LIBRARIES)
|
||||||
|
set(EPOLLSHIM_FOUND TRUE)
|
||||||
|
endif (EPOLLSHIM_INCLUDE_DIRS AND EPOLLSHIM_LIBRARIES)
|
||||||
|
|
||||||
|
include(FindPackageHandleStandardArgs)
|
||||||
|
find_package_handle_standard_args(EPOLLSHIM DEFAULT_MSG EPOLLSHIM_LIBRARIES EPOLLSHIM_INCLUDE_DIRS)
|
||||||
|
mark_as_advanced(EPOLLSHIM_INCLUDE_DIRS EPOLLSHIM_LIBRARIES)
|
|
@ -0,0 +1,18 @@
|
||||||
|
# Try to find OSMesa on a Unix system
|
||||||
|
#
|
||||||
|
# This will define:
|
||||||
|
#
|
||||||
|
# OSMESA_LIBRARIES - Link these to use OSMesa
|
||||||
|
# OSMESA_INCLUDE_DIR - Include directory for OSMesa
|
||||||
|
#
|
||||||
|
# Copyright (c) 2014 Brandon Schaefer <brandon.schaefer@canonical.com>
|
||||||
|
|
||||||
|
if (NOT WIN32)
|
||||||
|
|
||||||
|
find_package (PkgConfig)
|
||||||
|
pkg_check_modules (PKG_OSMESA QUIET osmesa)
|
||||||
|
|
||||||
|
set (OSMESA_INCLUDE_DIR ${PKG_OSMESA_INCLUDE_DIRS})
|
||||||
|
set (OSMESA_LIBRARIES ${PKG_OSMESA_LIBRARIES})
|
||||||
|
|
||||||
|
endif ()
|
|
@ -0,0 +1,41 @@
|
||||||
|
# Find Vulkan
|
||||||
|
#
|
||||||
|
# VULKAN_INCLUDE_DIR
|
||||||
|
# VULKAN_LIBRARY
|
||||||
|
# VULKAN_FOUND
|
||||||
|
|
||||||
|
if (WIN32)
|
||||||
|
find_path(VULKAN_INCLUDE_DIR NAMES vulkan/vulkan.h HINTS
|
||||||
|
"$ENV{VULKAN_SDK}/Include"
|
||||||
|
"$ENV{VK_SDK_PATH}/Include")
|
||||||
|
if (CMAKE_SIZEOF_VOID_P EQUAL 8)
|
||||||
|
find_library(VULKAN_LIBRARY NAMES vulkan-1 HINTS
|
||||||
|
"$ENV{VULKAN_SDK}/Lib"
|
||||||
|
"$ENV{VULKAN_SDK}/Bin"
|
||||||
|
"$ENV{VK_SDK_PATH}/Bin")
|
||||||
|
find_library(VULKAN_STATIC_LIBRARY NAMES vkstatic.1 HINTS
|
||||||
|
"$ENV{VULKAN_SDK}/Lib"
|
||||||
|
"$ENV{VULKAN_SDK}/Bin"
|
||||||
|
"$ENV{VK_SDK_PATH}/Bin")
|
||||||
|
else()
|
||||||
|
find_library(VULKAN_LIBRARY NAMES vulkan-1 HINTS
|
||||||
|
"$ENV{VULKAN_SDK}/Lib32"
|
||||||
|
"$ENV{VULKAN_SDK}/Bin32"
|
||||||
|
"$ENV{VK_SDK_PATH}/Bin32")
|
||||||
|
find_library(VULKAN_STATIC_LIBRARY NAMES vkstatic.1 HINTS
|
||||||
|
"$ENV{VULKAN_SDK}/Lib32"
|
||||||
|
"$ENV{VULKAN_SDK}/Bin32"
|
||||||
|
"$ENV{VK_SDK_PATH}/Bin32")
|
||||||
|
endif()
|
||||||
|
else()
|
||||||
|
find_path(VULKAN_INCLUDE_DIR NAMES vulkan/vulkan.h HINTS
|
||||||
|
"$ENV{VULKAN_SDK}/include")
|
||||||
|
find_library(VULKAN_LIBRARY NAMES vulkan HINTS
|
||||||
|
"$ENV{VULKAN_SDK}/lib")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
include(FindPackageHandleStandardArgs)
|
||||||
|
find_package_handle_standard_args(Vulkan DEFAULT_MSG VULKAN_LIBRARY VULKAN_INCLUDE_DIR)
|
||||||
|
|
||||||
|
mark_as_advanced(VULKAN_INCLUDE_DIR VULKAN_LIBRARY VULKAN_STATIC_LIBRARY)
|
||||||
|
|
|
@ -0,0 +1,26 @@
|
||||||
|
find_package(PkgConfig)
|
||||||
|
|
||||||
|
pkg_check_modules(WaylandProtocols QUIET wayland-protocols>=${WaylandProtocols_FIND_VERSION})
|
||||||
|
|
||||||
|
execute_process(COMMAND ${PKG_CONFIG_EXECUTABLE} --variable=pkgdatadir wayland-protocols
|
||||||
|
OUTPUT_VARIABLE WaylandProtocols_PKGDATADIR
|
||||||
|
RESULT_VARIABLE _pkgconfig_failed)
|
||||||
|
if (_pkgconfig_failed)
|
||||||
|
message(FATAL_ERROR "Missing wayland-protocols pkgdatadir")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
string(REGEX REPLACE "[\r\n]" "" WaylandProtocols_PKGDATADIR "${WaylandProtocols_PKGDATADIR}")
|
||||||
|
|
||||||
|
find_package_handle_standard_args(WaylandProtocols
|
||||||
|
FOUND_VAR
|
||||||
|
WaylandProtocols_FOUND
|
||||||
|
REQUIRED_VARS
|
||||||
|
WaylandProtocols_PKGDATADIR
|
||||||
|
VERSION_VAR
|
||||||
|
WaylandProtocols_VERSION
|
||||||
|
HANDLE_COMPONENTS
|
||||||
|
)
|
||||||
|
|
||||||
|
set(WAYLAND_PROTOCOLS_FOUND ${WaylandProtocols_FOUND})
|
||||||
|
set(WAYLAND_PROTOCOLS_PKGDATADIR ${WaylandProtocols_PKGDATADIR})
|
||||||
|
set(WAYLAND_PROTOCOLS_VERSION ${WaylandProtocols_VERSION})
|
|
@ -0,0 +1,34 @@
|
||||||
|
# - Try to find XKBCommon
|
||||||
|
# Once done, this will define
|
||||||
|
#
|
||||||
|
# XKBCOMMON_FOUND - System has XKBCommon
|
||||||
|
# XKBCOMMON_INCLUDE_DIRS - The XKBCommon include directories
|
||||||
|
# XKBCOMMON_LIBRARIES - The libraries needed to use XKBCommon
|
||||||
|
# XKBCOMMON_DEFINITIONS - Compiler switches required for using XKBCommon
|
||||||
|
|
||||||
|
find_package(PkgConfig)
|
||||||
|
pkg_check_modules(PC_XKBCOMMON QUIET xkbcommon)
|
||||||
|
set(XKBCOMMON_DEFINITIONS ${PC_XKBCOMMON_CFLAGS_OTHER})
|
||||||
|
|
||||||
|
find_path(XKBCOMMON_INCLUDE_DIR
|
||||||
|
NAMES xkbcommon/xkbcommon.h
|
||||||
|
HINTS ${PC_XKBCOMMON_INCLUDE_DIR} ${PC_XKBCOMMON_INCLUDE_DIRS}
|
||||||
|
)
|
||||||
|
|
||||||
|
find_library(XKBCOMMON_LIBRARY
|
||||||
|
NAMES xkbcommon
|
||||||
|
HINTS ${PC_XKBCOMMON_LIBRARY} ${PC_XKBCOMMON_LIBRARY_DIRS}
|
||||||
|
)
|
||||||
|
|
||||||
|
set(XKBCOMMON_LIBRARIES ${XKBCOMMON_LIBRARY})
|
||||||
|
set(XKBCOMMON_LIBRARY_DIRS ${XKBCOMMON_LIBRARY_DIRS})
|
||||||
|
set(XKBCOMMON_INCLUDE_DIRS ${XKBCOMMON_INCLUDE_DIR})
|
||||||
|
|
||||||
|
include(FindPackageHandleStandardArgs)
|
||||||
|
find_package_handle_standard_args(XKBCommon DEFAULT_MSG
|
||||||
|
XKBCOMMON_LIBRARY
|
||||||
|
XKBCOMMON_INCLUDE_DIR
|
||||||
|
)
|
||||||
|
|
||||||
|
mark_as_advanced(XKBCOMMON_LIBRARY XKBCOMMON_INCLUDE_DIR)
|
||||||
|
|
|
@ -0,0 +1,13 @@
|
||||||
|
# Define the environment for cross compiling from Linux to Win32
|
||||||
|
SET(CMAKE_SYSTEM_NAME Windows) # Target system name
|
||||||
|
SET(CMAKE_SYSTEM_VERSION 1)
|
||||||
|
SET(CMAKE_C_COMPILER "x86_64-w64-mingw32-gcc")
|
||||||
|
SET(CMAKE_CXX_COMPILER "x86_64-w64-mingw32-g++")
|
||||||
|
SET(CMAKE_RC_COMPILER "x86_64-w64-mingw32-windres")
|
||||||
|
SET(CMAKE_RANLIB "x86_64-w64-mingw32-ranlib")
|
||||||
|
|
||||||
|
# Configure the behaviour of the find commands
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH "/usr/x86_64-w64-mingw32")
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
|
|
@ -0,0 +1,386 @@
|
||||||
|
cmake_minimum_required(VERSION 3.0)
|
||||||
|
|
||||||
|
project(GLFW C)
|
||||||
|
|
||||||
|
set(CMAKE_LEGACY_CYGWIN_WIN32 OFF)
|
||||||
|
|
||||||
|
if (POLICY CMP0054)
|
||||||
|
cmake_policy(SET CMP0054 NEW)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
set(GLFW_VERSION_MAJOR "3")
|
||||||
|
set(GLFW_VERSION_MINOR "3")
|
||||||
|
set(GLFW_VERSION_PATCH "0")
|
||||||
|
set(GLFW_VERSION_EXTRA "")
|
||||||
|
set(GLFW_VERSION "${GLFW_VERSION_MAJOR}.${GLFW_VERSION_MINOR}")
|
||||||
|
set(GLFW_VERSION_FULL "${GLFW_VERSION}.${GLFW_VERSION_PATCH}${GLFW_VERSION_EXTRA}")
|
||||||
|
|
||||||
|
set_property(GLOBAL PROPERTY USE_FOLDERS ON)
|
||||||
|
|
||||||
|
#option(BUILD_SHARED_LIBS "Build shared libraries" ON)
|
||||||
|
set(BUILD_SHARED_LIBS OFF)
|
||||||
|
option(GLFW_BUILD_EXAMPLES "Build the GLFW example programs" OFF)
|
||||||
|
option(GLFW_BUILD_TESTS "Build the GLFW test programs" OFF)
|
||||||
|
option(GLFW_BUILD_DOCS "Build the GLFW documentation" OFF)
|
||||||
|
option(GLFW_INSTALL "Generate installation target" OFF)
|
||||||
|
option(GLFW_VULKAN_STATIC "Use the Vulkan loader statically linked into application" OFF)
|
||||||
|
|
||||||
|
include(GNUInstallDirs)
|
||||||
|
|
||||||
|
if (UNIX)
|
||||||
|
option(GLFW_USE_OSMESA "Use OSMesa for offscreen context creation" OFF)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (WIN32)
|
||||||
|
option(GLFW_USE_HYBRID_HPG "Force use of high-performance GPU on hybrid systems" OFF)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (UNIX AND NOT APPLE)
|
||||||
|
option(GLFW_USE_WAYLAND "Use Wayland for window creation" OFF)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (MSVC)
|
||||||
|
option(USE_MSVC_RUNTIME_LIBRARY_DLL "Use MSVC runtime library DLL" ON)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (BUILD_SHARED_LIBS)
|
||||||
|
set(_GLFW_BUILD_DLL 1)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (BUILD_SHARED_LIBS AND UNIX)
|
||||||
|
# On Unix-like systems, shared libraries can use the soname system.
|
||||||
|
set(GLFW_LIB_NAME glfw)
|
||||||
|
else()
|
||||||
|
set(GLFW_LIB_NAME glfw3)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (GLFW_VULKAN_STATIC)
|
||||||
|
set(_GLFW_VULKAN_STATIC 1)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
list(APPEND CMAKE_MODULE_PATH "${GLFW_SOURCE_DIR}/CMake/modules")
|
||||||
|
|
||||||
|
find_package(Threads REQUIRED)
|
||||||
|
find_package(Vulkan)
|
||||||
|
|
||||||
|
if (GLFW_BUILD_DOCS)
|
||||||
|
set(DOXYGEN_SKIP_DOT TRUE)
|
||||||
|
find_package(Doxygen)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Set compiler specific flags
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (MSVC)
|
||||||
|
if (MSVC90)
|
||||||
|
# Workaround for VS 2008 not shipping with the DirectX 9 SDK
|
||||||
|
include(CheckIncludeFile)
|
||||||
|
check_include_file(dinput.h DINPUT_H_FOUND)
|
||||||
|
if (NOT DINPUT_H_FOUND)
|
||||||
|
message(FATAL_ERROR "DirectX 9 SDK not found")
|
||||||
|
endif()
|
||||||
|
# Workaround for VS 2008 not shipping with stdint.h
|
||||||
|
list(APPEND glfw_INCLUDE_DIRS "${GLFW_SOURCE_DIR}/deps/vs2008")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (NOT USE_MSVC_RUNTIME_LIBRARY_DLL)
|
||||||
|
foreach (flag CMAKE_C_FLAGS
|
||||||
|
CMAKE_C_FLAGS_DEBUG
|
||||||
|
CMAKE_C_FLAGS_RELEASE
|
||||||
|
CMAKE_C_FLAGS_MINSIZEREL
|
||||||
|
CMAKE_C_FLAGS_RELWITHDEBINFO)
|
||||||
|
|
||||||
|
if (${flag} MATCHES "/MD")
|
||||||
|
string(REGEX REPLACE "/MD" "/MT" ${flag} "${${flag}}")
|
||||||
|
endif()
|
||||||
|
if (${flag} MATCHES "/MDd")
|
||||||
|
string(REGEX REPLACE "/MDd" "/MTd" ${flag} "${${flag}}")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
endforeach()
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (MINGW)
|
||||||
|
# Workaround for legacy MinGW not providing XInput and DirectInput
|
||||||
|
include(CheckIncludeFile)
|
||||||
|
|
||||||
|
check_include_file(dinput.h DINPUT_H_FOUND)
|
||||||
|
check_include_file(xinput.h XINPUT_H_FOUND)
|
||||||
|
if (NOT DINPUT_H_FOUND OR NOT XINPUT_H_FOUND)
|
||||||
|
list(APPEND glfw_INCLUDE_DIRS "${GLFW_SOURCE_DIR}/deps/mingw")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Enable link-time exploit mitigation features enabled by default on MSVC
|
||||||
|
include(CheckCCompilerFlag)
|
||||||
|
|
||||||
|
# Compatibility with data execution prevention (DEP)
|
||||||
|
set(CMAKE_REQUIRED_FLAGS "-Wl,--nxcompat")
|
||||||
|
check_c_compiler_flag("" _GLFW_HAS_DEP)
|
||||||
|
if (_GLFW_HAS_DEP)
|
||||||
|
set(CMAKE_SHARED_LINKER_FLAGS "-Wl,--nxcompat ${CMAKE_SHARED_LINKER_FLAGS}")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Compatibility with address space layout randomization (ASLR)
|
||||||
|
set(CMAKE_REQUIRED_FLAGS "-Wl,--dynamicbase")
|
||||||
|
check_c_compiler_flag("" _GLFW_HAS_ASLR)
|
||||||
|
if (_GLFW_HAS_ASLR)
|
||||||
|
set(CMAKE_SHARED_LINKER_FLAGS "-Wl,--dynamicbase ${CMAKE_SHARED_LINKER_FLAGS}")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Compatibility with 64-bit address space layout randomization (ASLR)
|
||||||
|
set(CMAKE_REQUIRED_FLAGS "-Wl,--high-entropy-va")
|
||||||
|
check_c_compiler_flag("" _GLFW_HAS_64ASLR)
|
||||||
|
if (_GLFW_HAS_64ASLR)
|
||||||
|
set(CMAKE_SHARED_LINKER_FLAGS "-Wl,--high-entropy-va ${CMAKE_SHARED_LINKER_FLAGS}")
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Detect and select backend APIs
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (GLFW_USE_WAYLAND)
|
||||||
|
set(_GLFW_WAYLAND 1)
|
||||||
|
message(STATUS "Using Wayland for window creation")
|
||||||
|
elseif (GLFW_USE_OSMESA)
|
||||||
|
set(_GLFW_OSMESA 1)
|
||||||
|
message(STATUS "Using OSMesa for headless context creation")
|
||||||
|
elseif (WIN32)
|
||||||
|
set(_GLFW_WIN32 1)
|
||||||
|
message(STATUS "Using Win32 for window creation")
|
||||||
|
elseif (APPLE)
|
||||||
|
set(_GLFW_COCOA 1)
|
||||||
|
message(STATUS "Using Cocoa for window creation")
|
||||||
|
elseif (UNIX)
|
||||||
|
set(_GLFW_X11 1)
|
||||||
|
message(STATUS "Using X11 for window creation")
|
||||||
|
else()
|
||||||
|
message(FATAL_ERROR "No supported platform was detected")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Add Vulkan static library if requested
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (GLFW_VULKAN_STATIC)
|
||||||
|
if (VULKAN_FOUND AND VULKAN_STATIC_LIBRARY)
|
||||||
|
list(APPEND glfw_LIBRARIES "${VULKAN_STATIC_LIBRARY}")
|
||||||
|
if (BUILD_SHARED_LIBS)
|
||||||
|
message(WARNING "Linking Vulkan loader static library into GLFW")
|
||||||
|
endif()
|
||||||
|
else()
|
||||||
|
if (BUILD_SHARED_LIBS OR GLFW_BUILD_EXAMPLES OR GLFW_BUILD_TESTS)
|
||||||
|
message(FATAL_ERROR "Vulkan loader static library not found")
|
||||||
|
else()
|
||||||
|
message(WARNING "Vulkan loader static library not found")
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Find and add Unix math and time libraries
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (UNIX AND NOT APPLE)
|
||||||
|
find_library(RT_LIBRARY rt)
|
||||||
|
mark_as_advanced(RT_LIBRARY)
|
||||||
|
if (RT_LIBRARY)
|
||||||
|
list(APPEND glfw_LIBRARIES "${RT_LIBRARY}")
|
||||||
|
list(APPEND glfw_PKG_LIBS "-lrt")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
find_library(MATH_LIBRARY m)
|
||||||
|
mark_as_advanced(MATH_LIBRARY)
|
||||||
|
if (MATH_LIBRARY)
|
||||||
|
list(APPEND glfw_LIBRARIES "${MATH_LIBRARY}")
|
||||||
|
list(APPEND glfw_PKG_LIBS "-lm")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (CMAKE_DL_LIBS)
|
||||||
|
list(APPEND glfw_LIBRARIES "${CMAKE_DL_LIBS}")
|
||||||
|
list(APPEND glfw_PKG_LIBS "-l${CMAKE_DL_LIBS}")
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Use Win32 for window creation
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (_GLFW_WIN32)
|
||||||
|
|
||||||
|
list(APPEND glfw_PKG_LIBS "-lgdi32")
|
||||||
|
|
||||||
|
if (GLFW_USE_HYBRID_HPG)
|
||||||
|
set(_GLFW_USE_HYBRID_HPG 1)
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Use X11 for window creation
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (_GLFW_X11)
|
||||||
|
|
||||||
|
find_package(X11 REQUIRED)
|
||||||
|
|
||||||
|
list(APPEND glfw_PKG_DEPS "x11")
|
||||||
|
|
||||||
|
# Set up library and include paths
|
||||||
|
list(APPEND glfw_INCLUDE_DIRS "${X11_X11_INCLUDE_PATH}")
|
||||||
|
list(APPEND glfw_LIBRARIES "${X11_X11_LIB}" "${CMAKE_THREAD_LIBS_INIT}")
|
||||||
|
|
||||||
|
# Check for XRandR (modern resolution switching and gamma control)
|
||||||
|
if (NOT X11_Xrandr_FOUND)
|
||||||
|
message(FATAL_ERROR "The RandR headers were not found")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Check for Xinerama (legacy multi-monitor support)
|
||||||
|
if (NOT X11_Xinerama_FOUND)
|
||||||
|
message(FATAL_ERROR "The Xinerama headers were not found")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Check for Xkb (X keyboard extension)
|
||||||
|
if (NOT X11_Xkb_FOUND)
|
||||||
|
message(FATAL_ERROR "The X keyboard extension headers were not found")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Check for Xcursor (cursor creation from RGBA images)
|
||||||
|
if (NOT X11_Xcursor_FOUND)
|
||||||
|
message(FATAL_ERROR "The Xcursor headers were not found")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
list(APPEND glfw_INCLUDE_DIRS "${X11_Xrandr_INCLUDE_PATH}"
|
||||||
|
"${X11_Xinerama_INCLUDE_PATH}"
|
||||||
|
"${X11_Xkb_INCLUDE_PATH}"
|
||||||
|
"${X11_Xcursor_INCLUDE_PATH}")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Use Wayland for window creation
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (_GLFW_WAYLAND)
|
||||||
|
find_package(ECM REQUIRED NO_MODULE)
|
||||||
|
list(APPEND CMAKE_MODULE_PATH "${ECM_MODULE_PATH}")
|
||||||
|
|
||||||
|
find_package(Wayland REQUIRED Client Cursor Egl)
|
||||||
|
find_package(WaylandScanner REQUIRED)
|
||||||
|
find_package(WaylandProtocols 1.15 REQUIRED)
|
||||||
|
|
||||||
|
list(APPEND glfw_PKG_DEPS "wayland-egl")
|
||||||
|
|
||||||
|
list(APPEND glfw_INCLUDE_DIRS "${Wayland_INCLUDE_DIRS}")
|
||||||
|
list(APPEND glfw_LIBRARIES "${Wayland_LIBRARIES}" "${CMAKE_THREAD_LIBS_INIT}")
|
||||||
|
|
||||||
|
find_package(XKBCommon REQUIRED)
|
||||||
|
list(APPEND glfw_INCLUDE_DIRS "${XKBCOMMON_INCLUDE_DIRS}")
|
||||||
|
|
||||||
|
include(CheckIncludeFiles)
|
||||||
|
include(CheckFunctionExists)
|
||||||
|
check_include_files(xkbcommon/xkbcommon-compose.h HAVE_XKBCOMMON_COMPOSE_H)
|
||||||
|
check_function_exists(memfd_create HAVE_MEMFD_CREATE)
|
||||||
|
|
||||||
|
if (NOT ("${CMAKE_SYSTEM_NAME}" STREQUAL "Linux"))
|
||||||
|
find_package(EpollShim)
|
||||||
|
if (EPOLLSHIM_FOUND)
|
||||||
|
list(APPEND glfw_INCLUDE_DIRS "${EPOLLSHIM_INCLUDE_DIRS}")
|
||||||
|
list(APPEND glfw_LIBRARIES "${EPOLLSHIM_LIBRARIES}")
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Use OSMesa for offscreen context creation
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (_GLFW_OSMESA)
|
||||||
|
find_package(OSMesa REQUIRED)
|
||||||
|
list(APPEND glfw_LIBRARIES "${CMAKE_THREAD_LIBS_INIT}")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Use Cocoa for window creation and NSOpenGL for context creation
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (_GLFW_COCOA)
|
||||||
|
|
||||||
|
list(APPEND glfw_LIBRARIES
|
||||||
|
"-framework Cocoa"
|
||||||
|
"-framework IOKit"
|
||||||
|
"-framework CoreFoundation"
|
||||||
|
"-framework CoreVideo")
|
||||||
|
|
||||||
|
set(glfw_PKG_DEPS "")
|
||||||
|
set(glfw_PKG_LIBS "-framework Cocoa -framework IOKit -framework CoreFoundation -framework CoreVideo")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Export GLFW library dependencies
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
foreach(arg ${glfw_PKG_DEPS})
|
||||||
|
set(GLFW_PKG_DEPS "${GLFW_PKG_DEPS} ${arg}")
|
||||||
|
endforeach()
|
||||||
|
foreach(arg ${glfw_PKG_LIBS})
|
||||||
|
set(GLFW_PKG_LIBS "${GLFW_PKG_LIBS} ${arg}")
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Create generated files
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
include(CMakePackageConfigHelpers)
|
||||||
|
|
||||||
|
set(GLFW_CONFIG_PATH "${CMAKE_INSTALL_LIBDIR}/cmake/glfw3")
|
||||||
|
|
||||||
|
configure_package_config_file(src/glfw3Config.cmake.in
|
||||||
|
src/glfw3Config.cmake
|
||||||
|
INSTALL_DESTINATION "${GLFW_CONFIG_PATH}"
|
||||||
|
NO_CHECK_REQUIRED_COMPONENTS_MACRO)
|
||||||
|
|
||||||
|
write_basic_package_version_file(src/glfw3ConfigVersion.cmake
|
||||||
|
VERSION ${GLFW_VERSION_FULL}
|
||||||
|
COMPATIBILITY SameMajorVersion)
|
||||||
|
|
||||||
|
configure_file(src/glfw_config.h.in src/glfw_config.h @ONLY)
|
||||||
|
|
||||||
|
configure_file(src/glfw3.pc.in src/glfw3.pc @ONLY)
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Add subdirectories
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
add_subdirectory(src)
|
||||||
|
|
||||||
|
if (GLFW_BUILD_EXAMPLES)
|
||||||
|
add_subdirectory(examples)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (GLFW_BUILD_TESTS)
|
||||||
|
add_subdirectory(tests)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (DOXYGEN_FOUND AND GLFW_BUILD_DOCS)
|
||||||
|
add_subdirectory(docs)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
# Install files other than the library
|
||||||
|
# The library is installed by src/CMakeLists.txt
|
||||||
|
#--------------------------------------------------------------------
|
||||||
|
if (GLFW_INSTALL)
|
||||||
|
install(DIRECTORY include/GLFW DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}
|
||||||
|
FILES_MATCHING PATTERN glfw3.h PATTERN glfw3native.h)
|
||||||
|
|
||||||
|
install(FILES "${GLFW_BINARY_DIR}/src/glfw3Config.cmake"
|
||||||
|
"${GLFW_BINARY_DIR}/src/glfw3ConfigVersion.cmake"
|
||||||
|
DESTINATION "${GLFW_CONFIG_PATH}")
|
||||||
|
|
||||||
|
install(EXPORT glfwTargets FILE glfw3Targets.cmake
|
||||||
|
EXPORT_LINK_INTERFACE_LIBRARIES
|
||||||
|
DESTINATION "${GLFW_CONFIG_PATH}")
|
||||||
|
install(FILES "${GLFW_BINARY_DIR}/src/glfw3.pc"
|
||||||
|
DESTINATION "${CMAKE_INSTALL_LIBDIR}/pkgconfig")
|
||||||
|
|
||||||
|
# Only generate this target if no higher-level project already has
|
||||||
|
# if (NOT TARGET uninstall)
|
||||||
|
# configure_file(cmake_uninstall.cmake.in
|
||||||
|
# cmake_uninstall.cmake IMMEDIATE @ONLY)
|
||||||
|
|
||||||
|
# add_custom_target(uninstall
|
||||||
|
# "${CMAKE_COMMAND}" -P
|
||||||
|
# "${GLFW_BINARY_DIR}/cmake_uninstall.cmake")
|
||||||
|
# set_target_properties(uninstall PROPERTIES FOLDER "GLFW3")
|
||||||
|
# endif()
|
||||||
|
endif()
|
||||||
|
|
|
@ -0,0 +1,22 @@
|
||||||
|
Copyright (c) 2002-2006 Marcus Geelnard
|
||||||
|
Copyright (c) 2006-2016 Camilla Löwy <elmindreda@glfw.org>
|
||||||
|
|
||||||
|
This software is provided 'as-is', without any express or implied
|
||||||
|
warranty. In no event will the authors be held liable for any damages
|
||||||
|
arising from the use of this software.
|
||||||
|
|
||||||
|
Permission is granted to anyone to use this software for any purpose,
|
||||||
|
including commercial applications, and to alter it and redistribute it
|
||||||
|
freely, subject to the following restrictions:
|
||||||
|
|
||||||
|
1. The origin of this software must not be misrepresented; you must not
|
||||||
|
claim that you wrote the original software. If you use this software
|
||||||
|
in a product, an acknowledgment in the product documentation would
|
||||||
|
be appreciated but is not required.
|
||||||
|
|
||||||
|
2. Altered source versions must be plainly marked as such, and must not
|
||||||
|
be misrepresented as being the original software.
|
||||||
|
|
||||||
|
3. This notice may not be removed or altered from any source
|
||||||
|
distribution.
|
||||||
|
|
|
@ -0,0 +1,474 @@
|
||||||
|
# GLFW
|
||||||
|
|
||||||
|
[![Build status](https://travis-ci.org/glfw/glfw.svg?branch=master)](https://travis-ci.org/glfw/glfw)
|
||||||
|
[![Build status](https://ci.appveyor.com/api/projects/status/0kf0ct9831i5l6sp/branch/master?svg=true)](https://ci.appveyor.com/project/elmindreda/glfw)
|
||||||
|
[![Coverity Scan](https://scan.coverity.com/projects/4884/badge.svg)](https://scan.coverity.com/projects/glfw-glfw)
|
||||||
|
|
||||||
|
## Introduction
|
||||||
|
|
||||||
|
GLFW is an Open Source, multi-platform library for OpenGL, OpenGL ES and Vulkan
|
||||||
|
application development. It provides a simple, platform-independent API for
|
||||||
|
creating windows, contexts and surfaces, reading input, handling events, etc.
|
||||||
|
|
||||||
|
GLFW natively supports Windows, macOS and Linux and other Unix-like systems.
|
||||||
|
An experimental implementation for the Wayland protocol is available but not
|
||||||
|
yet officially supported.
|
||||||
|
|
||||||
|
GLFW is licensed under the [zlib/libpng
|
||||||
|
license](http://www.glfw.org/license.html).
|
||||||
|
|
||||||
|
The latest stable release is version 3.2.1.
|
||||||
|
|
||||||
|
See the [downloads](http://www.glfw.org/download.html) page for details and
|
||||||
|
files, or fetch the `latest` branch, which always points to the latest stable
|
||||||
|
release. Each release starting with 3.0 also has a corresponding [annotated
|
||||||
|
tag](https://github.com/glfw/glfw/releases) with source and binary archives.
|
||||||
|
The [version history](http://www.glfw.org/changelog.html) lists all user-visible
|
||||||
|
changes for every release.
|
||||||
|
|
||||||
|
This is a development branch for version 3.3, which is _not yet described_.
|
||||||
|
Pre-release documentation is available [here](http://www.glfw.org/docs/3.3/).
|
||||||
|
|
||||||
|
The `master` branch is the stable integration branch and _should_ always compile
|
||||||
|
and run on all supported platforms, although details of newly added features may
|
||||||
|
change until they have been included in a release. New features and many bug
|
||||||
|
fixes live in [other branches](https://github.com/glfw/glfw/branches/all) until
|
||||||
|
they are stable enough to merge.
|
||||||
|
|
||||||
|
If you are new to GLFW, you may find the
|
||||||
|
[tutorial](http://www.glfw.org/docs/latest/quick.html) for GLFW 3 useful. If
|
||||||
|
you have used GLFW 2 in the past, there is a [transition
|
||||||
|
guide](http://www.glfw.org/docs/latest/moving.html) for moving to the GLFW
|
||||||
|
3 API.
|
||||||
|
|
||||||
|
|
||||||
|
## Compiling GLFW
|
||||||
|
|
||||||
|
GLFW itself requires only the headers and libraries for your window system. It
|
||||||
|
does not need the headers for any context creation API (WGL, GLX, EGL, NSGL,
|
||||||
|
OSMesa) or rendering API (OpenGL, OpenGL ES, Vulkan) to enable support for them.
|
||||||
|
|
||||||
|
GLFW supports compilation on Windows with Visual C++ 2010 and later, MinGW and
|
||||||
|
MinGW-w64, on macOS with Clang and on Linux and other Unix-like systems with GCC
|
||||||
|
and Clang. It will likely compile in other environments as well, but this is
|
||||||
|
not regularly tested.
|
||||||
|
|
||||||
|
There are [pre-compiled Windows binaries](http://www.glfw.org/download.html)
|
||||||
|
available for all supported compilers.
|
||||||
|
|
||||||
|
See the [compilation guide](http://www.glfw.org/docs/latest/compile.html) for
|
||||||
|
more information about how to compile GLFW yourself.
|
||||||
|
|
||||||
|
|
||||||
|
## Using GLFW
|
||||||
|
|
||||||
|
See the [documentation](http://www.glfw.org/docs/latest/) for tutorials, guides
|
||||||
|
and the API reference.
|
||||||
|
|
||||||
|
|
||||||
|
## Contributing to GLFW
|
||||||
|
|
||||||
|
See the [contribution
|
||||||
|
guide](https://github.com/glfw/glfw/blob/master/docs/CONTRIBUTING.md) for
|
||||||
|
more information.
|
||||||
|
|
||||||
|
|
||||||
|
## System requirements
|
||||||
|
|
||||||
|
GLFW supports Windows XP and later and macOS 10.7 and later. Linux and other
|
||||||
|
Unix-like systems running the X Window System are supported even without
|
||||||
|
a desktop environment or modern extensions, although some features require
|
||||||
|
a running window or clipboard manager. The OSMesa backend requires Mesa 6.3.
|
||||||
|
|
||||||
|
See the [compatibility guide](http://www.glfw.org/docs/latest/compat.html)
|
||||||
|
in the documentation for more information.
|
||||||
|
|
||||||
|
|
||||||
|
## Dependencies
|
||||||
|
|
||||||
|
GLFW itself depends only on the headers and libraries for your window system.
|
||||||
|
|
||||||
|
The (experimental) Wayland backend also depends on the `extra-cmake-modules`
|
||||||
|
package, which is used to generated Wayland protocol headers.
|
||||||
|
|
||||||
|
The examples and test programs depend on a number of tiny libraries. These are
|
||||||
|
located in the `deps/` directory.
|
||||||
|
|
||||||
|
- [getopt\_port](https://github.com/kimgr/getopt_port/) for examples
|
||||||
|
with command-line options
|
||||||
|
- [TinyCThread](https://github.com/tinycthread/tinycthread) for threaded
|
||||||
|
examples
|
||||||
|
- An OpenGL 3.2 core loader generated by
|
||||||
|
[glad](https://github.com/Dav1dde/glad) for examples using modern OpenGL
|
||||||
|
- [linmath.h](https://github.com/datenwolf/linmath.h) for linear algebra in
|
||||||
|
examples
|
||||||
|
- [Nuklear](https://github.com/vurtun/nuklear) for test and example UI
|
||||||
|
- [stb\_image\_write](https://github.com/nothings/stb) for writing images to disk
|
||||||
|
- [Vulkan headers](https://www.khronos.org/registry/vulkan/) for Vulkan tests
|
||||||
|
|
||||||
|
The Vulkan example additionally requires the LunarG Vulkan SDK to be installed,
|
||||||
|
or it will not be included in the build. On macOS you need to provide the path
|
||||||
|
to the SDK manually as it has no standard installation location.
|
||||||
|
|
||||||
|
The documentation is generated with [Doxygen](http://doxygen.org/) if CMake can
|
||||||
|
find that tool.
|
||||||
|
|
||||||
|
|
||||||
|
## Reporting bugs
|
||||||
|
|
||||||
|
Bugs are reported to our [issue tracker](https://github.com/glfw/glfw/issues).
|
||||||
|
Please check the [contribution
|
||||||
|
guide](https://github.com/glfw/glfw/blob/master/docs/CONTRIBUTING.md) for
|
||||||
|
information on what to include when reporting a bug.
|
||||||
|
|
||||||
|
|
||||||
|
## Changelog
|
||||||
|
|
||||||
|
- Added `glfwGetError` function for querying the last error code and its
|
||||||
|
description (#970)
|
||||||
|
- Added `glfwUpdateGamepadMappings` function for importing gamepad mappings in
|
||||||
|
SDL\_GameControllerDB format (#900)
|
||||||
|
- Added `glfwJoystickIsGamepad` function for querying whether a joystick has
|
||||||
|
a gamepad mapping (#900)
|
||||||
|
- Added `glfwGetJoystickGUID` function for querying the SDL compatible GUID of
|
||||||
|
a joystick (#900)
|
||||||
|
- Added `glfwGetGamepadName` function for querying the name provided by the
|
||||||
|
gamepad mapping (#900)
|
||||||
|
- Added `glfwGetGamepadState` function, `GLFW_GAMEPAD_*` and `GLFWgamepadstate`
|
||||||
|
for retrieving gamepad input state (#900)
|
||||||
|
- Added `glfwGetWindowContentScale`, `glfwGetMonitorContentScale` and
|
||||||
|
`glfwSetWindowContentScaleCallback` for DPI-aware rendering
|
||||||
|
(#235,#439,#677,#845,#898)
|
||||||
|
- Added `glfwRequestWindowAttention` function for requesting attention from the
|
||||||
|
user (#732,#988)
|
||||||
|
- Added `glfwGetKeyScancode` function that allows retrieving platform dependent
|
||||||
|
scancodes for keys (#830)
|
||||||
|
- Added `glfwSetWindowMaximizeCallback` and `GLFWwindowmaximizefun` for
|
||||||
|
receiving window maximization events (#778)
|
||||||
|
- Added `glfwSetWindowAttrib` function for changing window attributes (#537)
|
||||||
|
- Added `glfwGetJoystickHats` function for querying joystick hats
|
||||||
|
(#889,#906,#934)
|
||||||
|
- Added `glfwInitHint` for setting initialization hints
|
||||||
|
- Added `glfwWindowHintString` for setting string type window hints (#893,#1139)
|
||||||
|
- Added `glfwGetWindowOpacity` and `glfwSetWindowOpacity` for controlling whole
|
||||||
|
window transparency (#1089)
|
||||||
|
- Added `glfwSetMonitorUserPointer` and `glfwGetMonitorUserPointer` for
|
||||||
|
per-monitor user pointers
|
||||||
|
- Added `glfwSetJoystickUserPointer` and `glfwGetJoystickUserPointer` for
|
||||||
|
per-joystick user pointers
|
||||||
|
- Added `glfwGetX11SelectionString` and `glfwSetX11SelectionString`
|
||||||
|
functions for accessing X11 primary selection (#894,#1056)
|
||||||
|
- Added headless [OSMesa](http://mesa3d.org/osmesa.html) backend (#850)
|
||||||
|
- Added definition of `GLAPIENTRY` to public header
|
||||||
|
- Added `GLFW_TRANSPARENT_FRAMEBUFFER` window hint and attribute for controlling
|
||||||
|
per-pixel framebuffer transparency (#197,#663,#715,#723,#1078)
|
||||||
|
- Added `GLFW_HOVERED` window attribute for polling cursor hover state (#1166)
|
||||||
|
- Added `GLFW_CENTER_CURSOR` window hint for controlling cursor centering
|
||||||
|
(#749,#842)
|
||||||
|
- Added `GLFW_FOCUS_ON_SHOW` window hint and attribute to control input focus
|
||||||
|
on calling show window (#1189)
|
||||||
|
- Added `GLFW_SCALE_TO_MONITOR` window hint for automatic window resizing
|
||||||
|
(#676,#1115)
|
||||||
|
- Added `GLFW_JOYSTICK_HAT_BUTTONS` init hint (#889)
|
||||||
|
- Added `GLFW_LOCK_KEY_MODS` input mode and `GLFW_MOD_*_LOCK` mod bits (#946)
|
||||||
|
- Added macOS specific `GLFW_COCOA_RETINA_FRAMEBUFFER` window hint
|
||||||
|
- Added macOS specific `GLFW_COCOA_FRAME_NAME` window hint (#195)
|
||||||
|
- Added macOS specific `GLFW_COCOA_GRAPHICS_SWITCHING` window hint (#377,#935)
|
||||||
|
- Added macOS specific `GLFW_COCOA_CHDIR_RESOURCES` init hint
|
||||||
|
- Added macOS specific `GLFW_COCOA_MENUBAR` init hint
|
||||||
|
- Added X11 specific `GLFW_X11_CLASS_NAME` and `GLFW_X11_INSTANCE_NAME` window
|
||||||
|
hints (#893,#1139)
|
||||||
|
- Added `GLFW_INCLUDE_ES32` for including the OpenGL ES 3.2 header
|
||||||
|
- Added `GLFW_OSMESA_CONTEXT_API` for creating OpenGL contexts with
|
||||||
|
[OSMesa](https://www.mesa3d.org/osmesa.html) (#281)
|
||||||
|
- Added `GenerateMappings.cmake` script for updating gamepad mappings
|
||||||
|
- Made `glfwCreateWindowSurface` emit an error when the window has a context
|
||||||
|
(#1194,#1205)
|
||||||
|
- Deprecated window parameter of clipboard string functions
|
||||||
|
- Deprecated charmods callback
|
||||||
|
- Removed `GLFW_USE_RETINA` compile-time option
|
||||||
|
- Removed `GLFW_USE_CHDIR` compile-time option
|
||||||
|
- Removed `GLFW_USE_MENUBAR` compile-time option
|
||||||
|
- Bugfix: Calling `glfwMaximizeWindow` on a full screen window was not ignored
|
||||||
|
- Bugfix: `GLFW_INCLUDE_VULKAN` could not be combined with the corresponding
|
||||||
|
OpenGL and OpenGL ES header macros
|
||||||
|
- Bugfix: `glfwGetInstanceProcAddress` returned `NULL` for
|
||||||
|
`vkGetInstanceProcAddr` when `_GLFW_VULKAN_STATIC` was enabled
|
||||||
|
- Bugfix: Invalid library paths were used in test and example CMake files (#930)
|
||||||
|
- Bugfix: The scancode for synthetic key release events was always zero
|
||||||
|
- Bugfix: The generated Doxyfile did not handle paths with spaces (#1081)
|
||||||
|
- [Win32] Added system error strings to relevant GLFW error descriptions (#733)
|
||||||
|
- [Win32] Moved to `WM_INPUT` for disabled cursor mode motion input (#125)
|
||||||
|
- [Win32] Removed XInput circular deadzone from joystick axis data (#1045)
|
||||||
|
- [Win32] Bugfix: Undecorated windows could not be iconified by the user (#861)
|
||||||
|
- [Win32] Bugfix: Deadzone logic could underflow with some controllers (#910)
|
||||||
|
- [Win32] Bugfix: Bitness test in `FindVulkan.cmake` was VS specific (#928)
|
||||||
|
- [Win32] Bugfix: `glfwVulkanSupported` emitted an error on systems with
|
||||||
|
a loader but no ICD (#916)
|
||||||
|
- [Win32] Bugfix: Non-iconified full sreeen windows did not prevent screen
|
||||||
|
blanking or password enabled screensavers (#851)
|
||||||
|
- [Win32] Bugfix: Mouse capture logic lost secondary release messages (#954)
|
||||||
|
- [Win32] Bugfix: The 32-bit Vulkan loader library static was not searched for
|
||||||
|
- [Win32] Bugfix: Vulkan libraries have a new path as of SDK 1.0.42.0 (#956)
|
||||||
|
- [Win32] Bugfix: Monitors with no display devices were not enumerated (#960)
|
||||||
|
- [Win32] Bugfix: Monitor events were not emitted (#784)
|
||||||
|
- [Win32] Bugfix: The Cygwin DLL was installed to the wrong directory (#1035)
|
||||||
|
- [Win32] Bugfix: Normalization of axis data via XInput was incorrect (#1045)
|
||||||
|
- [Win32] Bugfix: `glfw3native.h` would undefine a foreign `APIENTRY` (#1062)
|
||||||
|
- [Win32] Bugfix: Disabled cursor mode prevented use of caption buttons
|
||||||
|
(#650,#1071)
|
||||||
|
- [Win32] Bugfix: Returned key names did not match other platforms (#943)
|
||||||
|
- [Win32] Bugfix: Undecorated windows did not maximize to workarea (#899)
|
||||||
|
- [Win32] Bugfix: Window was resized twice when entering full screen (#1085)
|
||||||
|
- [Win32] Bugfix: The HID device notification was not unregistered (#1170)
|
||||||
|
- [Win32] Bugfix: `glfwCreateWindow` activated window even with `GLFW_FOCUSED`
|
||||||
|
hint set to false (#1179,#1180)
|
||||||
|
- [Win32] Bugfix: The keypad equals key was reported as `GLFW_KEY_UNKNOWN`
|
||||||
|
(#1315,#1316)
|
||||||
|
- [X11] Moved to XI2 `XI_RawMotion` for disable cursor mode motion input (#125)
|
||||||
|
- [X11] Replaced `_GLFW_HAS_XF86VM` compile-time option with dynamic loading
|
||||||
|
- [X11] Bugfix: `glfwGetVideoMode` would segfault on Cygwin/X
|
||||||
|
- [X11] Bugfix: Dynamic X11 library loading did not use full sonames (#941)
|
||||||
|
- [X11] Bugfix: Window creation on 64-bit would read past top of stack (#951)
|
||||||
|
- [X11] Bugfix: XDND support had multiple non-conformance issues (#968)
|
||||||
|
- [X11] Bugfix: The RandR monitor path was disabled despite working RandR (#972)
|
||||||
|
- [X11] Bugfix: IM-duplicated key events would leak at low polling rates (#747)
|
||||||
|
- [X11] Bugfix: Gamma ramp setting via RandR did not validate ramp size
|
||||||
|
- [X11] Bugfix: Key name string encoding depended on current locale (#981,#983)
|
||||||
|
- [X11] Bugfix: Incremental reading of selections was not supported (#275)
|
||||||
|
- [X11] Bugfix: Selection I/O reported but did not support `COMPOUND_TEXT`
|
||||||
|
- [X11] Bugfix: Latin-1 text read from selections was not converted to UTF-8
|
||||||
|
- [X11] Bugfix: NVidia EGL would segfault if unloaded before closing the display
|
||||||
|
- [X11] Bugfix: Checking window maximized attrib could crash some WMs (#1356)
|
||||||
|
- [X11] Bugfix: Update cursor position on enter event (#1366)
|
||||||
|
- [Linux] Added workaround for missing `SYN_DROPPED` in pre-2.6.39 kernel
|
||||||
|
headers (#1196)
|
||||||
|
- [Linux] Moved to evdev for joystick input (#906,#1005)
|
||||||
|
- [Linux] Bugfix: Event processing did not detect joystick disconnection (#932)
|
||||||
|
- [Linux] Bugfix: The joystick device path could be truncated (#1025)
|
||||||
|
- [Linux] Bugfix: `glfwInit` would fail if inotify creation failed (#833)
|
||||||
|
- [Linux] Bugfix: `strdup` was used without any required feature macro (#1055)
|
||||||
|
- [Cocoa] Added support for Vulkan window surface creation via
|
||||||
|
[MoltenVK](https://moltengl.com/moltenvk/) (#870)
|
||||||
|
- [Cocoa] Added support for loading a `MainMenu.nib` when available
|
||||||
|
- [Cocoa] Bugfix: Disabling window aspect ratio would assert (#852)
|
||||||
|
- [Cocoa] Bugfix: Window creation failed to set first responder (#876,#883)
|
||||||
|
- [Cocoa] Bugfix: Removed use of deprecated `CGDisplayIOServicePort` function
|
||||||
|
(#165,#192,#508,#511)
|
||||||
|
- [Cocoa] Bugfix: Disabled use of deprecated `CGDisplayModeCopyPixelEncoding`
|
||||||
|
function on macOS 10.12+
|
||||||
|
- [Cocoa] Bugfix: Running in AppSandbox would emit warnings (#816,#882)
|
||||||
|
- [Cocoa] Bugfix: Windows created after the first were not cascaded (#195)
|
||||||
|
- [Cocoa] Bugfix: Leaving video mode with `glfwSetWindowMonitor` would set
|
||||||
|
incorrect position and size (#748)
|
||||||
|
- [Cocoa] Bugfix: Iconified full screen windows could not be restored (#848)
|
||||||
|
- [Cocoa] Bugfix: Value range was ignored for joystick hats and buttons (#888)
|
||||||
|
- [Cocoa] Bugfix: Full screen framebuffer was incorrectly sized for some video
|
||||||
|
modes (#682)
|
||||||
|
- [Cocoa] Bugfix: A string object for IME was updated non-idiomatically (#1050)
|
||||||
|
- [Cocoa] Bugfix: A hidden or disabled cursor would become visible when a user
|
||||||
|
notification was shown (#971,#1028)
|
||||||
|
- [Cocoa] Bugfix: Some characters did not repeat due to Press and Hold (#1010)
|
||||||
|
- [Cocoa] Bugfix: Window title was lost when full screen or undecorated (#1082)
|
||||||
|
- [Cocoa] Bugfix: Window was resized twice when entering full screen (#1085)
|
||||||
|
- [Cocoa] Bugfix: Duplicate size events were not filtered (#1085)
|
||||||
|
- [Cocoa] Bugfix: Event polling did not initialize AppKit if necessary (#1218)
|
||||||
|
- [Cocoa] Bugfix: OpenGL rendering was not initially visible on 10.14
|
||||||
|
(#1334,#1346)
|
||||||
|
- [WGL] Added support for `WGL_EXT_colorspace` for OpenGL ES contexts
|
||||||
|
- [WGL] Added support for `WGL_ARB_create_context_no_error`
|
||||||
|
- [GLX] Added support for `GLX_ARB_create_context_no_error`
|
||||||
|
- [GLX] Bugfix: Context creation could segfault if no GLXFBConfigs were
|
||||||
|
available (#1040)
|
||||||
|
- [EGL] Added support for `EGL_KHR_get_all_proc_addresses` (#871)
|
||||||
|
- [EGL] Added support for `EGL_KHR_context_flush_control`
|
||||||
|
- [EGL] Bugfix: The test for `EGL_RGB_BUFFER` was invalid
|
||||||
|
|
||||||
|
|
||||||
|
## Contact
|
||||||
|
|
||||||
|
On [glfw.org](http://www.glfw.org/) you can find the latest version of GLFW, as
|
||||||
|
well as news, documentation and other information about the project.
|
||||||
|
|
||||||
|
If you have questions related to the use of GLFW, we have a
|
||||||
|
[forum](http://discourse.glfw.org/), and the `#glfw` IRC channel on
|
||||||
|
[Freenode](http://freenode.net/).
|
||||||
|
|
||||||
|
If you have a bug to report, a patch to submit or a feature you'd like to
|
||||||
|
request, please file it in the
|
||||||
|
[issue tracker](https://github.com/glfw/glfw/issues) on GitHub.
|
||||||
|
|
||||||
|
Finally, if you're interested in helping out with the development of GLFW or
|
||||||
|
porting it to your favorite platform, join us on the forum, GitHub or IRC.
|
||||||
|
|
||||||
|
|
||||||
|
## Acknowledgements
|
||||||
|
|
||||||
|
GLFW exists because people around the world donated their time and lent their
|
||||||
|
skills.
|
||||||
|
|
||||||
|
- Bobyshev Alexander
|
||||||
|
- Matt Arsenault
|
||||||
|
- David Avedissian
|
||||||
|
- Keith Bauer
|
||||||
|
- John Bartholomew
|
||||||
|
- Coşku Baş
|
||||||
|
- Niklas Behrens
|
||||||
|
- Niklas Bergström
|
||||||
|
- Denis Bernard
|
||||||
|
- Doug Binks
|
||||||
|
- blanco
|
||||||
|
- Kyle Brenneman
|
||||||
|
- Rok Breulj
|
||||||
|
- Martin Capitanio
|
||||||
|
- David Carlier
|
||||||
|
- Arturo Castro
|
||||||
|
- Chi-kwan Chan
|
||||||
|
- Ian Clarkson
|
||||||
|
- Michał Cichoń
|
||||||
|
- Lambert Clara
|
||||||
|
- Yaron Cohen-Tal
|
||||||
|
- Omar Cornut
|
||||||
|
- Andrew Corrigan
|
||||||
|
- Bailey Cosier
|
||||||
|
- Noel Cower
|
||||||
|
- Jason Daly
|
||||||
|
- Jarrod Davis
|
||||||
|
- Olivier Delannoy
|
||||||
|
- Paul R. Deppe
|
||||||
|
- Michael Dickens
|
||||||
|
- Роман Донченко
|
||||||
|
- Mario Dorn
|
||||||
|
- Wolfgang Draxinger
|
||||||
|
- Jonathan Dummer
|
||||||
|
- Ralph Eastwood
|
||||||
|
- Fredrik Ehnbom
|
||||||
|
- Robin Eklind
|
||||||
|
- Siavash Eliasi
|
||||||
|
- Felipe Ferreira
|
||||||
|
- Michael Fogleman
|
||||||
|
- Gerald Franz
|
||||||
|
- Mário Freitas
|
||||||
|
- GeO4d
|
||||||
|
- Marcus Geelnard
|
||||||
|
- Stephen Gowen
|
||||||
|
- Kovid Goyal
|
||||||
|
- Eloi Marín Gratacós
|
||||||
|
- Stefan Gustavson
|
||||||
|
- Jonathan Hale
|
||||||
|
- Sylvain Hellegouarch
|
||||||
|
- Matthew Henry
|
||||||
|
- heromyth
|
||||||
|
- Lucas Hinderberger
|
||||||
|
- Paul Holden
|
||||||
|
- Warren Hu
|
||||||
|
- IntellectualKitty
|
||||||
|
- Aaron Jacobs
|
||||||
|
- Erik S. V. Jansson
|
||||||
|
- Toni Jovanoski
|
||||||
|
- Arseny Kapoulkine
|
||||||
|
- Cem Karan
|
||||||
|
- Osman Keskin
|
||||||
|
- Josh Kilmer
|
||||||
|
- Cameron King
|
||||||
|
- Peter Knut
|
||||||
|
- Christoph Kubisch
|
||||||
|
- Yuri Kunde Schlesner
|
||||||
|
- Konstantin Käfer
|
||||||
|
- Eric Larson
|
||||||
|
- Robin Leffmann
|
||||||
|
- Glenn Lewis
|
||||||
|
- Shane Liesegang
|
||||||
|
- Eyal Lotem
|
||||||
|
- Tristam MacDonald
|
||||||
|
- Hans Mackowiak
|
||||||
|
- Дмитри Малышев
|
||||||
|
- Zbigniew Mandziejewicz
|
||||||
|
- Célestin Marot
|
||||||
|
- Kyle McDonald
|
||||||
|
- David Medlock
|
||||||
|
- Bryce Mehring
|
||||||
|
- Jonathan Mercier
|
||||||
|
- Marcel Metz
|
||||||
|
- Liam Middlebrook
|
||||||
|
- Jonathan Miller
|
||||||
|
- Kenneth Miller
|
||||||
|
- Bruce Mitchener
|
||||||
|
- Jack Moffitt
|
||||||
|
- Jeff Molofee
|
||||||
|
- Pierre Morel
|
||||||
|
- Jon Morton
|
||||||
|
- Pierre Moulon
|
||||||
|
- Martins Mozeiko
|
||||||
|
- Julian Møller
|
||||||
|
- ndogxj
|
||||||
|
- Kristian Nielsen
|
||||||
|
- Kamil Nowakowski
|
||||||
|
- Denis Ovod
|
||||||
|
- Ozzy
|
||||||
|
- Andri Pálsson
|
||||||
|
- Peoro
|
||||||
|
- Braden Pellett
|
||||||
|
- Christopher Pelloux
|
||||||
|
- Arturo J. Pérez
|
||||||
|
- Anthony Pesch
|
||||||
|
- Orson Peters
|
||||||
|
- Emmanuel Gil Peyrot
|
||||||
|
- Cyril Pichard
|
||||||
|
- Keith Pitt
|
||||||
|
- Stanislav Podgorskiy
|
||||||
|
- Alexandre Pretyman
|
||||||
|
- przemekmirek
|
||||||
|
- Philip Rideout
|
||||||
|
- Eddie Ringle
|
||||||
|
- Jorge Rodriguez
|
||||||
|
- Ed Ropple
|
||||||
|
- Aleksey Rybalkin
|
||||||
|
- Riku Salminen
|
||||||
|
- Brandon Schaefer
|
||||||
|
- Sebastian Schuberth
|
||||||
|
- Christian Sdunek
|
||||||
|
- Matt Sealey
|
||||||
|
- Steve Sexton
|
||||||
|
- Arkady Shapkin
|
||||||
|
- Yoshiki Shibukawa
|
||||||
|
- Dmitri Shuralyov
|
||||||
|
- Daniel Skorupski
|
||||||
|
- Bradley Smith
|
||||||
|
- Patrick Snape
|
||||||
|
- Erlend Sogge Heggen
|
||||||
|
- Julian Squires
|
||||||
|
- Johannes Stein
|
||||||
|
- Pontus Stenetorp
|
||||||
|
- Michael Stocker
|
||||||
|
- Justin Stoecker
|
||||||
|
- Elviss Strazdins
|
||||||
|
- Paul Sultana
|
||||||
|
- Nathan Sweet
|
||||||
|
- TTK-Bandit
|
||||||
|
- Sergey Tikhomirov
|
||||||
|
- Arthur Tombs
|
||||||
|
- Ioannis Tsakpinis
|
||||||
|
- Samuli Tuomola
|
||||||
|
- Matthew Turner
|
||||||
|
- urraka
|
||||||
|
- Elias Vanderstuyft
|
||||||
|
- Stef Velzel
|
||||||
|
- Jari Vetoniemi
|
||||||
|
- Ricardo Vieira
|
||||||
|
- Nicholas Vitovitch
|
||||||
|
- Simon Voordouw
|
||||||
|
- Corentin Wallez
|
||||||
|
- Torsten Walluhn
|
||||||
|
- Patrick Walton
|
||||||
|
- Xo Wang
|
||||||
|
- Jay Weisskopf
|
||||||
|
- Frank Wille
|
||||||
|
- Ryogo Yoshimura
|
||||||
|
- Andrey Zholos
|
||||||
|
- Santi Zupancic
|
||||||
|
- Jonas Ådahl
|
||||||
|
- Lasse Öörni
|
||||||
|
- All the unmentioned and anonymous contributors in the GLFW community, for bug
|
||||||
|
reports, patches, feedback, testing and encouragement
|
||||||
|
|
|
@ -0,0 +1,29 @@
|
||||||
|
|
||||||
|
if (NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt")
|
||||||
|
message(FATAL_ERROR "Cannot find install manifest: \"@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt\"")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
file(READ "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt" files)
|
||||||
|
string(REGEX REPLACE "\n" ";" files "${files}")
|
||||||
|
|
||||||
|
foreach (file ${files})
|
||||||
|
message(STATUS "Uninstalling \"$ENV{DESTDIR}${file}\"")
|
||||||
|
if (EXISTS "$ENV{DESTDIR}${file}")
|
||||||
|
exec_program("@CMAKE_COMMAND@" ARGS "-E remove \"$ENV{DESTDIR}${file}\""
|
||||||
|
OUTPUT_VARIABLE rm_out
|
||||||
|
RETURN_VALUE rm_retval)
|
||||||
|
if (NOT "${rm_retval}" STREQUAL 0)
|
||||||
|
MESSAGE(FATAL_ERROR "Problem when removing \"$ENV{DESTDIR}${file}\"")
|
||||||
|
endif()
|
||||||
|
elseif (IS_SYMLINK "$ENV{DESTDIR}${file}")
|
||||||
|
EXEC_PROGRAM("@CMAKE_COMMAND@" ARGS "-E remove \"$ENV{DESTDIR}${file}\""
|
||||||
|
OUTPUT_VARIABLE rm_out
|
||||||
|
RETURN_VALUE rm_retval)
|
||||||
|
if (NOT "${rm_retval}" STREQUAL 0)
|
||||||
|
message(FATAL_ERROR "Problem when removing symlink \"$ENV{DESTDIR}${file}\"")
|
||||||
|
endif()
|
||||||
|
else()
|
||||||
|
message(STATUS "File \"$ENV{DESTDIR}${file}\" does not exist.")
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue