Compare commits
18 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
8e394594c8 | ||
|
|
a0bc503e32 | ||
|
|
278e280199 | ||
|
|
c6deefe96d | ||
|
|
3cc5a6a95f | ||
|
|
12365b79e3 | ||
|
|
add2572f4b | ||
|
|
c80ca011dd | ||
|
|
93f31592d8 | ||
|
|
0fc09edd73 | ||
|
|
46b93115a6 | ||
|
|
7d4d9d108d | ||
|
|
0aa713d6c1 | ||
|
|
f0ac5474ff | ||
|
|
bc3e7beb76 | ||
|
|
9c723941a9 | ||
|
|
7144e76127 | ||
|
|
4b329a36e0 |
@@ -1,142 +0,0 @@
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 1000 # Hz
|
||||
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
||||
trajectory_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
gpio_command_controller:
|
||||
type: gpio_controllers/GpioCommandController
|
||||
|
||||
trajectory_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- joint_1
|
||||
- joint_2
|
||||
- joint_3
|
||||
- joint_4
|
||||
- joint_5
|
||||
- joint_6
|
||||
- joint_7
|
||||
- joint_8
|
||||
- joint_9
|
||||
- joint_10
|
||||
- joint_11
|
||||
- joint_12
|
||||
command_interfaces:
|
||||
- position
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
state_publish_rate: 200.0
|
||||
action_monitor_rate: 20.0
|
||||
allow_partial_joints_goal: false
|
||||
open_loop_control: true
|
||||
allow_integration_in_goal_trajectories: true
|
||||
constraints:
|
||||
goal_time: 0.5
|
||||
stopped_velocity_tolerance: 0.02
|
||||
gpio_command_controller:
|
||||
ros__parameters:
|
||||
gpios:
|
||||
- joint_1
|
||||
- joint_2
|
||||
- joint_3
|
||||
- joint_4
|
||||
- joint_5
|
||||
- joint_6
|
||||
- joint_7
|
||||
- joint_8
|
||||
- joint_9
|
||||
- joint_10
|
||||
- joint_11
|
||||
- joint_12
|
||||
command_interfaces:
|
||||
joint_1:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_2:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_3:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_4:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_5:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_6:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_7:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_8:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_9:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_10:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_11:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
joint_12:
|
||||
- interfaces:
|
||||
- fault
|
||||
- enable
|
||||
state_interfaces:
|
||||
joint_1:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_2:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_3:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_4:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_5:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_6:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_7:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_8:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_9:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_10:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_11:
|
||||
- interfaces:
|
||||
- fault
|
||||
joint_12:
|
||||
- interfaces:
|
||||
- fault
|
||||
@@ -1,95 +0,0 @@
|
||||
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration, TextSubstitution
|
||||
from launch.actions import DeclareLaunchArgument,TimerAction
|
||||
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare arguments
|
||||
declared_arguments = []
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
'description_file',
|
||||
default_value='motor_drive.config.xacro',
|
||||
description='URDF/XACRO description file with the axis.',
|
||||
)
|
||||
)
|
||||
|
||||
description_file = LaunchConfiguration('description_file')
|
||||
|
||||
# Get URDF via xacro
|
||||
robot_description_content = Command(
|
||||
[
|
||||
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||
" ",
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("ecrt_driver"),
|
||||
"description",
|
||||
description_file,
|
||||
]
|
||||
),
|
||||
]
|
||||
)
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
|
||||
robot_controllers = PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("ecrt_driver"),
|
||||
"config",
|
||||
"controllers.yaml",
|
||||
]
|
||||
)
|
||||
|
||||
control_node = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
parameters=[robot_description, robot_controllers,
|
||||
{
|
||||
"lock_memory": True,
|
||||
"thread_priority": 90
|
||||
}
|
||||
],
|
||||
output="both",
|
||||
)
|
||||
|
||||
robot_state_pub_node = Node(
|
||||
package="robot_state_publisher",
|
||||
executable="robot_state_publisher",
|
||||
parameters=[robot_description],
|
||||
output='screen'
|
||||
)
|
||||
|
||||
joint_state_broadcaster_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["joint_state_broadcaster", "-c", "/controller_manager"],
|
||||
)
|
||||
|
||||
gpio_controller_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["gpio_command_controller", "-c", "/controller_manager"],
|
||||
)
|
||||
|
||||
trajectory_controller_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["trajectory_controller", "-c", "/controller_manager"],
|
||||
)
|
||||
delay_node=TimerAction(period=1.0,actions=[gpio_controller_spawner,trajectory_controller_spawner])
|
||||
nodes = [
|
||||
control_node,
|
||||
robot_state_pub_node,
|
||||
joint_state_broadcaster_spawner,
|
||||
delay_node,
|
||||
]#position_controller_spawner,
|
||||
|
||||
return LaunchDescription(
|
||||
declared_arguments +
|
||||
nodes)
|
||||
@@ -1,304 +0,0 @@
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include <filesystem>
|
||||
#include <fstream> // 添加这行来支持文件流操作
|
||||
#include <time.h>
|
||||
#include "std_msgs/msg/string.hpp"
|
||||
#include "trajectory_msgs/msg/joint_trajectory.hpp"
|
||||
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
|
||||
#include "control_msgs/msg/dynamic_interface_group_values.hpp"
|
||||
#include "control_msgs/action/follow_joint_trajectory.hpp"
|
||||
#include "sensor_msgs/msg/joint_state.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
namespace fs = std::filesystem;
|
||||
constexpr double rad_to_count= 524288.0/(2*M_PI);
|
||||
constexpr double count_to_rad=2*M_PI/524288.0;
|
||||
class TestMotor : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
TestMotor();
|
||||
~TestMotor();
|
||||
|
||||
int motor_dst(std::string name,double dst);//add by hehe
|
||||
//void ctrl_motor(int id,double pos,int reset,int enable);
|
||||
void motor_fault(int id,double fault);
|
||||
void motor_enable(int id,double enable);
|
||||
void motor_pos(int id,double pos);
|
||||
void motor_loop(int motor_id,int cnt);
|
||||
void motor_action(int id,double angle);
|
||||
void all_motor();
|
||||
void ControlLoop();
|
||||
private:
|
||||
rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr cmdPub_;
|
||||
rclcpp::Publisher<control_msgs::msg::DynamicInterfaceGroupValues>::SharedPtr gpioPub_;
|
||||
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr jointStatesSub_;
|
||||
rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SharedPtr client_;
|
||||
// 文件流相关
|
||||
std::ofstream data_file_; // 用于写入数据的文件流
|
||||
std::string data_file_path_; // 数据文件路径
|
||||
|
||||
rclcpp::TimerBase::SharedPtr controlTimer_;
|
||||
rclcpp::Time lastTime_; // 移至类成员
|
||||
|
||||
bool isRunning_;
|
||||
bool isPaused_;
|
||||
bool isFinished_;
|
||||
bool isRobotEnabled_;
|
||||
bool enableCommandExecuted_;
|
||||
int loop_cnt=0;
|
||||
int jogDirection_;
|
||||
//add by hehe
|
||||
std::unordered_map<std::string,double> curMap_;
|
||||
std::unordered_map<std::string,double> dstMap_;
|
||||
//control_msgs::msg::DynamicInterfaceGroupValues posMsg_;
|
||||
sensor_msgs::msg::JointState curJointSta_;
|
||||
//add by hehe end
|
||||
// 执行当前状态对应的动作
|
||||
void JointStatesCallback(const sensor_msgs::msg::JointState::SharedPtr msg);
|
||||
};
|
||||
|
||||
// 机器人控制器构造函数
|
||||
TestMotor::TestMotor() : Node("test_motor_node")
|
||||
{
|
||||
std::cout << "TestMotor Node is created!" << std::endl;
|
||||
// 创建发布者
|
||||
cmdPub_ = this->create_publisher<trajectory_msgs::msg::JointTrajectory>("/trajectory_controller/joint_trajectory", 10);
|
||||
//action
|
||||
client_=rclcpp_action::create_client<control_msgs::action::FollowJointTrajectory>(this,"/trajectory_controller/follow_joint_trajectory");
|
||||
// 创建发布者
|
||||
gpioPub_ = this->create_publisher<control_msgs::msg::DynamicInterfaceGroupValues>("/gpio_command_controller/commands", 10);
|
||||
// 订阅仿真状态
|
||||
jointStatesSub_ = this->create_subscription<sensor_msgs::msg::JointState>("/joint_states", 10,std::bind(&TestMotor::JointStatesCallback, this, std::placeholders::_1));
|
||||
lastTime_ = this->now(); // 初始化时间
|
||||
// 创建定时器,每10ms执行一次控制逻辑(频率100Hz)
|
||||
controlTimer_ = this->create_wall_timer(std::chrono::milliseconds(5000),std::bind(&TestMotor::ControlLoop, this)); // 绑定到新的控制函数);
|
||||
curMap_.clear();
|
||||
dstMap_.clear();
|
||||
//posMsg_.interface_groups.resize(12);
|
||||
//posMsg_.interface_values.resize(12);
|
||||
motor_enable(6,1);
|
||||
motor_enable(13,1);
|
||||
std::cout << "TestMotor Node is created finished!" << std::endl;
|
||||
}
|
||||
|
||||
TestMotor::~TestMotor()
|
||||
{
|
||||
std::cout << "Robot controller stopped." << std::endl;
|
||||
}
|
||||
|
||||
void TestMotor::JointStatesCallback(const sensor_msgs::msg::JointState::SharedPtr msg)
|
||||
{
|
||||
if (!msg) { // 检查消息是否有效
|
||||
std::cout << "get null joint states!" << std::endl;
|
||||
return;
|
||||
}
|
||||
for(int i=0;i<msg->name.size();i++)
|
||||
{
|
||||
curMap_[msg->name[i]] = msg->position[i];
|
||||
///std::cout<<"cur:"<<msg->name[i]<<":"<<curMap_[msg->name[i]]<<std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
int TestMotor::motor_dst(std::string name,double dst){
|
||||
control_msgs::msg::DynamicInterfaceGroupValues posMsg_;
|
||||
double val=curMap_[name];
|
||||
double diff=dst-val;
|
||||
double tempJointValue=0;
|
||||
float delta=0.0;
|
||||
if(diff>600){
|
||||
delta=120.0;
|
||||
tempJointValue=val+delta;
|
||||
}else if(diff<-600){
|
||||
delta=-120.0;
|
||||
tempJointValue=val+delta;
|
||||
}else{
|
||||
return 0;
|
||||
}
|
||||
posMsg_.interface_groups.push_back(name);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
tempValue.interface_names = {"position"};
|
||||
tempValue.values = {tempJointValue};
|
||||
posMsg_.interface_values.push_back(tempValue);
|
||||
return 0;
|
||||
}
|
||||
|
||||
// 状态机主循环
|
||||
void TestMotor::ControlLoop() {
|
||||
//Gpio_publish_joint_trajectory();
|
||||
all_motor();
|
||||
}
|
||||
void TestMotor::motor_pos(int id,double delta)
|
||||
{
|
||||
control_msgs::msg::DynamicInterfaceGroupValues posMsg_;
|
||||
std::string target_motor="joint_" + std::to_string(id);
|
||||
for(int i=0;i<12;i++){
|
||||
std::string tempInterfaceGroup = "joint_" + std::to_string(i+1);
|
||||
posMsg_.interface_groups.push_back(tempInterfaceGroup);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
//position
|
||||
tempValue.interface_names = {"position"};
|
||||
if(id==0){
|
||||
tempValue.values = {curMap_[tempInterfaceGroup]+delta};
|
||||
}else{
|
||||
if(tempInterfaceGroup!=target_motor)
|
||||
tempValue.values = {curMap_[tempInterfaceGroup]};
|
||||
else
|
||||
tempValue.values = {curMap_[tempInterfaceGroup]+delta};
|
||||
}
|
||||
std::cout<<tempInterfaceGroup<<":"<<curMap_[tempInterfaceGroup]<<"-->"<<tempValue.values[0]<<std::endl;
|
||||
posMsg_.interface_values.push_back(tempValue);
|
||||
}
|
||||
|
||||
gpioPub_->publish(posMsg_);
|
||||
usleep(10000);
|
||||
}
|
||||
void TestMotor::motor_fault(int id,double fault)
|
||||
{
|
||||
control_msgs::msg::DynamicInterfaceGroupValues posMsg_;
|
||||
std::string target_motor="joint_" + std::to_string(id);
|
||||
std::cout<<"fault:";
|
||||
for(int i=0;i<12;i++){
|
||||
std::string tempInterfaceGroup = "joint_" + std::to_string(i+1);
|
||||
posMsg_.interface_groups.push_back(tempInterfaceGroup);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
//reset
|
||||
tempValue.interface_names = {"fault"};
|
||||
if(id==0){
|
||||
tempValue.values = {fault};
|
||||
}else{
|
||||
if(tempInterfaceGroup!=target_motor)
|
||||
tempValue.values = {0};
|
||||
else
|
||||
tempValue.values = {fault};
|
||||
}
|
||||
|
||||
std::cout<<tempInterfaceGroup<<":"<<tempValue.values[0]<<",";
|
||||
posMsg_.interface_values.push_back(tempValue);
|
||||
}
|
||||
std::cout<<std::endl;
|
||||
gpioPub_->publish(posMsg_);
|
||||
usleep(50000);
|
||||
}
|
||||
void TestMotor::motor_enable(int id,double enable)
|
||||
{
|
||||
control_msgs::msg::DynamicInterfaceGroupValues posMsg_;
|
||||
std::string target_motor="joint_" + std::to_string(id);
|
||||
std::cout<<"enable:";
|
||||
for(int i=0;i<12;i++){
|
||||
std::string tempInterfaceGroup = "joint_" + std::to_string(i+1);
|
||||
posMsg_.interface_groups.push_back(tempInterfaceGroup);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
//enable
|
||||
tempValue.interface_names = {"enable"};
|
||||
#if 1
|
||||
if(i<id)
|
||||
tempValue.values = {enable};
|
||||
else
|
||||
tempValue.values = {0};
|
||||
#else
|
||||
if(id==0){
|
||||
tempValue.values = {enable};
|
||||
}else{
|
||||
if(tempInterfaceGroup!=target_motor)
|
||||
tempValue.values = {0};
|
||||
else
|
||||
tempValue.values = {enable};
|
||||
}
|
||||
#endif
|
||||
std::cout<<tempInterfaceGroup<<":"<<tempValue.values[0]<<",";
|
||||
posMsg_.interface_values.push_back(tempValue);
|
||||
}
|
||||
std::cout<<std::endl;
|
||||
gpioPub_->publish(posMsg_);
|
||||
usleep(1000000);
|
||||
}
|
||||
void TestMotor::motor_action(int id,double delta)
|
||||
{
|
||||
//std::cout<<"motor_action:"<<id<<","<<delta<<std::endl;
|
||||
if(client_->wait_for_action_server(std::chrono::seconds(5))){
|
||||
auto goal=control_msgs::action::FollowJointTrajectory::Goal();
|
||||
goal.trajectory.joint_names={"joint_1","joint_2","joint_3","joint_4","joint_5","joint_6","joint_7","joint_8","joint_9","joint_10","joint_11","joint_12"};
|
||||
trajectory_msgs::msg::JointTrajectoryPoint point;
|
||||
for(int i=0;i<12;i++){
|
||||
std::string joint="joint_"+std::to_string(i+1);
|
||||
//if(id==(i+1))
|
||||
if(i<12)
|
||||
point.positions.push_back(curMap_[joint]+delta);
|
||||
else
|
||||
point.positions.push_back(curMap_[joint]);
|
||||
printf("%s: %.2f/%.2f\n",joint.c_str(),curMap_[joint],point.positions[i]);
|
||||
}
|
||||
goal.trajectory.points.push_back(point);
|
||||
auto send_goal_option=rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SendGoalOptions();
|
||||
send_goal_option.goal_response_callback=[this](auto res){
|
||||
auto goal_handle=res.get();
|
||||
if(goal_handle){
|
||||
printf("goal has be accept!!!\n");
|
||||
}
|
||||
};
|
||||
send_goal_option.feedback_callback=[this](auto,auto feedback){
|
||||
for(int i=0;i<12;i++){
|
||||
printf("%s,%.3f/%.3f\n",feedback->joint_names[i].c_str(),feedback->desired.positions[i],feedback->actual.positions[i]);
|
||||
}
|
||||
};
|
||||
send_goal_option.result_callback=[this](auto ret){
|
||||
if(ret.code==rclcpp_action::ResultCode::SUCCEEDED)
|
||||
printf("action ret succeed\n");
|
||||
else if(ret.code==rclcpp_action::ResultCode::ABORTED)
|
||||
printf("action ret aborted\n");
|
||||
};
|
||||
client_->async_send_goal(goal,send_goal_option);
|
||||
}else{
|
||||
printf("wait action server error\n");
|
||||
}
|
||||
}
|
||||
void TestMotor::motor_loop(int motor_id,int loop_cnt){
|
||||
std::cout<<"start test:"<<motor_id<<std::endl;
|
||||
motor_fault(0,1);
|
||||
//motor_enable(motor_id,1);
|
||||
if(loop_cnt%2==0)
|
||||
//motor_pos(motor_id,3000);
|
||||
motor_action(motor_id,-0.05);
|
||||
else
|
||||
//motor_pos(motor_id,-3000);
|
||||
motor_action(motor_id,0.05);
|
||||
///usleep(3*1000000);
|
||||
}
|
||||
void TestMotor::all_motor(){
|
||||
loop_cnt+=1;
|
||||
static int sw=0;
|
||||
|
||||
motor_loop(0,loop_cnt);
|
||||
#if 0
|
||||
int mid=loop_cnt%100;
|
||||
if(mid<13&&mid>0)
|
||||
motor_loop(mid,sw);
|
||||
else{
|
||||
loop_cnt=0;
|
||||
sw+=1;
|
||||
motor_loop(1,sw);
|
||||
}
|
||||
|
||||
#endif
|
||||
#if 0
|
||||
motor_loop(2,loop_cnt);
|
||||
motor_loop(3,loop_cnt);
|
||||
motor_loop(4,loop_cnt);
|
||||
motor_loop(5,loop_cnt);
|
||||
motor_loop(6,loop_cnt);
|
||||
motor_loop(7,loop_cnt);
|
||||
motor_loop(8,loop_cnt);
|
||||
motor_loop(9,loop_cnt);
|
||||
motor_loop(10,loop_cnt);
|
||||
motor_loop(11,loop_cnt);
|
||||
motor_loop(12,loop_cnt);
|
||||
#endif
|
||||
}
|
||||
int main(int argc,char* argv[]){
|
||||
rclcpp::init(argc,argv);
|
||||
auto node=std::make_shared<TestMotor>();
|
||||
///usleep(10000000);
|
||||
///node->all_motor();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
return 0;
|
||||
}
|
||||
@@ -14,6 +14,7 @@ find_package(rclcpp_lifecycle REQUIRED)
|
||||
find_package(rclcpp_action REQUIRED)
|
||||
find_package(trajectory_msgs REQUIRED)
|
||||
find_package(control_msgs REQUIRED)
|
||||
find_package(controller_manager_msgs REQUIRED)
|
||||
find_library(ECRT_LIB
|
||||
NAMES ethercat ecrt
|
||||
PATHS /opt/etherlab/lib /usr/local/lib /usr/lib
|
||||
@@ -35,22 +36,34 @@ ament_target_dependencies(
|
||||
pluginlib
|
||||
rclcpp
|
||||
rclcpp_lifecycle
|
||||
rclcpp_action
|
||||
)
|
||||
|
||||
|
||||
# 构建可执行文件
|
||||
add_executable(test_motor src/test_motor.cpp)
|
||||
ament_target_dependencies(test_motor
|
||||
#add_executable(test_motor src/test_motor.cpp)
|
||||
#ament_target_dependencies(test_motor
|
||||
# rclcpp
|
||||
# rclcpp_action
|
||||
# geometry_msgs
|
||||
# sensor_msgs
|
||||
# trajectory_msgs
|
||||
# control_msgs
|
||||
# controller_manager_msgs
|
||||
#)
|
||||
#install(TARGETS test_motor DESTINATION lib/${PROJECT_NAME})
|
||||
|
||||
add_executable(dual_motor src/dual_motor.cpp)
|
||||
ament_target_dependencies(dual_motor
|
||||
rclcpp
|
||||
rclcpp_action
|
||||
geometry_msgs
|
||||
sensor_msgs
|
||||
trajectory_msgs
|
||||
control_msgs
|
||||
controller_manager_msgs
|
||||
)
|
||||
install(TARGETS test_motor DESTINATION lib/${PROJECT_NAME})
|
||||
|
||||
|
||||
install(TARGETS dual_motor DESTINATION lib/${PROJECT_NAME})
|
||||
|
||||
# Causes the visibility macros to use dllexport rather than dllimport,
|
||||
# which is appropriate when building the dll but not consuming it.
|
||||
72
ecrt_dev_dual/config/dual_arm_controllers.yaml
Normal file
72
ecrt_dev_dual/config/dual_arm_controllers.yaml
Normal file
@@ -0,0 +1,72 @@
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 250
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
left_arm_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
right_arm_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
left_arm_gpio_controller:
|
||||
type: gpio_controllers/GpioCommandController
|
||||
right_arm_gpio_controller:
|
||||
type: gpio_controllers/GpioCommandController
|
||||
left_arm_controller:
|
||||
ros__parameters:
|
||||
joints: [left_arm_joint_1, left_arm_joint_2,left_arm_joint_3,left_arm_joint_4,left_arm_joint_5,left_arm_joint_6]
|
||||
command_interfaces: [position]
|
||||
state_interfaces: [position, velocity]
|
||||
|
||||
right_arm_controller:
|
||||
ros__parameters:
|
||||
joints: [right_arm_joint_1,right_arm_joint_2,right_arm_joint_3,right_arm_joint_4,right_arm_joint_5,right_arm_joint_6]
|
||||
command_interfaces: [position]
|
||||
state_interfaces: [position, velocity]
|
||||
|
||||
left_arm_gpio_controller:
|
||||
ros__parameters:
|
||||
gpios:
|
||||
- left_arm_joint_1
|
||||
- left_arm_joint_2
|
||||
- left_arm_joint_3
|
||||
- left_arm_joint_4
|
||||
- left_arm_joint_5
|
||||
- left_arm_joint_6
|
||||
command_interfaces:
|
||||
left_arm_joint_1: { interfaces: [fault, enable] }
|
||||
left_arm_joint_2: { interfaces: [fault, enable] }
|
||||
left_arm_joint_3: { interfaces: [fault, enable] }
|
||||
left_arm_joint_4: { interfaces: [fault, enable] }
|
||||
left_arm_joint_5: { interfaces: [fault, enable] }
|
||||
left_arm_joint_6: { interfaces: [fault, enable] }
|
||||
state_interfaces:
|
||||
left_arm_joint_1: { interfaces: [fault, enable] }
|
||||
left_arm_joint_2: { interfaces: [fault, enable] }
|
||||
left_arm_joint_3: { interfaces: [fault, enable] }
|
||||
left_arm_joint_4: { interfaces: [fault, enable] }
|
||||
left_arm_joint_5: { interfaces: [fault, enable] }
|
||||
left_arm_joint_6: { interfaces: [fault, enable] }
|
||||
|
||||
right_arm_gpio_controller:
|
||||
ros__parameters:
|
||||
gpios:
|
||||
- right_arm_joint_1
|
||||
- right_arm_joint_2
|
||||
- right_arm_joint_3
|
||||
- right_arm_joint_4
|
||||
- right_arm_joint_5
|
||||
- right_arm_joint_6
|
||||
command_interfaces:
|
||||
right_arm_joint_1: { interfaces: [fault, enable] }
|
||||
right_arm_joint_2: { interfaces: [fault, enable] }
|
||||
right_arm_joint_3: { interfaces: [fault, enable] }
|
||||
right_arm_joint_4: { interfaces: [fault, enable] }
|
||||
right_arm_joint_5: { interfaces: [fault, enable] }
|
||||
right_arm_joint_6: { interfaces: [fault, enable] }
|
||||
state_interfaces:
|
||||
right_arm_joint_1: { interfaces: [fault, enable] }
|
||||
right_arm_joint_2: { interfaces: [fault, enable] }
|
||||
right_arm_joint_3: { interfaces: [fault, enable] }
|
||||
right_arm_joint_4: { interfaces: [fault, enable] }
|
||||
right_arm_joint_5: { interfaces: [fault, enable] }
|
||||
right_arm_joint_6: { interfaces: [fault, enable] }
|
||||
@@ -16,7 +16,9 @@
|
||||
<!-- 状态接口(位置/速度/力矩) -->
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
<state_interface name="fault"/>
|
||||
<state_interface name="enable"/>
|
||||
|
||||
<!-- 命令接口(位置控制/故障重置/使能) -->
|
||||
|
||||
@@ -44,18 +46,18 @@
|
||||
</hardware>
|
||||
|
||||
<!-- 调用子宏生成多个关节(仅需指定名称和位置索引) -->
|
||||
<xacro:single_joint_config joint_name="joint_1" ec_position="1" />
|
||||
<xacro:single_joint_config joint_name="joint_2" ec_position="2" />
|
||||
<xacro:single_joint_config joint_name="joint_3" ec_position="3" />
|
||||
<xacro:single_joint_config joint_name="joint_4" ec_position="4" />
|
||||
<xacro:single_joint_config joint_name="joint_5" ec_position="5" />
|
||||
<xacro:single_joint_config joint_name="joint_6" ec_position="6" />
|
||||
<xacro:single_joint_config joint_name="joint_7" ec_position="7" />
|
||||
<xacro:single_joint_config joint_name="joint_8" ec_position="8" />
|
||||
<xacro:single_joint_config joint_name="joint_9" ec_position="9" />
|
||||
<xacro:single_joint_config joint_name="joint_10" ec_position="10" />
|
||||
<xacro:single_joint_config joint_name="joint_11" ec_position="11" />
|
||||
<xacro:single_joint_config joint_name="joint_12" ec_position="12" />
|
||||
<xacro:single_joint_config joint_name="left_arm_joint_1" ec_position="1" />
|
||||
<xacro:single_joint_config joint_name="left_arm_joint_2" ec_position="2" />
|
||||
<xacro:single_joint_config joint_name="left_arm_joint_3" ec_position="3" />
|
||||
<xacro:single_joint_config joint_name="left_arm_joint_4" ec_position="4" />
|
||||
<xacro:single_joint_config joint_name="left_arm_joint_5" ec_position="5" />
|
||||
<xacro:single_joint_config joint_name="left_arm_joint_6" ec_position="6" />
|
||||
<xacro:single_joint_config joint_name="right_arm_joint_1" ec_position="7" />
|
||||
<xacro:single_joint_config joint_name="right_arm_joint_2" ec_position="8" />
|
||||
<xacro:single_joint_config joint_name="right_arm_joint_3" ec_position="9" />
|
||||
<xacro:single_joint_config joint_name="right_arm_joint_4" ec_position="10" />
|
||||
<xacro:single_joint_config joint_name="right_arm_joint_5" ec_position="11" />
|
||||
<xacro:single_joint_config joint_name="right_arm_joint_6" ec_position="12" />
|
||||
</ros2_control>
|
||||
</xacro:macro>
|
||||
|
||||
@@ -30,6 +30,10 @@
|
||||
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
|
||||
#include "rclcpp_lifecycle/state.hpp"
|
||||
#include "ethercat_driver/visibility_control.h"
|
||||
#include <pthread.h>
|
||||
#include <sched.h>
|
||||
#include <sys/mman.h>
|
||||
#include <atomic>
|
||||
//#include "ethercat_interface/ec_slave.hpp"
|
||||
//#include "ethercat_interface/ec_master.hpp"
|
||||
#include "zer_config.hpp"
|
||||
@@ -73,20 +77,21 @@ public:
|
||||
void writeData();
|
||||
void check_master_state();
|
||||
void check_domain1_state();
|
||||
void check_slave_config_states();
|
||||
bool check_slave_config_states();
|
||||
void set_motor_enable(int id,bool enable){
|
||||
if(id>0&&id<13){
|
||||
if(id>0&&id<NUM_SLAVES+1){
|
||||
motor_enable_arr[id-1].store(enable);
|
||||
}
|
||||
};
|
||||
bool get_motor_enable(int id){
|
||||
if(id>0&&id<13){
|
||||
if(id>0&&id<NUM_SLAVES+1){
|
||||
return motor_enable_arr[id-1].load();
|
||||
}
|
||||
return false;
|
||||
}
|
||||
struct timespec timespec_add(struct timespec time1, struct timespec time2);
|
||||
private:
|
||||
std::chrono::high_resolution_clock::time_point rec_time;
|
||||
std::array<std::atomic<bool>, NUM_SLAVES> motor_enable_arr;
|
||||
std::vector<std::unordered_map<std::string, std::string>> getEcModuleParam(
|
||||
std::string & urdf, std::string component_name, std::string component_type);
|
||||
@@ -114,27 +119,75 @@ private:
|
||||
ec_domain_state_t domain1_state = {};
|
||||
ec_master_state_t master_state = {};
|
||||
ec_slave_config_state_t sc_state[NUM_SLAVES] = {};
|
||||
|
||||
bool all_motor_op=false;
|
||||
|
||||
std::mutex ec_mutex_;
|
||||
bool activated_;
|
||||
#define FREQUENCY 1000
|
||||
#define NSEC_PER_SEC (1000000000L)
|
||||
int32_t getValidCount_ze(uint8_t id){
|
||||
int32_t val=dst_rads[id]*rad_to_count+pos_offsets[id];
|
||||
if(id<NUM_SLAVES){
|
||||
int32_t min=pos_offsets[id]-262000;//262144
|
||||
int32_t max=pos_offsets[id]+262000;
|
||||
if(val<min){
|
||||
return min;
|
||||
}else if(val>max){
|
||||
return max;
|
||||
}
|
||||
}
|
||||
return val;
|
||||
};
|
||||
double getValidAngle(uint8_t id){
|
||||
double rad=hw_joint_commands_[id][2];
|
||||
if(id<NUM_SLAVES){
|
||||
if(id==2||id==8)
|
||||
rad=-rad;
|
||||
if(rad>M_PI){
|
||||
return M_PI-0.001;
|
||||
}else if(rad<-M_PI){
|
||||
return -M_PI+0.001;
|
||||
}
|
||||
}
|
||||
return rad;
|
||||
}
|
||||
std::atomic<bool> activated_{false};
|
||||
#define FREQUENCY 250
|
||||
#define CSP_MAX_VEL_COUNTS_PER_S 65536
|
||||
#define CSP_POS_DEADBAND 10 //CSP允许的误差(计数)
|
||||
#define CSP_POS_DEADBAND 10
|
||||
#define CSP_DEADBAND1 100//100 //CSP允许的误差(计数),原来是10
|
||||
#define CSP_DEADBAND2 1000 //300
|
||||
#define CSP_SPEED1 20//30
|
||||
#define CSP_SPEED2 100
|
||||
#define CLOCK_TO_USE CLOCK_MONOTONIC
|
||||
#define NSEC_PER_SEC (1000000000L)
|
||||
#define PERIOD_NS (NSEC_PER_SEC / FREQUENCY) //本次设置周期PERIOD_NS为1ms
|
||||
#define DIFF_NS(A, B) (((B).tv_sec - (A).tv_sec) * NSEC_PER_SEC + (B).tv_nsec - (A).tv_nsec)
|
||||
#define TIMESPEC2NS(T) ((uint64_t) (T).tv_sec * NSEC_PER_SEC + (T).tv_nsec)
|
||||
const struct timespec cycletime = {0, PERIOD_NS};
|
||||
uint16_t clear_cmd[NUM_SLAVES];
|
||||
uint16_t command[NUM_SLAVES]; //状态字掩码
|
||||
uint16_t status[NUM_SLAVES]; //状态字
|
||||
uint16_t last_status[NUM_SLAVES]; //上个循环的状态字
|
||||
int8_t last_mode_cmd[NUM_SLAVES] = {CYCLIC_VELOCITY};
|
||||
uint8_t reach_target[NUM_SLAVES];
|
||||
uint8_t op_states[NUM_SLAVES]={0};
|
||||
double dst_rads[NUM_SLAVES]={0};
|
||||
int32_t step_pos[NUM_SLAVES]={0};
|
||||
int32_t cur_pos[NUM_SLAVES]={0};
|
||||
double enable_arr[NUM_SLAVES]={0};
|
||||
int8_t mode_cmd=8;
|
||||
int inited = 0; //初始化
|
||||
unsigned int counter = 0;
|
||||
unsigned int sync_ref_counter = 0;
|
||||
bool has_clear_all=false;
|
||||
enum ErrState{
|
||||
ERR_NONE,
|
||||
ERR_ACK,
|
||||
ERR_ACK_WAIT,
|
||||
ERR_CLEAR,
|
||||
ERR_CLEAR_WAIT,
|
||||
ERR_FIN,
|
||||
ERR_FIN_WAIT
|
||||
};
|
||||
ErrState errStaArr[NUM_SLAVES]={ERR_NONE};
|
||||
};
|
||||
} // namespace ethercat_driver
|
||||
|
||||
@@ -2,6 +2,7 @@
|
||||
#include <math.h>
|
||||
#define NUM_SLAVES 12
|
||||
#define ZER_VID_PID 0x5a65726f,0x00029252
|
||||
#define YY_VID_PID 0x00001097,0x00002406
|
||||
typedef struct {
|
||||
unsigned int ctrl_word; // 0x6040:00
|
||||
unsigned int target_position; // 0x607A:00
|
||||
@@ -19,11 +20,14 @@ typedef struct {
|
||||
unsigned int reserved2; // 0xf0ff:00
|
||||
} zer_offset_t;
|
||||
|
||||
static zer_offset_t zer_offsets[12];
|
||||
|
||||
static zer_offset_t zer_offsets[NUM_SLAVES];
|
||||
static double rated_currents[NUM_SLAVES]={12.5,12.5,6.3,5.4,5.4,5.4,12.5,12.5,6.3,5.4,5.4,5.4};
|
||||
static double pos_offsets[NUM_SLAVES]={248214.0,358098.0,251704.0,240977.0,280113.0,54646.0, 211980.0,262157.0,281128.0,270017.0,268839.0,275363.0};
|
||||
//static double pos_offsets[NUM_SLAVES]={-13930.0, 95954.0, -10440.0, -21167.0, 17969.0, -207498.0, -50164.0, 13.0, 18984.0, 7873.0, 1553.0, 13219.0};
|
||||
constexpr double rad_to_count= 524288.0/(2*M_PI);
|
||||
constexpr double count_to_rad=2*M_PI/524288.0;
|
||||
|
||||
constexpr double speed_to_count=524288.0/(2*M_PI);//262144.0/(2*M_PI);
|
||||
constexpr double count_to_speed=2*M_PI/524288.0;//2*M_PI/262144.0;
|
||||
#define PDO_ENTRY(alias,position,index) \
|
||||
{alias,position, ZER_VID_PID, 0x6040, 0, &zer_offsets[index].ctrl_word,NULL}, \
|
||||
{alias,position, ZER_VID_PID, 0x607A, 0, &zer_offsets[index].target_position,NULL},\
|
||||
@@ -40,7 +44,7 @@ constexpr double count_to_rad=2*M_PI/524288.0;
|
||||
{alias,position, ZER_VID_PID, 0x6061, 0, &zer_offsets[index].modes_of_operation_display,NULL},\
|
||||
{alias,position, ZER_VID_PID, 0xf0ff, 0, &zer_offsets[index].reserved2,NULL},
|
||||
// ------------------- PDO 定义(CSV/CSP/CST),对应 0x1600/0x1A00 -------------------
|
||||
// 下列结构由IGH主站 cstruct 自动生成
|
||||
#if 1
|
||||
const static ec_pdo_entry_reg_t zer_domain1_regs[] = {
|
||||
PDO_ENTRY(0,1,0)
|
||||
PDO_ENTRY(0,2,1)
|
||||
@@ -57,7 +61,25 @@ const static ec_pdo_entry_reg_t zer_domain1_regs[] = {
|
||||
PDO_ENTRY(0,12,11)
|
||||
{} // 结束标记
|
||||
};
|
||||
#else
|
||||
const static ec_pdo_entry_reg_t zer_domain1_regs[] = {
|
||||
YY_PDO_ENTRY(0,1,0)
|
||||
PDO_ENTRY(0,2,1)
|
||||
PDO_ENTRY(0,3,2)
|
||||
PDO_ENTRY(0,4,3)
|
||||
PDO_ENTRY(0,5,4)
|
||||
PDO_ENTRY(0,6,5)
|
||||
PDO_ENTRY(0,7,6)
|
||||
|
||||
PDO_ENTRY(0,8,7)
|
||||
PDO_ENTRY(0,9,8)
|
||||
PDO_ENTRY(0,10,9)
|
||||
PDO_ENTRY(0,11,10)
|
||||
PDO_ENTRY(0,12,11)
|
||||
PDO_ENTRY(0,13,12)
|
||||
{} // 结束标记
|
||||
};
|
||||
#endif
|
||||
|
||||
static ec_pdo_entry_info_t zer_device_pdo_entries[] = {
|
||||
/*RxPdo 0x1600*/
|
||||
@@ -91,4 +113,4 @@ static ec_sync_info_t zer_device_syncs[] = {
|
||||
{2, EC_DIR_OUTPUT, 1, zer_device_pdos + 0, EC_WD_ENABLE},
|
||||
{3, EC_DIR_INPUT, 1, zer_device_pdos + 1, EC_WD_DISABLE},
|
||||
{0xff}
|
||||
};
|
||||
};
|
||||
55
ecrt_dev_dual/launch/dual_arm.launch.py
Normal file
55
ecrt_dev_dual/launch/dual_arm.launch.py
Normal file
@@ -0,0 +1,55 @@
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
def load_robot_desc():
|
||||
return {
|
||||
"robot_description": Command([
|
||||
FindExecutable(name="xacro"), " ",
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare("ecrt_driver"),
|
||||
"description", "motor_drive.config.xacro"
|
||||
])
|
||||
])
|
||||
}
|
||||
|
||||
def generate_launch_description():
|
||||
ld = LaunchDescription()
|
||||
ret=load_robot_desc()
|
||||
print(ret["robot_description"])
|
||||
ld.add_action(Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
parameters=[load_robot_desc(),
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare("ecrt_driver"),
|
||||
"config", "dual_arm_controllers.yaml"
|
||||
]),{"lock_memory": True,
|
||||
"thread_priority": 99,
|
||||
"cpu_affinity": 6}
|
||||
],
|
||||
output="both"))
|
||||
ld.add_action(Node(
|
||||
package="robot_state_publisher",
|
||||
executable="robot_state_publisher",
|
||||
parameters=[load_robot_desc()]))
|
||||
#状态发布
|
||||
jsb = Node(package="controller_manager", executable="spawner",
|
||||
arguments=["joint_state_broadcaster"])
|
||||
ld.add_action(jsb)
|
||||
#左右关节
|
||||
left = Node(package="controller_manager", executable="spawner",
|
||||
arguments=["left_arm_controller",'--inactive'])
|
||||
right = Node(package="controller_manager", executable="spawner",
|
||||
arguments=["right_arm_controller",'--inactive'])
|
||||
#左右gpio
|
||||
l_gpio = Node(package="controller_manager", executable="spawner",
|
||||
arguments=["left_arm_gpio_controller"])
|
||||
r_gpio = Node(package="controller_manager", executable="spawner",
|
||||
arguments=["right_arm_gpio_controller"])
|
||||
ld.add_action(left)
|
||||
ld.add_action(right)
|
||||
ld.add_action(l_gpio)
|
||||
ld.add_action(r_gpio)
|
||||
return ld
|
||||
@@ -12,7 +12,7 @@
|
||||
<depend>hardware_interface</depend>
|
||||
<depend>pluginlib</depend>
|
||||
<depend>rclcpp</depend>
|
||||
|
||||
<depend>rclcpp_action</depend>
|
||||
<depend>rclcpp_lifecycle</depend>
|
||||
<depend>ethercat_interface</depend>
|
||||
|
||||
484
ecrt_dev_dual/src/dual_motor.cpp
Normal file
484
ecrt_dev_dual/src/dual_motor.cpp
Normal file
@@ -0,0 +1,484 @@
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include <filesystem>
|
||||
#include <fstream> // 添加这行来支持文件流操作
|
||||
#include <time.h>
|
||||
#include <termios.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include "std_msgs/msg/string.hpp"
|
||||
#include "trajectory_msgs/msg/joint_trajectory.hpp"
|
||||
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
|
||||
#include "control_msgs/msg/dynamic_interface_group_values.hpp"
|
||||
#include "control_msgs/action/follow_joint_trajectory.hpp"
|
||||
#include "sensor_msgs/msg/joint_state.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
#include <controller_manager_msgs/srv/switch_controller.hpp>
|
||||
|
||||
namespace fs = std::filesystem;
|
||||
constexpr double rad_to_count= 524288.0/(2*M_PI);
|
||||
constexpr double count_to_rad=2*M_PI/524288.0;
|
||||
class TestMotor : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
TestMotor();
|
||||
~TestMotor();
|
||||
|
||||
int motor_dst(std::string name,double dst);//add by hehe
|
||||
//void ctrl_motor(int id,double pos,int reset,int enable);
|
||||
void left_clear(double clear);
|
||||
void left_enable(double enable);
|
||||
void right_clear(double clear);
|
||||
void right_enable(double enable);
|
||||
void motor_action(int id,double angle);
|
||||
void ControlLoop();
|
||||
bool activateController(const std::string& controller_name);
|
||||
void setJointValueTarget(double angle);
|
||||
void setJointValueTarget(const std::vector<double> angles);
|
||||
void pubTraj(const std::vector<double> angles1,const std::vector<double> angles2);
|
||||
void pubTraj(const double angle);
|
||||
bool motor_drv_on=false;
|
||||
bool all_motor_op=false;
|
||||
bool is_reach=false;
|
||||
std::unordered_map<std::string,double> curMap_;
|
||||
std::unordered_map<std::string,double> dstMap_;
|
||||
void left_pubTraj(const std::vector<double> angles);
|
||||
void right_pubTraj(const std::vector<double> angles);
|
||||
private:
|
||||
//rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr cmdPub_;
|
||||
rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr left_ctl_;
|
||||
rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr right_ctl_;
|
||||
///rclcpp::Publisher<control_msgs::msg::DynamicInterfaceGroupValues>::SharedPtr gpioPub_;
|
||||
rclcpp::Publisher<control_msgs::msg::DynamicInterfaceGroupValues>::SharedPtr left_gpio_;
|
||||
rclcpp::Publisher<control_msgs::msg::DynamicInterfaceGroupValues>::SharedPtr right_gpio_;
|
||||
|
||||
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr jointStatesSub_;
|
||||
//rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr left_state_;
|
||||
//rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr right_state_;
|
||||
|
||||
rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SharedPtr client_;
|
||||
rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_client;
|
||||
// 文件流相关
|
||||
std::ofstream data_file_; // 用于写入数据的文件流
|
||||
std::string data_file_path_; // 数据文件路径
|
||||
|
||||
rclcpp::TimerBase::SharedPtr controlTimer_;
|
||||
rclcpp::Time lastTime_; // 移至类成员
|
||||
struct termios original_termios_;
|
||||
|
||||
//add by hehe
|
||||
sensor_msgs::msg::JointState curJointSta_;
|
||||
int loop_cnt=0;
|
||||
//add by hehe end
|
||||
// 执行当前状态对应的动作
|
||||
void JointStatesCallback(const sensor_msgs::msg::JointState::SharedPtr msg);
|
||||
};
|
||||
|
||||
// 机器人控制器构造函数
|
||||
TestMotor::TestMotor() : Node("test_motor_node")
|
||||
{
|
||||
std::cout << "TestMotor Node is created!" << std::endl;
|
||||
// 创建发布者
|
||||
left_ctl_ = this->create_publisher<trajectory_msgs::msg::JointTrajectory>("/left_arm_controller/joint_trajectory", 10);
|
||||
right_ctl_ = this->create_publisher<trajectory_msgs::msg::JointTrajectory>("/right_arm_controller/joint_trajectory", 10);
|
||||
//action
|
||||
client_=rclcpp_action::create_client<control_msgs::action::FollowJointTrajectory>(this,"/trajectory_controller/follow_joint_trajectory");
|
||||
switch_client = create_client<controller_manager_msgs::srv::SwitchController>("/controller_manager/switch_controller");
|
||||
// 创建发布者
|
||||
//gpioPub_ = this->create_publisher<control_msgs::msg::DynamicInterfaceGroupValues>("/gpio_command_controller/commands", 10);
|
||||
left_gpio_=this->create_publisher<control_msgs::msg::DynamicInterfaceGroupValues>("/left_arm_gpio_controller/commands",10);
|
||||
right_gpio_=this->create_publisher<control_msgs::msg::DynamicInterfaceGroupValues>("right_arm_gpio_controller/commands",10);
|
||||
// 订阅仿真状态
|
||||
jointStatesSub_ = this->create_subscription<sensor_msgs::msg::JointState>("/joint_states", 10,std::bind(&TestMotor::JointStatesCallback, this, std::placeholders::_1));
|
||||
|
||||
lastTime_ = this->now(); // 初始化时间
|
||||
// 创建定时器,每10ms执行一次控制逻辑(频率100Hz)
|
||||
controlTimer_ = this->create_wall_timer(std::chrono::milliseconds(5000),std::bind(&TestMotor::ControlLoop, this)); // 绑定到新的控制函数);
|
||||
curMap_.clear();
|
||||
dstMap_.clear();
|
||||
//posMsg_.interface_groups.resize(12);
|
||||
//posMsg_.interface_values.resize(12);
|
||||
///std::cout << "start enblex ..." << std::endl;
|
||||
|
||||
std::cout << "TestMotor Node is created finished!" << std::endl;
|
||||
}
|
||||
|
||||
TestMotor::~TestMotor()
|
||||
{
|
||||
std::cout << "Robot controller stopped." << std::endl;
|
||||
}
|
||||
///std::vector<double> angles={-40, -40, -40, 0, -40, 0,40, 40, 40, 0, 40, 0};
|
||||
void TestMotor::JointStatesCallback(const sensor_msgs::msg::JointState::SharedPtr msg)
|
||||
{
|
||||
if (!msg) { // 检查消息是否有效
|
||||
std::cout << "get null joint states!" << std::endl;
|
||||
return;
|
||||
}
|
||||
if(msg->name.size()>0)
|
||||
motor_drv_on=true;
|
||||
//printf("motor_drv_on:%d\n",motor_drv_on);
|
||||
all_motor_op=true;
|
||||
for(int i=0;i<msg->name.size();i++)
|
||||
{
|
||||
curMap_[msg->name[i]] = msg->position[i];
|
||||
///std::cout<<"cur:"<<msg->name[i]<<":"<<curMap_[msg->name[i]]<<std::endl;
|
||||
if(curMap_[msg->name[i]]==9999.0)
|
||||
all_motor_op=false;
|
||||
}
|
||||
if(all_motor_op){
|
||||
if(is_reach){
|
||||
////pubTraj(angles);
|
||||
}
|
||||
}
|
||||
}
|
||||
bool TestMotor::activateController(const std::string& controller_name) {
|
||||
///std::cout<<"激活控制器"<<controller_name<<std::endl;
|
||||
auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
|
||||
request->activate_controllers = {controller_name};
|
||||
request->deactivate_controllers = {};
|
||||
request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
|
||||
request->activate_asap = true;
|
||||
request->timeout = rclcpp::Duration::from_seconds(5.0);
|
||||
|
||||
auto future = switch_client->async_send_request(request);
|
||||
auto result = future.get();
|
||||
return result->ok;
|
||||
}
|
||||
void TestMotor::left_pubTraj(const std::vector<double> angles){
|
||||
trajectory_msgs::msg::JointTrajectory traj_msg;
|
||||
///traj_msg.header.stamp = this->now();
|
||||
traj_msg.joint_names = {"left_arm_joint_1", "left_arm_joint_2", "left_arm_joint_3", "left_arm_joint_4", "left_arm_joint_5", "left_arm_joint_6"};
|
||||
trajectory_msgs::msg::JointTrajectoryPoint point;
|
||||
for(int i=0;i<6;i++){
|
||||
std::string jname = "left_arm_joint_" + std::to_string(i+1);
|
||||
dstMap_[jname]=angles.at(i)*M_PI/180.0;
|
||||
double rad=curMap_[jname];
|
||||
rad=dstMap_[jname];
|
||||
point.positions.push_back(rad);
|
||||
printf("D %s: %.2f-->%.2f\n",jname.c_str(),curMap_[jname],rad);
|
||||
}
|
||||
traj_msg.points.push_back(point);
|
||||
left_ctl_->publish(traj_msg);
|
||||
}
|
||||
void TestMotor::right_pubTraj(const std::vector<double> angles){
|
||||
trajectory_msgs::msg::JointTrajectory traj_msg;
|
||||
///traj_msg.header.stamp = this->now();
|
||||
traj_msg.joint_names = {"right_arm_joint_1", "right_arm_joint_2", "right_arm_joint_3", "right_arm_joint_4", "right_arm_joint_5", "right_arm_joint_6"};
|
||||
trajectory_msgs::msg::JointTrajectoryPoint point;
|
||||
for(int i=0;i<6;i++){
|
||||
std::string jname = "right_arm_joint_" + std::to_string(i+1);
|
||||
dstMap_[jname]=angles.at(i)*M_PI/180.0;
|
||||
double rad=curMap_[jname];
|
||||
rad=dstMap_[jname];
|
||||
point.positions.push_back(rad);
|
||||
printf("D %s: %.2f-->%.2f\n",jname.c_str(),curMap_[jname],rad);
|
||||
}
|
||||
traj_msg.points.push_back(point);
|
||||
right_ctl_->publish(traj_msg);
|
||||
}
|
||||
// 状态机主循环
|
||||
void TestMotor::ControlLoop() {
|
||||
//Gpio_publish_joint_trajectory();
|
||||
////all_motor();
|
||||
}
|
||||
void TestMotor::left_clear(double clear)
|
||||
{
|
||||
control_msgs::msg::DynamicInterfaceGroupValues gpioMsg_;
|
||||
//std::cout<<"fault:";
|
||||
for(int i=0;i<6;i++){
|
||||
std::string tempInterfaceGroup = "left_arm_joint_" + std::to_string(i+1);
|
||||
gpioMsg_.interface_groups.push_back(tempInterfaceGroup);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
//reset
|
||||
tempValue.interface_names = {"fault"};
|
||||
tempValue.values = {clear};
|
||||
std::cout<<tempInterfaceGroup<<":"<<tempValue.values[0]<<",";
|
||||
gpioMsg_.interface_values.push_back(tempValue);
|
||||
}
|
||||
std::cout<<std::endl;
|
||||
left_gpio_->publish(gpioMsg_);
|
||||
usleep(50000);
|
||||
}
|
||||
void TestMotor::left_enable(double enable)
|
||||
{
|
||||
control_msgs::msg::DynamicInterfaceGroupValues gpioMsg_;
|
||||
////std::cout<<"enable:";
|
||||
for(int i=0;i<6;i++){
|
||||
std::string tempInterfaceGroup = "left_arm_joint_" + std::to_string(i+1);
|
||||
gpioMsg_.interface_groups.push_back(tempInterfaceGroup);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
tempValue.interface_names = {"enable"};
|
||||
tempValue.values = {enable};
|
||||
gpioMsg_.interface_values.push_back(tempValue);
|
||||
}
|
||||
left_gpio_->publish(gpioMsg_);
|
||||
usleep(1000000);
|
||||
}
|
||||
|
||||
void TestMotor::right_clear(double clear)
|
||||
{
|
||||
control_msgs::msg::DynamicInterfaceGroupValues gpioMsg_;
|
||||
//std::cout<<"fault:";
|
||||
for(int i=0;i<6;i++){
|
||||
std::string tempInterfaceGroup = "right_arm_joint_" + std::to_string(i+1);
|
||||
gpioMsg_.interface_groups.push_back(tempInterfaceGroup);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
//reset
|
||||
tempValue.interface_names = {"fault"};
|
||||
tempValue.values = {clear};
|
||||
std::cout<<tempInterfaceGroup<<":"<<tempValue.values[0]<<",";
|
||||
gpioMsg_.interface_values.push_back(tempValue);
|
||||
}
|
||||
std::cout<<std::endl;
|
||||
right_gpio_->publish(gpioMsg_);
|
||||
usleep(50000);
|
||||
}
|
||||
void TestMotor::right_enable(double enable)
|
||||
{
|
||||
control_msgs::msg::DynamicInterfaceGroupValues gpioMsg_;
|
||||
////std::cout<<"enable:";
|
||||
for(int i=0;i<6;i++){
|
||||
std::string tempInterfaceGroup = "right_arm_joint_" + std::to_string(i+1);
|
||||
gpioMsg_.interface_groups.push_back(tempInterfaceGroup);
|
||||
control_msgs::msg::InterfaceValue tempValue;
|
||||
tempValue.interface_names = {"enable"};
|
||||
tempValue.values = {enable};
|
||||
gpioMsg_.interface_values.push_back(tempValue);
|
||||
}
|
||||
right_gpio_->publish(gpioMsg_);
|
||||
usleep(1000000);
|
||||
}
|
||||
void TestMotor::setJointValueTarget(std::vector<double> angles){
|
||||
return;
|
||||
if(client_->wait_for_action_server(std::chrono::seconds(5))){
|
||||
auto goal=control_msgs::action::FollowJointTrajectory::Goal();
|
||||
goal.trajectory.joint_names={"joint_1","joint_2","joint_3","joint_4","joint_5","joint_6","joint_7","joint_8","joint_9","joint_10","joint_11","joint_12"};
|
||||
trajectory_msgs::msg::JointTrajectoryPoint point;
|
||||
// for(int i=0;i<12;i++){
|
||||
// std::string joint="joint_"+std::to_string(i+1);
|
||||
// double rad=angles.at(i)*M_PI/180.0;
|
||||
// point.positions.push_back(rad);
|
||||
// printf("D %s: %.2f/%.2f\n",joint.c_str(),curMap_[joint],point.positions[i]);
|
||||
// }
|
||||
double delta=0.01;
|
||||
for(int i=0;i<12;i++){
|
||||
std::string jname = "joint_" + std::to_string(i+1);
|
||||
dstMap_[jname]=angles.at(i)*M_PI/180.0;
|
||||
double rad=0.0;
|
||||
double diff=dstMap_[jname]-curMap_[jname];
|
||||
if(diff<-0.03)
|
||||
rad= curMap_[jname]-delta;
|
||||
else if(diff>0.03)
|
||||
rad= curMap_[jname]+delta;
|
||||
point.positions.push_back(rad);
|
||||
printf("D %s: %.2f/%.2f\n",jname.c_str(),curMap_[jname],point.positions[i]);
|
||||
}
|
||||
|
||||
|
||||
|
||||
goal.trajectory.points.push_back(point);
|
||||
auto send_goal_option=rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SendGoalOptions();
|
||||
send_goal_option.goal_response_callback=[this](auto res){
|
||||
auto goal_handle=res.get();
|
||||
if(goal_handle){
|
||||
printf("goal has be accept!!!\n");
|
||||
}
|
||||
};
|
||||
send_goal_option.feedback_callback=[this](auto,auto feedback){
|
||||
for(int i=0;i<12;i++){
|
||||
printf("%s,%.3f/%.3f\n",feedback->joint_names[i].c_str(),feedback->desired.positions[i],feedback->actual.positions[i]);
|
||||
}
|
||||
};
|
||||
send_goal_option.result_callback=[this](auto ret){
|
||||
if(ret.code==rclcpp_action::ResultCode::SUCCEEDED)
|
||||
printf("action ret succeed\n");
|
||||
else if(ret.code==rclcpp_action::ResultCode::ABORTED)
|
||||
printf("action ret aborted\n");
|
||||
};
|
||||
//client_->async_send_goal(goal,send_goal_option);
|
||||
client_->async_send_goal(goal,send_goal_option);
|
||||
}else{
|
||||
printf("wait action server error\n");
|
||||
}
|
||||
}
|
||||
void TestMotor::setJointValueTarget(double angle){
|
||||
return;
|
||||
if(client_->wait_for_action_server(std::chrono::seconds(5))){
|
||||
auto goal=control_msgs::action::FollowJointTrajectory::Goal();
|
||||
goal.trajectory.joint_names={"joint_1","joint_2","joint_3","joint_4","joint_5","joint_6","joint_7","joint_8","joint_9","joint_10","joint_11","joint_12"};
|
||||
trajectory_msgs::msg::JointTrajectoryPoint point;
|
||||
for(int i=0;i<12;i++){
|
||||
std::string joint="joint_"+std::to_string(i+1);
|
||||
point.positions.push_back(angle);
|
||||
printf("S %s: %.2f/%.2f\n",joint.c_str(),curMap_[joint],point.positions[i]);
|
||||
}
|
||||
goal.trajectory.points.push_back(point);
|
||||
auto send_goal_option=rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SendGoalOptions();
|
||||
send_goal_option.goal_response_callback=[this](auto res){
|
||||
auto goal_handle=res.get();
|
||||
if(goal_handle){
|
||||
printf("goal has be accept!!!\n");
|
||||
}
|
||||
};
|
||||
send_goal_option.feedback_callback=[this](auto,auto feedback){
|
||||
for(int i=0;i<12;i++){
|
||||
printf("%s,%.3f/%.3f\n",feedback->joint_names[i].c_str(),feedback->desired.positions[i],feedback->actual.positions[i]);
|
||||
}
|
||||
};
|
||||
send_goal_option.result_callback=[this](auto ret){
|
||||
if(ret.code==rclcpp_action::ResultCode::SUCCEEDED)
|
||||
printf("action ret succeed\n");
|
||||
else if(ret.code==rclcpp_action::ResultCode::ABORTED)
|
||||
printf("action ret aborted\n");
|
||||
};
|
||||
client_->async_send_goal(goal,send_goal_option);
|
||||
}else{
|
||||
printf("wait action server error\n");
|
||||
}
|
||||
}
|
||||
void TestMotor::motor_action(int id,double delta)
|
||||
{
|
||||
return;
|
||||
//std::cout<<"motor_action:"<<id<<","<<delta<<std::endl;
|
||||
if(client_->wait_for_action_server(std::chrono::seconds(5))){
|
||||
auto goal=control_msgs::action::FollowJointTrajectory::Goal();
|
||||
goal.trajectory.joint_names={"joint_1","joint_2","joint_3","joint_4","joint_5","joint_6","joint_7","joint_8","joint_9","joint_10","joint_11","joint_12"};
|
||||
trajectory_msgs::msg::JointTrajectoryPoint point;
|
||||
for(int i=0;i<12;i++){
|
||||
std::string joint="joint_"+std::to_string(i+1);
|
||||
//if(id==(i+1))
|
||||
if(i<12)
|
||||
point.positions.push_back(curMap_[joint]+delta);
|
||||
else
|
||||
point.positions.push_back(curMap_[joint]);
|
||||
printf("%s: %.2f/%.2f\n",joint.c_str(),curMap_[joint],point.positions[i]);
|
||||
}
|
||||
goal.trajectory.points.push_back(point);
|
||||
auto send_goal_option=rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SendGoalOptions();
|
||||
send_goal_option.goal_response_callback=[this](auto res){
|
||||
auto goal_handle=res.get();
|
||||
if(goal_handle){
|
||||
printf("goal has be accept!!!\n");
|
||||
}
|
||||
};
|
||||
send_goal_option.feedback_callback=[this](auto,auto feedback){
|
||||
for(int i=0;i<12;i++){
|
||||
printf("%s,%.3f/%.3f\n",feedback->joint_names[i].c_str(),feedback->desired.positions[i],feedback->actual.positions[i]);
|
||||
}
|
||||
};
|
||||
send_goal_option.result_callback=[this](auto ret){
|
||||
if(ret.code==rclcpp_action::ResultCode::SUCCEEDED)
|
||||
printf("action ret succeed\n");
|
||||
else if(ret.code==rclcpp_action::ResultCode::ABORTED)
|
||||
printf("action ret aborted\n");
|
||||
};
|
||||
client_->async_send_goal(goal,send_goal_option);
|
||||
}else{
|
||||
printf("wait action server error\n");
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc,char* argv[]){
|
||||
rclcpp::init(argc,argv);
|
||||
auto node=std::make_shared<TestMotor>();
|
||||
auto spin_thread=std::thread([=](){
|
||||
rclcpp::spin(node);
|
||||
});
|
||||
std::cout<<"等待电机驱动启动...\n";
|
||||
while(rclcpp::ok()&&!node->motor_drv_on){
|
||||
sleep(1);
|
||||
}
|
||||
std::cout<<"电机驱动启动完毕!\n等待电机进入OP...\n";
|
||||
//std::cout<<""<<std::endl;
|
||||
while(rclcpp::ok()&&!node->all_motor_op){
|
||||
sleep(1);
|
||||
}
|
||||
std::cout<<"电机进入OP!\n切换控制器...\n";
|
||||
///bool ret=node->activateController("trajectory_controller");
|
||||
//if(ret)
|
||||
{
|
||||
|
||||
std::vector<double> angles1={0, 0, 0, 0, 0, 0};
|
||||
std::vector<double> angles2={90,0, 40, 0, 0, 0};
|
||||
#if 0
|
||||
node->is_reach=true;
|
||||
static int loop_cnt=0;
|
||||
while(rclcpp::ok()){
|
||||
std::cout<<"开始执行角度1.05...\n";
|
||||
loop_cnt+=1;
|
||||
if(loop_cnt%2==0){
|
||||
angles1={-40, -40, -40,-40,-40,-40};
|
||||
angles2={-40,-40,-40, -40,-40,-40};
|
||||
}else{
|
||||
angles1={40, 40, 40,40,40,40};
|
||||
angles2={40,40,40, 40,40,40};
|
||||
}
|
||||
angles1={10, 20, 30,40,50,60};
|
||||
angles2={40,40,40, 40,40,40};
|
||||
std::cout<<"开始动作...\n";
|
||||
///node->left_pubTraj(angles1);
|
||||
sleep(2);
|
||||
node->right_pubTraj(angles1);
|
||||
sleep(10);
|
||||
std::cout<<"开始执行复位...\n";
|
||||
angles1={0, 0, 0, 0, 0, 0};
|
||||
angles2={0, 0, 0,0, 0, 0};
|
||||
///node->left_pubTraj(angles1);
|
||||
sleep(2);
|
||||
////node->right_pubTraj(angles2);
|
||||
sleep(10);
|
||||
}
|
||||
#endif
|
||||
#if 1
|
||||
sleep(1);
|
||||
node->activateController("left_arm_controller");
|
||||
std::cout<<"左臂测试...\n";
|
||||
///node->left_clear(1);
|
||||
node->left_enable(1);
|
||||
angles1={-40, -40, -40,0,-40,0};
|
||||
node->left_pubTraj(angles1);
|
||||
sleep(4);
|
||||
std::cout<<"左臂回位...\n";
|
||||
angles1={0, 0, 0, 0, 0, 0};
|
||||
node->left_pubTraj(angles1);
|
||||
sleep(4);
|
||||
node->left_enable(0);
|
||||
std::cout<<"左臂测试完毕!\n";
|
||||
#endif
|
||||
sleep(2);
|
||||
node->activateController("right_arm_controller");
|
||||
std::cout<<"左臂测试...\n";
|
||||
///node->left_clear(1);
|
||||
angles1={-40, -40, -40,0,-40,0};
|
||||
node->right_pubTraj(angles1);
|
||||
node->right_enable(1);
|
||||
sleep(4);
|
||||
std::cout<<"左臂回位...\n";
|
||||
angles1={0, 0, 0, 0, 0, 0};
|
||||
node->right_pubTraj(angles1);
|
||||
sleep(4);
|
||||
node->right_enable(0);
|
||||
std::cout<<"左臂测试完毕!\n";
|
||||
sleep(2);
|
||||
std::cout<<"双臂同时测试...\n";
|
||||
node->left_enable(1);
|
||||
node->right_enable(1);
|
||||
angles1={40, 40, 40,0,40,0};
|
||||
node->left_pubTraj(angles1);
|
||||
node->right_pubTraj(angles1);
|
||||
sleep(4);
|
||||
std::cout<<"双臂回位...\n";
|
||||
angles1={0, 0, 0, 0, 0, 0};
|
||||
node->left_pubTraj(angles1);
|
||||
node->right_pubTraj(angles1);
|
||||
sleep(4);
|
||||
node->left_enable(0);
|
||||
node->right_enable(0);
|
||||
std::cout<<"双臂测试完毕!\n";
|
||||
}
|
||||
///usleep(10000000);
|
||||
///node->all_motor();
|
||||
rclcpp::shutdown();
|
||||
spin_thread.join();
|
||||
return 0;
|
||||
}
|
||||
@@ -1,4 +1,9 @@
|
||||
|
||||
#include <sys/mman.h> // 用于 mlockall
|
||||
#include <pthread.h> // 用于线程优先级设置
|
||||
#include <sched.h> // 用于调度策略
|
||||
#include <cstring> // 用于 strerror
|
||||
#include <unistd.h> // 用于 getpid
|
||||
#include <sys/resource.h>
|
||||
#include "ethercat_driver/ethercat_driver.hpp"
|
||||
#include <tinyxml2.h>
|
||||
#include <string>
|
||||
@@ -6,18 +11,41 @@
|
||||
#include"ecrt.h"
|
||||
#include "hardware_interface/types/hardware_interface_type_values.hpp"
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
#include <chrono>
|
||||
#include<sstream>
|
||||
static std::stringstream logStream;
|
||||
namespace ethercat_driver
|
||||
{
|
||||
CallbackReturn EthercatDriver::on_init(
|
||||
const hardware_interface::HardwareInfo & info)
|
||||
CallbackReturn EthercatDriver::on_init(const hardware_interface::HardwareInfo & info)
|
||||
{
|
||||
if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) {
|
||||
return CallbackReturn::ERROR;
|
||||
}
|
||||
|
||||
cpu_set_t cpuset;
|
||||
CPU_ZERO(&cpuset);
|
||||
int cpu_core=7;
|
||||
CPU_SET(cpu_core, &cpuset);
|
||||
if (pthread_setaffinity_np(pthread_self(), sizeof(cpu_set_t), &cpuset) != 0) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("hehe"), "Failed to set CPU affinity to core %d!", cpu_core);
|
||||
return CallbackReturn::ERROR;
|
||||
}
|
||||
|
||||
struct sched_param param;
|
||||
param.sched_priority = 90;
|
||||
|
||||
if (pthread_setschedparam(pthread_self(), SCHED_FIFO, ¶m) != 0) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("EthercatDriver"),
|
||||
"Failed to set real-time priority: %s", strerror(errno));
|
||||
return CallbackReturn::ERROR;
|
||||
}
|
||||
|
||||
if (mlockall(MCL_CURRENT | MCL_FUTURE) != 0) {
|
||||
RCLCPP_WARN(rclcpp::get_logger("EthercatDriver"),
|
||||
"Failed to lock memory: %s", strerror(errno));
|
||||
}
|
||||
const std::lock_guard<std::mutex> lock(ec_mutex_);
|
||||
activated_ = false;
|
||||
activated_.store(false,std::memory_order_relaxed);
|
||||
for(int i=0;i<NUM_SLAVES;i++){
|
||||
set_motor_enable(i+1,false);
|
||||
}
|
||||
@@ -60,7 +88,7 @@ CallbackReturn EthercatDriver::on_init(
|
||||
info_.gpios[g].command_interfaces.size(),
|
||||
std::numeric_limits<double>::quiet_NaN());
|
||||
}
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints.size:%d,%d,%d",info_.joints.size(),info_.joints[0].state_interfaces.size(),info_.joints[1].state_interfaces.size());
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints.size:%ld,%ld,%ld",info_.joints.size(),info_.joints[0].state_interfaces.size(),info_.joints[1].state_interfaces.size());
|
||||
for (uint j = 0; j < info_.joints.size(); j++) {
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints");
|
||||
// check all joints for EC modules and load into ec_modules_
|
||||
@@ -78,7 +106,7 @@ RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints.size:%d,%d,%d",info_.j
|
||||
}
|
||||
}
|
||||
}
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "gpios.size:%d",info_.gpios.size());
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "gpios.size:%ld",info_.gpios.size());
|
||||
for (uint g = 0; g < info_.gpios.size(); g++) {
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "gpios");
|
||||
// check all gpios for EC modules and load into ec_modules_
|
||||
@@ -96,7 +124,7 @@ RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints.size:%d,%d,%d",info_.j
|
||||
}
|
||||
}
|
||||
}
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "sensors.size:%d",info_.joints.size());
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "sensors.size:%ld",info_.joints.size());
|
||||
for (uint s = 0; s < info_.sensors.size(); s++) {
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "sensors");
|
||||
// check all sensors for EC modules and load into ec_modules_
|
||||
@@ -126,21 +154,24 @@ RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints.size:%d,%d,%d",info_.j
|
||||
perror("ecrt_master_create_domain");
|
||||
//g_started.store(false); return false;
|
||||
}
|
||||
const uint32_t shift_step = PERIOD_NS / 12;
|
||||
for (int i = 0; i < NUM_SLAVES; i++) {
|
||||
std::cout << "Configuring slave " << i << "..." << std::endl;
|
||||
std::cout << "Configuring slave " << i+1 << "..." << std::endl;
|
||||
{
|
||||
sc[i] = ecrt_master_slave_config(master, 0, i+1, ZER_VID_PID);
|
||||
if (!sc[i])
|
||||
{
|
||||
std::cout << "Failed slave cfg at pos " << i << std::endl;
|
||||
std::cout << "Failed slave cfg at position " << i << std::endl;
|
||||
}
|
||||
if (ecrt_slave_config_pdos(sc[i], EC_END, zer_device_syncs))
|
||||
{
|
||||
std::cout << "Failed PDO config " << i << std::endl;
|
||||
}
|
||||
}
|
||||
ecrt_slave_config_dc(sc[i], 0x0300, PERIOD_NS, 200, 0, 0);
|
||||
ecrt_slave_config_dc(sc[i], 0x0300, PERIOD_NS, 20000, 0, 0);
|
||||
//ecrt_slave_config_dc(sc[i], 0x0700, PERIOD_NS, 5000, PERIOD_NS/2, 0);
|
||||
}
|
||||
///ecrt_master_set_send_interval(master, PERIOD_NS);
|
||||
ecrt_domain_reg_pdo_entry_list(domain1,zer_domain1_regs);
|
||||
if (ecrt_master_activate(master)) {
|
||||
perror("ecrt_master_activate");
|
||||
@@ -159,18 +190,20 @@ RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints.size:%d,%d,%d",info_.j
|
||||
CallbackReturn EthercatDriver::on_configure(
|
||||
const rclcpp_lifecycle::State & /*previous_state*/)
|
||||
{
|
||||
RCLCPP_INFO(rclcpp::get_logger("hehe"),"on configure......");
|
||||
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
std::vector<hardware_interface::StateInterface>
|
||||
EthercatDriver::export_state_interfaces()
|
||||
{
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "#######export_state_interfaces:%d,%d,%d",info_.joints.size(),info_.sensors.size(),info_.gpios.size());
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "#######export_state_interfaces:%ld,%ld,%ld",info_.joints.size(),info_.sensors.size(),info_.gpios.size());
|
||||
std::vector<hardware_interface::StateInterface> state_interfaces;
|
||||
// export joint state interface
|
||||
for (uint j = 0; j < info_.joints.size(); j++) {
|
||||
for (uint i = 0; i < info_.joints[j].state_interfaces.size(); i++) {
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"export:%s,%s\n",info_.joints[j].name.c_str(),info_.joints[j].state_interfaces[i].name.c_str());
|
||||
////RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"export:%s,%s",info_.joints[j].name.c_str(),info_.joints[j].state_interfaces[i].name.c_str());
|
||||
state_interfaces.emplace_back(
|
||||
hardware_interface::StateInterface(
|
||||
info_.joints[j].name,
|
||||
@@ -204,7 +237,7 @@ EthercatDriver::export_state_interfaces()
|
||||
std::vector<hardware_interface::CommandInterface>
|
||||
EthercatDriver::export_command_interfaces()
|
||||
{
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "#######export_command_interfaces:%d",info_.joints.size());
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "#######export_command_interfaces:%ld",info_.joints.size());
|
||||
std::vector<hardware_interface::CommandInterface> command_interfaces;
|
||||
// export joint command interface
|
||||
///std::vector<double> test;
|
||||
@@ -220,7 +253,7 @@ RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "#######export_command_interfa
|
||||
for (uint j = 0; j < info_.joints.size(); j++) {
|
||||
////RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"size:%d\n",info_.joints[j].command_interfaces.size());
|
||||
for (uint i = 0; i < info_.joints[j].command_interfaces.size(); i++) {
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"joints:%s,%s\n",info_.joints[j].name.c_str(),info_.joints[j].command_interfaces[i].name.c_str());
|
||||
///RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"joints:%s,%s",info_.joints[j].name.c_str(),info_.joints[j].command_interfaces[i].name.c_str());
|
||||
command_interfaces.emplace_back(
|
||||
hardware_interface::CommandInterface(
|
||||
info_.joints[j].name,
|
||||
@@ -241,7 +274,7 @@ RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "#######export_command_interfa
|
||||
// export gpio command interface
|
||||
for (uint g = 0; g < info_.gpios.size(); g++) {
|
||||
for (uint i = 0; i < info_.gpios[g].command_interfaces.size(); i++) {
|
||||
printf("gpios:%s,%s\n",info_.gpios[g].name,info_.gpios[g].command_interfaces[i].name);
|
||||
///printf("gpios:%s,%s\n",info_.gpios[g].name,info_.gpios[g].command_interfaces[i].name);
|
||||
command_interfaces.emplace_back(
|
||||
hardware_interface::CommandInterface(
|
||||
info_.gpios[g].name,
|
||||
@@ -256,7 +289,7 @@ CallbackReturn EthercatDriver::on_activate(
|
||||
const rclcpp_lifecycle::State & /*previous_state*/)
|
||||
{
|
||||
const std::lock_guard<std::mutex> lock(ec_mutex_);
|
||||
if (activated_) {
|
||||
if (activated_.load(std::memory_order_relaxed)) {
|
||||
RCLCPP_FATAL(rclcpp::get_logger("EthercatDriver"), "Double on_activate()");
|
||||
return CallbackReturn::ERROR;
|
||||
}
|
||||
@@ -266,7 +299,7 @@ CallbackReturn EthercatDriver::on_activate(
|
||||
} else {
|
||||
control_frequency_ = std::stod(info_.hardware_parameters["control_frequency"]);
|
||||
}
|
||||
control_frequency_=1000;
|
||||
control_frequency_=FREQUENCY;
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"control_frequency_:%d\n",control_frequency_);
|
||||
if (control_frequency_ < 0) {
|
||||
RCLCPP_FATAL(
|
||||
@@ -275,10 +308,18 @@ CallbackReturn EthercatDriver::on_activate(
|
||||
}
|
||||
clock_gettime(CLOCK_TO_USE, &wakeupTime);
|
||||
for(int i=0;i<NUM_SLAVES;i++){
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"slave:%d,ctl offset:%p,sta offset:%p\n",i,zer_offsets[i].ctrl_word,zer_offsets[i].status_word);
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"slave:%d,ctl offset:%d,sta offset:%d\n",i,zer_offsets[i].ctrl_word,zer_offsets[i].status_word);
|
||||
}
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"activate finish");
|
||||
activated_ = true;
|
||||
|
||||
|
||||
for(int i=0;i<info_.joints.size();i++){
|
||||
for(int j=0;j<info_.joints[i].command_interfaces.size();j++)
|
||||
hw_joint_commands_[i][j]=0.0;
|
||||
}
|
||||
for(int i=0;i<NUM_SLAVES;i++)
|
||||
RCLCPP_INFO(rclcpp::get_logger("hehe"),"hw_joint_commands_[i][2]:%.1f",hw_joint_commands_[i][2]);
|
||||
activated_.store(true,std::memory_order_relaxed);
|
||||
all_motor_op=false;
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
@@ -288,6 +329,7 @@ CallbackReturn EthercatDriver::on_deactivate(
|
||||
const std::lock_guard<std::mutex> lock(ec_mutex_);
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "SSSSSSSSSSSSSSSSSSSSSSSS...");
|
||||
for(int i=0;i<NUM_SLAVES;i++){
|
||||
///RCLCPP_INFO(rclcpp::get_logger("hehe"),"close state:%.1f",hw_joint_states_[i][0]);
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0007);
|
||||
// CSV 安全:速度清零
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_velocity, 0);
|
||||
@@ -298,7 +340,7 @@ CallbackReturn EthercatDriver::on_deactivate(
|
||||
EC_WRITE_S16(domain1_pd + zer_offsets[i].target_torque, 0);
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0007);//切换 switched on 状态
|
||||
}
|
||||
activated_ = false;
|
||||
activated_.store(false,std::memory_order_relaxed);
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "System successfully stopped!");
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
@@ -310,11 +352,16 @@ hardware_interface::return_type EthercatDriver::read(
|
||||
const rclcpp::Duration & /*period*/)
|
||||
{
|
||||
// try to lock so we can avoid blocking the read/write loop on the lock.
|
||||
const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
|
||||
////const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
|
||||
//printf("read data...\n");
|
||||
if (lock.owns_lock() && activated_) {
|
||||
////master_.readData();
|
||||
//if (lock.owns_lock() && activated_) {
|
||||
if (activated_.load(std::memory_order_relaxed)){
|
||||
auto start=std::chrono::high_resolution_clock::now();
|
||||
readData();
|
||||
auto end=std::chrono::high_resolution_clock::now();
|
||||
auto diff=end-start;
|
||||
if(diff.count()>120000)
|
||||
RCLCPP_INFO(rclcpp::get_logger("Ethercat"),"rdiff:%ld",diff.count());
|
||||
}
|
||||
return hardware_interface::return_type::OK;
|
||||
}
|
||||
@@ -346,20 +393,26 @@ void EthercatDriver::check_master_state(void)
|
||||
|
||||
master_state = ms;
|
||||
}
|
||||
void EthercatDriver::check_slave_config_states(void)
|
||||
bool EthercatDriver::check_slave_config_states(void)
|
||||
{
|
||||
ec_slave_config_state_t s;
|
||||
bool all_op=true;
|
||||
for (int i = 0; i < NUM_SLAVES; ++i) {
|
||||
errStaArr[i]=ERR_NONE;
|
||||
if (!sc[i]) continue;
|
||||
ecrt_slave_config_state(sc[i], &s);
|
||||
if (s.al_state != sc_state[i].al_state)
|
||||
//printf("[S%02d] State 0x%02X.\n", i, s.al_state);
|
||||
if (s.online != sc_state[i].online)
|
||||
//printf("[S%02d] %s.\n", i, s.online ? "online" : "offline");
|
||||
if (s.operational != sc_state[i].operational)
|
||||
//printf("[S%02d] %soperational.\n", i, s.operational ? "" : "Not ");
|
||||
if ((s.al_state != sc_state[i].al_state)||(s.online != sc_state[i].online)||(s.operational != sc_state[i].operational)){
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"[S%02d] %s,State 0x%02X,OP %s", i, s.online ? "online" : "offline",s.al_state,s.operational ? "OK" : "ERR");
|
||||
}
|
||||
sc_state[i] = s;
|
||||
if(!s.operational){
|
||||
op_states[i]=0;
|
||||
all_op=false;
|
||||
}else{
|
||||
op_states[i]=1;
|
||||
}
|
||||
}
|
||||
return all_op;
|
||||
}
|
||||
struct timespec EthercatDriver::timespec_add(struct timespec time1, struct timespec time2)
|
||||
{
|
||||
@@ -376,44 +429,51 @@ struct timespec EthercatDriver::timespec_add(struct timespec time1, struct times
|
||||
return result;
|
||||
}
|
||||
void EthercatDriver::readData(){
|
||||
|
||||
#if 0
|
||||
static int print_cnt=0;
|
||||
if(print_cnt++%1000==0){
|
||||
for(int i=0;i<info_.joints.size();i++){
|
||||
printf("[%d]%s:",i,info_.joints[i].name.c_str());
|
||||
for(int j=0;j<info_.joints[i].command_interfaces.size();j++)
|
||||
printf("%.2f,",hw_joint_commands_[i][j]);
|
||||
printf("\n");
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
#endif
|
||||
print_cnt+=1;
|
||||
|
||||
#if 1
|
||||
wakeupTime = timespec_add(wakeupTime, cycletime);
|
||||
clock_nanosleep(CLOCK_TO_USE, TIMER_ABSTIME, &wakeupTime, NULL); //使用绝对时间,精确等待下一个周期,避免循环执行的时间造成周期漂移
|
||||
ecrt_master_application_time(master, TIMESPEC2NS(wakeupTime)); // 更新主站应用时间
|
||||
ecrt_master_receive(master); //接收 EtherCAT 帧
|
||||
ecrt_domain_process(domain1); //处理域数据
|
||||
// check process data state (optional)
|
||||
check_domain1_state(); //检查域状态
|
||||
////clock_nanosleep(CLOCK_TO_USE, TIMER_ABSTIME, &wakeupTime, NULL);
|
||||
ecrt_master_application_time(master, TIMESPEC2NS(wakeupTime));
|
||||
#endif
|
||||
ecrt_master_receive(master);
|
||||
ecrt_domain_process(domain1);
|
||||
check_domain1_state();
|
||||
if (counter) {
|
||||
counter--;
|
||||
} else { // do this at 1 Hz
|
||||
counter = FREQUENCY;
|
||||
// check for master state (optional)
|
||||
//check_master_state(); //检查主站状态
|
||||
// check for slave configuration state(s)
|
||||
//check_slave_config_states(); //检查从站状态
|
||||
check_master_state();
|
||||
if(all_motor_op){
|
||||
if(!has_clear_all){
|
||||
has_clear_all=true;
|
||||
for (int i = 0; i < NUM_SLAVES; ++i) {
|
||||
reach_target[i]=1;
|
||||
uint16_t err = EC_READ_U16(domain1_pd + zer_offsets[i].error_code);
|
||||
if(err>0){
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],first code 0x%04x",i,err);
|
||||
clear_cmd[i]=1;//
|
||||
has_clear_all=false;
|
||||
}else{
|
||||
clear_cmd[i]=0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}else{
|
||||
all_motor_op=check_slave_config_states(); //检查从站状态
|
||||
////return;
|
||||
}
|
||||
}
|
||||
if (!inited) {
|
||||
for (int i = 0; i < NUM_SLAVES; ++i) {
|
||||
command[i] = 0x004F;
|
||||
status[i] = 0x000F;
|
||||
last_status[i] = status[i];
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0080);
|
||||
last_status[i] = status[i];
|
||||
}
|
||||
inited = 1;
|
||||
}
|
||||
|
||||
for (int i = 0; i < NUM_SLAVES; ++i)
|
||||
{
|
||||
uint16_t sw = EC_READ_U16(domain1_pd + zer_offsets[i].status_word);
|
||||
@@ -422,55 +482,128 @@ void EthercatDriver::readData(){
|
||||
int16_t tv = EC_READ_S16(domain1_pd + zer_offsets[i].torque_actual_value);
|
||||
int8_t md = EC_READ_S8 (domain1_pd + zer_offsets[i].modes_of_operation_display);
|
||||
uint16_t err = EC_READ_U16(domain1_pd + zer_offsets[i].error_code);
|
||||
hw_joint_states_[i][0]=pos*count_to_rad;
|
||||
hw_joint_states_[i][1]=vel;
|
||||
hw_joint_states_[i][2]=40960;//err
|
||||
cur_pos[i]=pos;
|
||||
double up_pos=cur_pos[i]-pos_offsets[i];
|
||||
//double angle=std::round(up_pos*count_to_rad * 1000.0) / 1000.0;
|
||||
if(i==2||i==8)
|
||||
up_pos=-up_pos;
|
||||
if(op_states[i]==1){
|
||||
hw_joint_states_[i][0]=up_pos*count_to_rad;//angle;
|
||||
hw_joint_states_[i][1]=vel*count_to_speed;//std::round(vel*count_to_speed*1000.0)/1000.0;
|
||||
double amp=tv*rated_currents[i];
|
||||
double effort=0.014*0.6*amp;
|
||||
hw_joint_states_[i][2]=effort;//std::round(amp*10.0)/10.0;
|
||||
}else{
|
||||
hw_joint_states_[i][0]=9999;
|
||||
hw_joint_states_[i][1]=9999;
|
||||
hw_joint_states_[i][2]=9999;
|
||||
}
|
||||
|
||||
hw_joint_states_[i][3]=err;
|
||||
hw_joint_states_[i][4]=enable_arr[i];
|
||||
//hw_joint_states_[i][2]=err;
|
||||
///RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],state:%.1f,%.1f,0x%04x",i,hw_joint_states_[i][0],hw_joint_states_[i][1],err);
|
||||
|
||||
status[i] = sw; //侦测子站状态字变化
|
||||
if (status[i] != last_status[i]) {
|
||||
last_status[i] = status[i];
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
void EthercatDriver::writeData(){
|
||||
static int print_cnt=0;
|
||||
print_cnt+=1;
|
||||
#if 0
|
||||
if(print_cnt%1000==0){
|
||||
logStream.str("");
|
||||
for(int i=0;i<info_.joints.size();i++){
|
||||
logStream<<info_.joints[i].name.c_str()<<":";
|
||||
for(int j=0;j<info_.joints[i].command_interfaces.size();j++)
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"%.2f,",hw_joint_commands_[i][j]);
|
||||
logStream<<hw_joint_commands_[i][j]<<",";
|
||||
logStream<<"\n";
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"[%02d]%s: %s",i,info_.joints[i].name.c_str(),logStream.str().c_str());
|
||||
}
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"%s",logStream.str().c_str());
|
||||
}
|
||||
#endif
|
||||
for (int i = 0; i < NUM_SLAVES; ++i)
|
||||
{
|
||||
dst_rads[i]=getValidAngle(i);
|
||||
#if 1
|
||||
if ((status[i]&0x006f)==0x0008){
|
||||
uint16_t err = EC_READ_U16(domain1_pd + zer_offsets[i].error_code);
|
||||
double fault=hw_joint_commands_[i][0];
|
||||
if(fault==1.0&&err>0){
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],fault code 0x%04x",i,err);
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0080);
|
||||
if(err>0){
|
||||
double fault=hw_joint_commands_[i][0];
|
||||
if(print_cnt%1000==1){
|
||||
///RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],EE:0x%04x",i,err);
|
||||
}
|
||||
if(fault==1.0||clear_cmd[i]==1){
|
||||
if(print_cnt%1000==0)
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],%.1f/%d,fault code 0x%04x",i,fault,clear_cmd[i],err);
|
||||
if(errStaArr[i]==ERR_NONE){
|
||||
errStaArr[i]=ERR_ACK;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
///static double last_enable[12];
|
||||
double enable=hw_joint_commands_[i][1];
|
||||
if(enable!=1){
|
||||
//clear fault
|
||||
if(errStaArr[i]==ERR_ACK){
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0000);
|
||||
errStaArr[i]=ERR_ACK_WAIT;
|
||||
///RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],0x%04x,ERR_ACK %d",i,err,(sw&0x006f)==0x0008);
|
||||
}else if(errStaArr[i]==ERR_ACK_WAIT){
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],0x%04x,ERR_ACK_WAIT %d",i,err,(sw&0x006f)==0x0008);
|
||||
if ((status[i]&0x006f)==0x0008){
|
||||
|
||||
}
|
||||
errStaArr[i]=ERR_CLEAR;
|
||||
}else if(errStaArr[i]==ERR_CLEAR){
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0080);
|
||||
errStaArr[i]=ERR_CLEAR_WAIT;
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],%d,ERR_CLEAR",i,clear_cmd[i]);
|
||||
}else if(errStaArr[i]==ERR_CLEAR_WAIT){
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],0x%04x,ERR_CLEAR_WAIT %d",i,err,(sw&0x006f)==0x0008);
|
||||
errStaArr[i]=ERR_FIN;
|
||||
}else if(errStaArr[i]==ERR_FIN){
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0006);
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],0x%04x,ERR_FIN %d",i,err,(sw&0x006f)==0x0008);
|
||||
errStaArr[i]=ERR_FIN_WAIT;
|
||||
}else if(errStaArr[i]==ERR_FIN_WAIT){
|
||||
//RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],0x%04x,ERR_FIN_WAIT %d",i,err,(sw&0x006f)==0x0008);
|
||||
if((status[i]&0x006f)==0x0008){
|
||||
errStaArr[i]=ERR_ACK;
|
||||
}else{
|
||||
errStaArr[i]=ERR_NONE;
|
||||
///continue;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if(errStaArr[i]!=ERR_NONE||op_states[i]!=1)
|
||||
continue;
|
||||
enable_arr[i]=hw_joint_commands_[i][1];
|
||||
//if(print_cnt%500==0)
|
||||
// RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"),"enable:%d,%.1f,%.2f",i,enable,hw_joint_commands_[i][2]);
|
||||
if(enable_arr[i]!=1.0){
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_velocity, 0);
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0007);
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0006);
|
||||
hw_joint_commands_[i][2]=0;
|
||||
continue;
|
||||
}
|
||||
//write
|
||||
|
||||
if ((status[i] & command[i]) == 0x0001 || (status[i] & command[i]) == 0x0040) {
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0006); // Ready to switch on
|
||||
command[i] = 0x006F;
|
||||
///printf("SS:%d\n",i);
|
||||
step_pos[i]=cur_pos[i];
|
||||
} else if ((status[i] & command[i]) == 0x0021) {
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0007); // Switched on
|
||||
command[i] = 0x006F;
|
||||
// 同步当前位置为目标位置
|
||||
int32_t pv2 = EC_READ_S32(domain1_pd + zer_offsets[i].position_actual_value);
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, pv2);
|
||||
/////g_cmd.target_pos[i].store(pv2, std::memory_order_relaxed);
|
||||
//printf("TTTTTTTTT:%d\n",i);
|
||||
step_pos[i]=cur_pos[i];
|
||||
} else if ((status[i] & command[i]) == 0x0023) {
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x000f); // Operation enabled
|
||||
command[i] = 0x006F;
|
||||
//printf("VVVVVVVV:%d\n",i);
|
||||
step_pos[i]=cur_pos[i];
|
||||
} else if ((status[i] & command[i]) == 0x0027) {
|
||||
// ---- 4) 运行态写目标(按模式/运行意图) ----
|
||||
//if(enable==1)
|
||||
if(true)
|
||||
{
|
||||
//EC_WRITE_U16(domain1_pd + offsets[i].ctrl_word, 0x001F); // 仅在PP模式下需要
|
||||
@@ -480,8 +613,6 @@ void EthercatDriver::readData(){
|
||||
break;
|
||||
case CYCLIC_POSITION: { // 8
|
||||
// ---- 绝对式目标生成,不再用 pv 做增量基准 ----
|
||||
////printf("%02d-->%d,%d,%d\n",i,hw_joint_commands_[i][0],hw_joint_commands_[i][1],hw_joint_commands_[i][2]);
|
||||
///break;
|
||||
// 每轴记住“上次下发的命令位置”
|
||||
static int32_t csp_cmd_pos[NUM_SLAVES]; // 上次下发到 0x607A 的值
|
||||
static uint8_t csp_inited[NUM_SLAVES] = {0}; // 是否已初始化
|
||||
@@ -490,52 +621,58 @@ void EthercatDriver::readData(){
|
||||
|
||||
// 进入/首次运行:把命令位置对齐到“当前实际位置”,避免冲击
|
||||
if (!csp_inited[i] || last_mode_cmd[i] != CYCLIC_POSITION) {
|
||||
csp_cmd_pos[i] = pos; // 先对齐
|
||||
csp_cmd_pos[i] = cur_pos[i]; // 先对齐
|
||||
vmax_acc[i] = 0;
|
||||
csp_inited[i] = 1;
|
||||
}
|
||||
double target_pos=hw_joint_commands_[i][2]*rad_to_count;
|
||||
static double last_pos[12];
|
||||
if(target_pos!=last_pos[i]){
|
||||
last_pos[i]=target_pos;
|
||||
//double down_pos=hw_joint_commands_[i][2]*rad_to_count;
|
||||
//if(i==2||i==8){
|
||||
// down_pos=-down_pos;
|
||||
//}
|
||||
//double target_pos=down_pos+pos_offsets[i]+262144.0;
|
||||
double target_pos=getValidCount_ze(i);
|
||||
if(print_cnt%1000==1){
|
||||
////RCLCPP_INFO(rclcpp::get_logger("hehe"),"[%d] rad:%.1f,target_pos:%.1f,cur pos:%d",i,dst_rads[i],target_pos,cur_pos[i]);
|
||||
}
|
||||
|
||||
// 期望的“最终绝对目标”
|
||||
const int32_t goal = target_pos;///g_cmd.target_pos[i].load(std::memory_order_relaxed);
|
||||
///if(i==0)
|
||||
///printf("%d,goal:%d,pv:%d,flag:%d\n",i,goal,pv,goal_flag[i]);
|
||||
static int pos_cnt=0;
|
||||
//if(pos_cnt++%500==0)
|
||||
// RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],cur:%d,dst:%.1f",i,pos,target_pos);
|
||||
// 本周期允许的最大步长(counts/周期),用定点累加保证平均速度上限严格等于 CSP_MAX_VEL_COUNTS_PER_S
|
||||
vmax_acc[i] += (int64_t)CSP_MAX_VEL_COUNTS_PER_S; // +v [counts/s]
|
||||
int32_t max_step = (int32_t)(vmax_acc[i] / FREQUENCY); // 下取整,得到本周期可用步长
|
||||
vmax_acc[i] -= (int64_t)max_step * FREQUENCY; // 保留余数到下周期
|
||||
|
||||
// 相对“命令轨迹”的误差(不是相对 pv)
|
||||
const int32_t err_cmd = goal - csp_cmd_pos[i];
|
||||
|
||||
// 死区:足够近就贴合到 goal
|
||||
if (err_cmd > -CSP_POS_DEADBAND && err_cmd < CSP_POS_DEADBAND) {
|
||||
csp_cmd_pos[i] = goal;
|
||||
} else {
|
||||
// 限速迈步:命令轨迹只按时间往 goal 逼近
|
||||
if (err_cmd > 0) csp_cmd_pos[i] += (err_cmd > max_step) ? max_step : err_cmd;
|
||||
else csp_cmd_pos[i] += (err_cmd < -max_step) ? -max_step : err_cmd;
|
||||
}
|
||||
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, target_pos);//
|
||||
#if 0
|
||||
int32_t max_step=CSP_MAX_VEL_COUNTS_PER_S/FREQUENCY;
|
||||
const int32_t goal=target_pos;
|
||||
const int32_t err_cmd = goal -csp_cmd_pos[i];
|
||||
if (err_cmd > -CSP_POS_DEADBAND && err_cmd < CSP_POS_DEADBAND) {
|
||||
csp_cmd_pos[i] = goal;
|
||||
} else {
|
||||
// 限速迈步:命令轨迹只按时间往 goal 逼近
|
||||
if (err_cmd > 0) csp_cmd_pos[i] += (err_cmd > max_step) ? max_step : err_cmd;
|
||||
else csp_cmd_pos[i] += (err_cmd < -max_step) ? -max_step : err_cmd;
|
||||
}
|
||||
////EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, csp_cmd_pos[i]);
|
||||
#else
|
||||
const int32_t err_cmd=target_pos-cur_pos[i];
|
||||
if (abs(err_cmd)<CSP_DEADBAND1) {
|
||||
step_pos[i] = target_pos;
|
||||
reach_target[i]=1;
|
||||
}else if(abs(err_cmd)<CSP_DEADBAND2){
|
||||
if(err_cmd>0) step_pos[i]+=(err_cmd>CSP_SPEED1) ? CSP_SPEED1:err_cmd;
|
||||
else step_pos[i]+=(err_cmd<-CSP_SPEED1) ? -CSP_SPEED1:err_cmd;
|
||||
// reach_target[i]=0;
|
||||
//if(err_cmd>0) step_pos[i]+=CSP_SPEED1;
|
||||
//else step_pos[i]-=CSP_SPEED1;
|
||||
} else {
|
||||
if(err_cmd>0) step_pos[i]+=(err_cmd>CSP_SPEED2) ? CSP_SPEED2:err_cmd;
|
||||
else step_pos[i]+=(err_cmd<-CSP_SPEED2) ? -CSP_SPEED2:err_cmd;
|
||||
//if(err_cmd>0) step_pos[i]+=CSP_SPEED2;
|
||||
//else step_pos[i]-=CSP_SPEED2;
|
||||
}
|
||||
////EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, step_pos[i]);
|
||||
#endif
|
||||
// 可选:跟随误差防护(避免 following error 过大时继续“加命令”)
|
||||
// const int32_t follow_err = csp_cmd_pos[i] - pv;
|
||||
// const int32_t FE_LIMIT = (int32_t) (你的驱动跟随误差阈值); // 参考驱动参数
|
||||
// if (std::abs(follow_err) > FE_LIMIT) {
|
||||
// // 例如:冻结或减半 max_step,给驱动时间追上
|
||||
// }
|
||||
#if 1
|
||||
// 下发“绝对目标”(不是增量)
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, csp_cmd_pos[i]);
|
||||
// 回显给上层(/joint_states_cmd 用)
|
||||
//////g_state.pos_cmd[i].store(csp_cmd_pos[i], std::memory_order_relaxed);
|
||||
#endif
|
||||
|
||||
break;
|
||||
}
|
||||
case CYCLIC_TORQUE: // 10
|
||||
@@ -567,186 +704,27 @@ void EthercatDriver::readData(){
|
||||
sync_ref_counter--;
|
||||
} else {
|
||||
sync_ref_counter = 1; // sync every 2 cycle
|
||||
|
||||
clock_gettime(CLOCK_TO_USE, &time);
|
||||
ecrt_master_sync_reference_clock_to(master, TIMESPEC2NS(time)); //每隔一个周期同步时钟
|
||||
ecrt_master_sync_slave_clocks(master);
|
||||
}
|
||||
ecrt_master_sync_slave_clocks(master);
|
||||
|
||||
// send process data
|
||||
ecrt_domain_queue(domain1); //排队域数据
|
||||
ecrt_master_send(master); //发送ETHERCAT帧
|
||||
}
|
||||
void EthercatDriver::writeData(){
|
||||
|
||||
///return;
|
||||
|
||||
for (int i = 0; i < NUM_SLAVES; ++i){
|
||||
int8_t mode_cmd=8;
|
||||
|
||||
int32_t pv = EC_READ_S32(domain1_pd + zer_offsets[i].position_actual_value);
|
||||
uint16_t sw = EC_READ_U16(domain1_pd + zer_offsets[i].status_word);
|
||||
status[i] = sw; //侦测子站状态字变化
|
||||
if (status[i] != last_status[i]) {
|
||||
// printf("[S%02d] 状态改变为: 0x%04X\n", i, status[i]);
|
||||
last_status[i] = status[i];
|
||||
}
|
||||
///printf("%d error status:%04x,%04x\n",i,status[i],status[i]&0x006f);
|
||||
|
||||
#if 0
|
||||
static double last_reset[12];
|
||||
if(last_reset[i]!=reset){
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],reset:%.1f",i,reset);
|
||||
last_reset[i]=reset;
|
||||
}
|
||||
#endif
|
||||
|
||||
if ((status[i]&0x006f)==0x0008){
|
||||
static int err_cnt=0;
|
||||
uint16_t err = EC_READ_U16(domain1_pd + zer_offsets[i].error_code);
|
||||
if(err_cnt++%500==0)
|
||||
printf("%d error status:%04x,err:%04x\n",i,status[i],err);
|
||||
}
|
||||
if ((status[i] & command[i]) == 0x0001 || (status[i] & command[i]) == 0x0040) {
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0006); // Ready to switch on
|
||||
command[i] = 0x006F;
|
||||
///printf("SS:%d\n",i);
|
||||
} else if ((status[i] & command[i]) == 0x0021) {
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0007); // Switched on
|
||||
command[i] = 0x006F;
|
||||
// 同步当前位置为目标位置
|
||||
int32_t pv2 = EC_READ_S32(domain1_pd + zer_offsets[i].position_actual_value);
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, pv2);
|
||||
/////g_cmd.target_pos[i].store(pv2, std::memory_order_relaxed);
|
||||
//printf("TTTTTTTTT:%d\n",i);
|
||||
} else if ((status[i] & command[i]) == 0x0023) {
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x000f); // Operation enabled
|
||||
command[i] = 0x006F;
|
||||
//printf("VVVVVVVV:%d\n",i);
|
||||
} else if ((status[i] & command[i]) == 0x0027) {
|
||||
// ---- 4) 运行态写目标(按模式/运行意图) ----
|
||||
static double last_enable[12];
|
||||
double enable=hw_joint_commands_[i][2];
|
||||
#if 0
|
||||
if(last_enable[i]!=enable){
|
||||
//std::cout<<i<<",enable:"<<enable<<std::endl;
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],enable:%.1f",i,enable);
|
||||
last_enable[i]=enable;
|
||||
}
|
||||
#endif
|
||||
if(enable==1)
|
||||
{
|
||||
//EC_WRITE_U16(domain1_pd + offsets[i].ctrl_word, 0x001F); // 仅在PP模式下需要
|
||||
switch (mode_cmd) {
|
||||
case CYCLIC_VELOCITY: // 9
|
||||
////////EC_WRITE_S32(domain1_pd + zer_offsets[i].target_velocity, vel_cmd);
|
||||
break;
|
||||
case CYCLIC_POSITION: { // 8
|
||||
// ---- 绝对式目标生成,不再用 pv 做增量基准 ----
|
||||
////printf("%02d-->%d,%d,%d\n",i,hw_joint_commands_[i][0],hw_joint_commands_[i][1],hw_joint_commands_[i][2]);
|
||||
///break;
|
||||
// 每轴记住“上次下发的命令位置”
|
||||
static int32_t csp_cmd_pos[NUM_SLAVES]; // 上次下发到 0x607A 的值
|
||||
static uint8_t csp_inited[NUM_SLAVES] = {0}; // 是否已初始化
|
||||
// 定点限速累计器:解决 v_max < FREQUENCY 时整除为 0 的问题
|
||||
static int64_t vmax_acc[NUM_SLAVES] = {0}; // 单位:counts/s 累加器
|
||||
|
||||
// 进入/首次运行:把命令位置对齐到“当前实际位置”,避免冲击
|
||||
if (!csp_inited[i] || last_mode_cmd[i] != CYCLIC_POSITION) {
|
||||
csp_cmd_pos[i] = pv; // 先对齐
|
||||
vmax_acc[i] = 0;
|
||||
csp_inited[i] = 1;
|
||||
}
|
||||
double target_pos=hw_joint_commands_[i][0];
|
||||
static double last_pos[12];
|
||||
if(target_pos!=last_pos[i]){
|
||||
|
||||
last_pos[i]=target_pos;
|
||||
}
|
||||
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "[%d],pos:%.1f",i,target_pos);
|
||||
// 期望的“最终绝对目标”
|
||||
const int32_t goal = pv;///g_cmd.target_pos[i].load(std::memory_order_relaxed);
|
||||
///if(i==0)
|
||||
///printf("%d,goal:%d,pv:%d,flag:%d\n",i,goal,pv,goal_flag[i]);
|
||||
// 本周期允许的最大步长(counts/周期),用定点累加保证平均速度上限严格等于 CSP_MAX_VEL_COUNTS_PER_S
|
||||
vmax_acc[i] += (int64_t)CSP_MAX_VEL_COUNTS_PER_S; // +v [counts/s]
|
||||
int32_t max_step = (int32_t)(vmax_acc[i] / FREQUENCY); // 下取整,得到本周期可用步长
|
||||
vmax_acc[i] -= (int64_t)max_step * FREQUENCY; // 保留余数到下周期
|
||||
|
||||
// 相对“命令轨迹”的误差(不是相对 pv)
|
||||
const int32_t err_cmd = goal - csp_cmd_pos[i];
|
||||
|
||||
// 死区:足够近就贴合到 goal
|
||||
if (err_cmd > -CSP_POS_DEADBAND && err_cmd < CSP_POS_DEADBAND) {
|
||||
csp_cmd_pos[i] = goal;
|
||||
} else {
|
||||
// 限速迈步:命令轨迹只按时间往 goal 逼近
|
||||
if (err_cmd > 0) csp_cmd_pos[i] += (err_cmd > max_step) ? max_step : err_cmd;
|
||||
else csp_cmd_pos[i] += (err_cmd < -max_step) ? -max_step : err_cmd;
|
||||
}
|
||||
|
||||
// 可选:跟随误差防护(避免 following error 过大时继续“加命令”)
|
||||
// const int32_t follow_err = csp_cmd_pos[i] - pv;
|
||||
// const int32_t FE_LIMIT = (int32_t) (你的驱动跟随误差阈值); // 参考驱动参数
|
||||
// if (std::abs(follow_err) > FE_LIMIT) {
|
||||
// // 例如:冻结或减半 max_step,给驱动时间追上
|
||||
// }
|
||||
#if 0
|
||||
// 下发“绝对目标”(不是增量)
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, csp_cmd_pos[i]);
|
||||
// 回显给上层(/joint_states_cmd 用)
|
||||
//////g_state.pos_cmd[i].store(csp_cmd_pos[i], std::memory_order_relaxed);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case CYCLIC_TORQUE: // 10
|
||||
///////EC_WRITE_S16(domain1_pd + zer_offsets[i].target_torque, tor_cmd);
|
||||
break;
|
||||
default:
|
||||
// 未知模式:默认速度模式安全置 0
|
||||
//EC_WRITE_S32(domain1_pd + offsets[i].target_velocity, 0);
|
||||
break;
|
||||
|
||||
}
|
||||
} else {
|
||||
// run_enable=false:清零目标
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0007);
|
||||
// CSV 安全:速度清零
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_velocity, 0);
|
||||
// CSP 安全:目标位置=当前位置 -> 立即“冻结”
|
||||
|
||||
int32_t pv_hold = EC_READ_S32(domain1_pd + zer_offsets[i].position_actual_value);
|
||||
EC_WRITE_S32(domain1_pd + zer_offsets[i].target_position, pv_hold);
|
||||
// 可选:扭矩模式也清零(最好维持急停状态,待修改)
|
||||
EC_WRITE_S16(domain1_pd + zer_offsets[i].target_torque, 0);
|
||||
EC_WRITE_U16(domain1_pd + zer_offsets[i].ctrl_word, 0x0007);//切换 switched on 状态
|
||||
}
|
||||
}
|
||||
}
|
||||
if (sync_ref_counter) {
|
||||
sync_ref_counter--;
|
||||
} else {
|
||||
sync_ref_counter = 1; // sync every 2 cycle
|
||||
|
||||
clock_gettime(CLOCK_TO_USE, &time);
|
||||
ecrt_master_sync_reference_clock_to(master, TIMESPEC2NS(time)); //每隔一个周期同步时钟
|
||||
}
|
||||
ecrt_master_sync_slave_clocks(master);
|
||||
|
||||
// send process data
|
||||
ecrt_domain_queue(domain1); //排队域数据
|
||||
ecrt_master_send(master); //发送ETHERCAT帧
|
||||
|
||||
}
|
||||
hardware_interface::return_type EthercatDriver::write(
|
||||
const rclcpp::Time & /*time*/,
|
||||
const rclcpp::Duration & /*period*/)
|
||||
{
|
||||
// try to lock so we can avoid blocking the read/write loop on the lock.
|
||||
const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
|
||||
//printf("write data...\n");
|
||||
if (lock.owns_lock() && activated_) {
|
||||
//writeData();
|
||||
/// const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
|
||||
if (activated_.load(std::memory_order_relaxed)){
|
||||
auto start=std::chrono::high_resolution_clock::now();
|
||||
writeData();
|
||||
auto end=std::chrono::high_resolution_clock::now();
|
||||
auto diff=end-start;
|
||||
if(diff.count()>100000)
|
||||
RCLCPP_INFO(rclcpp::get_logger("Ethercat"),"wdiff:%ld",diff.count());
|
||||
}
|
||||
return hardware_interface::return_type::OK;
|
||||
}
|
||||
@@ -36,6 +36,14 @@ class GripperDevNode(Node):
|
||||
self.cur_goal=None
|
||||
self.timer_on=False
|
||||
self.target_mode=0
|
||||
self.enable_ok=False
|
||||
flag = self.clawControl.serialOperation(self.com_dev, 115200, True)
|
||||
if flag==1:
|
||||
ret = self.clawControl.enableClamp(self.devid, True)
|
||||
if ret==1:
|
||||
self.enable_ok=True
|
||||
else:
|
||||
print(self.comd_dev,'enble fail!')
|
||||
print('gripper_dev_node init:',self.com_dev)
|
||||
#self.feedback_timer = self.create_timer(0.1, self.update_feedback)
|
||||
def gripper_cmd_callback_action(self,goal):
|
||||
@@ -46,20 +54,22 @@ class GripperDevNode(Node):
|
||||
self.target_torque=req.torque
|
||||
self.target_mode=req.mode
|
||||
print('recv goal',self.devid,self.target_loc,self.target_speed,self.target_torque,self.target_mode)
|
||||
flag = self.clawControl.serialOperation(self.com_dev, 115200, True)
|
||||
if flag==1:
|
||||
ret = self.clawControl.enableClamp(self.devid, True)
|
||||
if ret!=1:
|
||||
print('enble fail!')
|
||||
result=GripperCmd.Result()
|
||||
result.state="gripper enable fail!"
|
||||
result.result=0
|
||||
goal.abort()
|
||||
return result
|
||||
print('start run...')
|
||||
#flag = self.clawControl.serialOperation(self.com_dev, 115200, True)
|
||||
#if flag==1:
|
||||
# ret = self.clawControl.enableClamp(self.devid, True)
|
||||
# if ret!=1:
|
||||
# print('enble fail!')
|
||||
# result=GripperCmd.Result()
|
||||
# result.state="gripper enable fail!"
|
||||
# result.result=0
|
||||
# goal.abort()
|
||||
# return result
|
||||
# print('start run...')
|
||||
if self.enable_ok:
|
||||
self.clawControl.runWithParam(self.devid,self.target_loc,self.target_speed,self.target_torque)
|
||||
##feedback
|
||||
loop_flag=True
|
||||
loop_times=0
|
||||
while loop_flag:
|
||||
loc = self.clawControl.getClampCurrentLocation(self.devid)
|
||||
speed = self.clawControl.getClampCurrentSpeed(self.devid)
|
||||
@@ -80,9 +90,18 @@ class GripperDevNode(Node):
|
||||
print('update feedback:',feedback_msg)
|
||||
self.cur_goal.publish_feedback(feedback_msg)
|
||||
time.sleep(1)
|
||||
loop_times+=1
|
||||
if loop_times>15:
|
||||
result=GripperCmd.Result()
|
||||
result.state="loop timeout!!!"
|
||||
result.result=0
|
||||
goal.abort()
|
||||
loop_times=0
|
||||
return result
|
||||
|
||||
else:
|
||||
result=GripperCmd.Result()
|
||||
result.state="uart open fail!"
|
||||
result.state="uart open fail & enable fail!"
|
||||
result.result=0
|
||||
goal.abort()
|
||||
return result
|
||||
@@ -96,7 +115,10 @@ class GripperDevNode(Node):
|
||||
goal.succeed()
|
||||
print('action finish',state)
|
||||
return result
|
||||
|
||||
def destroy_node(self):
|
||||
super.destroy_node()
|
||||
flag = self.clawControl.serialOperation(self.com_dev, 115200, False)
|
||||
|
||||
def gripper_cmd_callback(self, request, response):
|
||||
self.cur_loc=request.loc
|
||||
self.cur_speed=request.speed
|
||||
@@ -116,6 +138,7 @@ def main():
|
||||
rclpy.init()
|
||||
node=GripperDevNode()
|
||||
rclpy.spin(node)
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
pass
|
||||
if __name__ == '__main__':
|
||||
|
||||
24
librealsense-r-256/.github/ISSUE_TEMPLATE.md
vendored
Normal file
24
librealsense-r-256/.github/ISSUE_TEMPLATE.md
vendored
Normal file
@@ -0,0 +1,24 @@
|
||||
* Before opening a new issue, we wanted to provide you with some useful suggestions (Click "Preview" above for a better view):
|
||||
|
||||
* Consider checking out SDK [examples](https://github.com/IntelRealSense/librealsense/tree/master/examples#sample-code-for-intel-realsense-cameras).
|
||||
* Have you looked in our [documentations](https://github.com/IntelRealSense/librealsense/tree/master/doc#useful-links)?
|
||||
* Is you question a [frequently asked one](https://github.com/IntelRealSense/librealsense/wiki/Troubleshooting-Q%26A)?
|
||||
* Try [searching our GitHub Issues](https://github.com/IntelRealSense/librealsense/issues?utf8=%E2%9C%93&q=is%3Aissue) (open and closed) for a similar issue.
|
||||
|
||||
* All users are welcomed to report bugs, ask questions, suggest or request enhancements and generally feel free to open new issue, even if they haven't followed any of the suggestions above :)
|
||||
|
||||
----------------------------------------------------------------------------------------------------
|
||||
|
||||
| Required Info | |
|
||||
|---------------------------------|------------------------------------------- |
|
||||
| Camera Model | { R200 / F200 / SR300 / ZR300 / D400 } |
|
||||
| Firmware Version | (Open RealSense Viewer --> Click info) |
|
||||
| Operating System & Version | {Win (8.1/10) / Linux (Ubuntu 14/16/17) / MacOS |
|
||||
| Kernel Version (Linux Only) | (e.g. 4.14.13) |
|
||||
| Platform | PC/Raspberry Pi/ NVIDIA Jetson / etc.. |
|
||||
| SDK Version | { legacy / 2.<?>.<?> } |
|
||||
| Language | {C/C#/labview/nodejs/opencv/pcl/python/unity } |
|
||||
| Segment | {Robot/Smartphone/VR/AR/others } |
|
||||
|
||||
### Issue Description
|
||||
<Describe your issue / question / feature request / etc..>
|
||||
9
librealsense-r-256/.github/pull_request_template.md
vendored
Normal file
9
librealsense-r-256/.github/pull_request_template.md
vendored
Normal file
@@ -0,0 +1,9 @@
|
||||
<!--
|
||||
Pull requests should go to the development branch:
|
||||
https://github.com/IntelRealSense/librealsense/tree/development/
|
||||
|
||||
If this is still a work-in-progress, please open it as DRAFT.
|
||||
|
||||
For further details, please see our contribution guidelines:
|
||||
https://github.com/IntelRealSense/librealsense/blob/master/CONTRIBUTING.md
|
||||
-->
|
||||
63
librealsense-r-256/.github/workflows/build-ROS2-package-CI.yaml
vendored
Normal file
63
librealsense-r-256/.github/workflows/build-ROS2-package-CI.yaml
vendored
Normal file
@@ -0,0 +1,63 @@
|
||||
name: build_lrs_ROS2_package
|
||||
|
||||
on:
|
||||
push:
|
||||
branches: ['**']
|
||||
pull_request:
|
||||
branches: ['**']
|
||||
|
||||
permissions: read-all
|
||||
|
||||
jobs:
|
||||
|
||||
build_lrs_ros2_package:
|
||||
runs-on: ubuntu-latest
|
||||
timeout-minutes: 30
|
||||
strategy:
|
||||
matrix:
|
||||
ros_distribution:
|
||||
- humble
|
||||
- iron
|
||||
- rolling
|
||||
- jazzy
|
||||
|
||||
include:
|
||||
# Humble Hawksbill
|
||||
- docker_image: ubuntu:jammy
|
||||
ros_distribution: humble
|
||||
|
||||
# Iron Irwini
|
||||
- docker_image: ubuntu:jammy
|
||||
ros_distribution: iron
|
||||
|
||||
# Rolling Ridley
|
||||
- docker_image: ubuntu:noble
|
||||
ros_distribution: rolling
|
||||
|
||||
# Jazzy Jalisco
|
||||
- docker_image: ubuntu:noble
|
||||
ros_distribution: jazzy
|
||||
|
||||
container:
|
||||
image: ${{ matrix.docker_image }}
|
||||
steps:
|
||||
|
||||
- name: setup ROS environment
|
||||
uses: ros-tooling/setup-ros@a6ce30ecca1e5dcc10ae5e6a44fe2169115bf852 #v0.7
|
||||
with:
|
||||
required-ros-distributions: ${{ matrix.ros_distribution }}
|
||||
|
||||
- name: build librealsense ROS 2
|
||||
uses: ros-tooling/action-ros-ci@0c87ffc035492b66c9afb9159ca9664fb0b513e1 #v0.3
|
||||
with:
|
||||
target-ros2-distro: ${{ matrix.ros_distribution }}
|
||||
skip-tests: true
|
||||
colcon-defaults: | # We align the build flags to the librealsense2 ROS2 release build.
|
||||
{
|
||||
"build": {
|
||||
"cmake-args": [
|
||||
"-DBUILD_GRAPHICAL_EXAMPLES=OFF",
|
||||
"-DBUILD_EXAMPLES=OFF"
|
||||
]
|
||||
}
|
||||
}
|
||||
621
librealsense-r-256/.github/workflows/buildsCI.yaml
vendored
Normal file
621
librealsense-r-256/.github/workflows/buildsCI.yaml
vendored
Normal file
@@ -0,0 +1,621 @@
|
||||
name: Build_CI
|
||||
|
||||
on:
|
||||
push:
|
||||
branches: ['**']
|
||||
pull_request:
|
||||
branches: ['**']
|
||||
|
||||
permissions: read-all
|
||||
|
||||
env:
|
||||
# Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.)
|
||||
LRS_BUILD_CONFIG: Debug
|
||||
LRS_RUN_CONFIG: Release
|
||||
LRS_RUN_WITH_DEB_CONFIG: RelWithDebInfo
|
||||
PYTHON_PATH: C:\\hostedtoolcache\\windows\\Python\\3.8.1\\x64\\python.exe
|
||||
# GH-Actions Windows VM currently supply ~14 GB available on D drive, and ~80 GB on drive C.
|
||||
# Building LRS statically with third parties is too much for drive D so we clone to drive 'D' and build on drive 'C'
|
||||
WIN_BUILD_DIR: C:/lrs_build
|
||||
|
||||
|
||||
jobs:
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
Win_SH_EX_CfU: # Windows, shared, with Examples & Tools, and Check for Updates
|
||||
runs-on: windows-2019
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Enable Long Paths
|
||||
shell: powershell
|
||||
run: |
|
||||
New-ItemProperty -Path "HKLM:\SYSTEM\CurrentControlSet\Control\FileSystem" -Name "LongPathsEnabled" -Value 1 -PropertyType DWORD -Force
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
|
||||
- name: PreBuild
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir ${{env.WIN_BUILD_DIR}}
|
||||
|
||||
- name: Configure CMake
|
||||
# Configure CMake in a 'build' subdirectory. `CMAKE_BUILD_TYPE` is only required if you are using a single-configuration generator such as make.
|
||||
# See https://cmake.org/cmake/help/latest/variable/CMAKE_BUILD_TYPE.html?highlight=cmake_build_type
|
||||
shell: bash
|
||||
run: |
|
||||
LRS_SRC_DIR=$(pwd)
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
pwd
|
||||
ls
|
||||
cmake ${LRS_SRC_DIR} -G "Visual Studio 16 2019" -DBUILD_SHARED_LIBS=true -DBUILD_EXAMPLES=true -DBUILD_TOOLS=true -DCHECK_FOR_UPDATES=true
|
||||
|
||||
- name: Build
|
||||
# Build your program with the given configuration
|
||||
shell: bash
|
||||
run: |
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake --build . --config ${{env.LRS_RUN_CONFIG}} -- -m
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
Win_SH_EX_No_Logs: # Windows, shared, with Examples & Tools, no EasyLogging and no Check for Updates
|
||||
runs-on: windows-2019
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Enable Long Paths
|
||||
shell: powershell
|
||||
run: |
|
||||
New-ItemProperty -Path "HKLM:\SYSTEM\CurrentControlSet\Control\FileSystem" -Name "LongPathsEnabled" -Value 1 -PropertyType DWORD -Force
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
|
||||
- name: PreBuild
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir ${{env.WIN_BUILD_DIR}}
|
||||
|
||||
- name: Configure CMake
|
||||
# Configure CMake in a 'build' subdirectory. `CMAKE_BUILD_TYPE` is only required if you are using a single-configuration generator such as make.
|
||||
# See https://cmake.org/cmake/help/latest/variable/CMAKE_BUILD_TYPE.html?highlight=cmake_build_type
|
||||
shell: bash
|
||||
run: |
|
||||
LRS_SRC_DIR=$(pwd)
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
pwd
|
||||
ls
|
||||
cmake ${LRS_SRC_DIR} -G "Visual Studio 16 2019" -DBUILD_SHARED_LIBS=true -DBUILD_EXAMPLES=true -DBUILD_TOOLS=true -DCHECK_FOR_UPDATES=false -DBUILD_EASYLOGGINGPP=false
|
||||
|
||||
- name: Build
|
||||
# Build your program with the given configuration
|
||||
shell: bash
|
||||
run: |
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake --build . --config ${{env.LRS_RUN_CONFIG}} -- -m
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
Win_ST_Py_CI: # Windows, Static, Python, Tools, libCI with executables
|
||||
runs-on: windows-2019
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
- uses: actions/setup-python@f677139bbe7f9c59b41e40162b753c062f5d49a3 #v5
|
||||
with:
|
||||
python-version: '3.8.1'
|
||||
|
||||
- name: Enable Long Paths
|
||||
shell: powershell
|
||||
run: |
|
||||
New-ItemProperty -Path "HKLM:\SYSTEM\CurrentControlSet\Control\FileSystem" -Name "LongPathsEnabled" -Value 1 -PropertyType DWORD -Force
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
|
||||
- name: PreBuild
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir ${{env.WIN_BUILD_DIR}}
|
||||
python3 -m pip install numpy
|
||||
|
||||
- name: Configure CMake
|
||||
# Configure CMake in a 'build' subdirectory. `CMAKE_BUILD_TYPE` is only required if you are using a single-configuration generator such as make.
|
||||
# See https://cmake.org/cmake/help/latest/variable/CMAKE_BUILD_TYPE.html?highlight=cmake_build_type
|
||||
shell: bash
|
||||
run: |
|
||||
LRS_SRC_DIR=$(pwd)
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake ${LRS_SRC_DIR} -G "Visual Studio 16 2019" -DBUILD_SHARED_LIBS=false -DBUILD_EXAMPLES=false -DBUILD_TOOLS=true -DBUILD_UNIT_TESTS=true -DUNIT_TESTS_ARGS="--not-live --context=windows" -DCHECK_FOR_UPDATES=false -DBUILD_WITH_DDS=false -DPYTHON_EXECUTABLE=${{env.PYTHON_PATH}} -DBUILD_PYTHON_BINDINGS=true
|
||||
|
||||
- name: Build
|
||||
# Build your program with the given configuration
|
||||
shell: bash
|
||||
run: |
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake --build . --config ${{env.LRS_RUN_CONFIG}} -- -m
|
||||
|
||||
- name: LibCI
|
||||
# Note: requires BUILD_UNIT_TESTS or the executable C++ unit-tests won't run (and it won't complain)
|
||||
shell: bash
|
||||
run: |
|
||||
python3 unit-tests/run-unit-tests.py --no-color --debug --stdout --not-live --context "windows" ${{env.WIN_BUILD_DIR}}/Release
|
||||
|
||||
- name: Client for realsense2-all
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir ${{env.WIN_BUILD_DIR}}/rs-all-client
|
||||
cd ${{env.WIN_BUILD_DIR}}/rs-all-client
|
||||
cmake $GITHUB_WORKSPACE/.github/workflows/rs-all-client -G "Visual Studio 16 2019"
|
||||
cmake --build . --config Release -- -m
|
||||
./Release/rs-all-client
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
Win_SH_Py_DDS_CI: # Windows, Shared, Python, Tools, DDS, libCI without executables
|
||||
runs-on: windows-2019
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
- uses: actions/setup-python@f677139bbe7f9c59b41e40162b753c062f5d49a3 #v5
|
||||
with:
|
||||
python-version: '3.8.1'
|
||||
|
||||
- name: Enable Long Paths
|
||||
shell: powershell
|
||||
run: |
|
||||
New-ItemProperty -Path "HKLM:\SYSTEM\CurrentControlSet\Control\FileSystem" -Name "LongPathsEnabled" -Value 1 -PropertyType DWORD -Force
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
|
||||
- name: PreBuild
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir ${{env.WIN_BUILD_DIR}}
|
||||
python3 -m pip install numpy
|
||||
|
||||
- name: Configure CMake
|
||||
shell: bash
|
||||
run: |
|
||||
LRS_SRC_DIR=$(pwd)
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake ${LRS_SRC_DIR} -G "Visual Studio 16 2019" -DBUILD_SHARED_LIBS=true -DBUILD_EXAMPLES=false -DBUILD_TOOLS=true -DBUILD_UNIT_TESTS=false -DCHECK_FOR_UPDATES=false -DBUILD_WITH_DDS=true -DPYTHON_EXECUTABLE=${{env.PYTHON_PATH}} -DBUILD_PYTHON_BINDINGS=true
|
||||
|
||||
- name: Build
|
||||
# Build your program with the given configuration
|
||||
shell: bash
|
||||
run: |
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake --build . --config ${{env.LRS_RUN_CONFIG}} -- -m
|
||||
|
||||
- name: LibCI
|
||||
# Note: we specifically disable BUILD_UNIT_TESTS so the executable C++ unit-tests won't run
|
||||
# This is to save time as DDS already lengthens the build...
|
||||
shell: bash
|
||||
run: |
|
||||
python3 unit-tests/run-unit-tests.py --no-color --debug --stdout --not-live --context "dds windows" ${{env.WIN_BUILD_DIR}}/Release
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
Win_SH_Py_DDS_SEC: # Windows, Shared, Python, Tools, DDS, additional security checks
|
||||
runs-on: windows-2019
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- uses: actions/setup-python@v5
|
||||
with:
|
||||
python-version: '3.8.1'
|
||||
|
||||
- name: Enable Long Paths
|
||||
shell: powershell
|
||||
run: |
|
||||
New-ItemProperty -Path "HKLM:\SYSTEM\CurrentControlSet\Control\FileSystem" -Name "LongPathsEnabled" -Value 1 -PropertyType DWORD -Force
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
|
||||
- name: PreBuild
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir ${{env.WIN_BUILD_DIR}}
|
||||
python3 -m pip install numpy
|
||||
|
||||
- name: Configure CMake
|
||||
shell: bash
|
||||
run: |
|
||||
LRS_SRC_DIR=$(pwd)
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake ${LRS_SRC_DIR} -G "Visual Studio 16 2019" -DBUILD_SHARED_LIBS=true -DBUILD_EXAMPLES=false -DBUILD_TOOLS=true -DBUILD_UNIT_TESTS=false -DCHECK_FOR_UPDATES=false -DBUILD_WITH_DDS=true -DPYTHON_EXECUTABLE=${{env.PYTHON_PATH}} -DBUILD_PYTHON_BINDINGS=true -DENABLE_SECURITY_FLAGS=true
|
||||
|
||||
- name: Build
|
||||
# Build your program with the given configuration
|
||||
shell: bash
|
||||
run: |
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake --build . --config ${{env.LRS_RUN_CONFIG}} -- -m
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
Win_SH_Py_RSUSB_Csharp: # Windows, Shared, Python, RSUSB backend, C# bindings
|
||||
runs-on: windows-2019
|
||||
timeout-minutes: 60
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
- uses: actions/setup-python@f677139bbe7f9c59b41e40162b753c062f5d49a3 #v5
|
||||
with:
|
||||
python-version: '3.8.1'
|
||||
|
||||
- name: Enable Long Paths
|
||||
shell: powershell
|
||||
run: |
|
||||
New-ItemProperty -Path "HKLM:\SYSTEM\CurrentControlSet\Control\FileSystem" -Name "LongPathsEnabled" -Value 1 -PropertyType DWORD -Force
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
|
||||
- name: PreBuild
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir ${{env.WIN_BUILD_DIR}}
|
||||
|
||||
- name: Configure CMake
|
||||
shell: bash
|
||||
run: |
|
||||
LRS_SRC_DIR=$(pwd)
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake ${LRS_SRC_DIR} -G "Visual Studio 16 2019" -DBUILD_SHARED_LIBS=true -DBUILD_EXAMPLES=false -DBUILD_TOOLS=false -DCHECK_FOR_UPDATES=false -DPYTHON_EXECUTABLE=${{env.PYTHON_PATH}} -DBUILD_PYTHON_BINDINGS=true -DFORCE_RSUSB_BACKEND=true -DBUILD_CSHARP_BINDINGS=true -DDOTNET_VERSION_LIBRARY="4.5" -DDOTNET_VERSION_EXAMPLES="4.5"
|
||||
|
||||
- name: Build
|
||||
# Build your program with the given configuration
|
||||
shell: bash
|
||||
run: |
|
||||
cd ${{env.WIN_BUILD_DIR}}
|
||||
cmake --build . --config ${{env.LRS_BUILD_CONFIG}} -- -m
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
U22_U24_ST_Py_EX_CfU: # Ubuntu, Static, Python, Examples & Tools, Check for Updates
|
||||
runs-on: ${{ matrix.os }}
|
||||
strategy:
|
||||
matrix:
|
||||
os: [ubuntu-22.04, ubuntu-24.04]
|
||||
include:
|
||||
- os: ubuntu-22.04
|
||||
name: U22
|
||||
- os: ubuntu-24.04
|
||||
name: U24
|
||||
name: ${{ matrix.name }}_ST_Py_EX_CfU
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Prebuild
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts && ./api_check.sh && cd ..
|
||||
mkdir build && cd build
|
||||
export LRS_LOG_LEVEL="DEBUG";
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
|
||||
- name: Build
|
||||
shell: bash
|
||||
run: |
|
||||
cd build
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_RUN_CONFIG}} -DBUILD_SHARED_LIBS=false -DBUILD_EXAMPLES=true -DBUILD_TOOLS=true -DCHECK_FOR_UPDATES=true -DBUILD_PYTHON_BINDINGS=true -DPYTHON_EXECUTABLE=$(which python3)
|
||||
cmake --build . -- -j4
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
U22_SH_Py_CI: # Ubuntu 2020, Shared, Python, LibCI with executables
|
||||
runs-on: ubuntu-22.04
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Prebuild
|
||||
shell: bash
|
||||
run: |
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
python3 -m pip install numpy
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
./pr_check.sh
|
||||
cd ..
|
||||
mkdir build
|
||||
|
||||
- name: Build
|
||||
shell: bash
|
||||
run: |
|
||||
cd build
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_RUN_CONFIG}} -DBUILD_SHARED_LIBS=true -DBUILD_EXAMPLES=false -DBUILD_TOOLS=true -DBUILD_UNIT_TESTS=true -DUNIT_TESTS_ARGS="--not-live --context=linux" -DCHECK_FOR_UPDATES=false -DBUILD_WITH_DDS=false -DBUILD_PYTHON_BINDINGS=true -DPYTHON_EXECUTABLE=$(which python3)
|
||||
cmake --build . -- -j4
|
||||
|
||||
- name: LibCI
|
||||
# Note: requires BUILD_UNIT_TESTS or the executable C++ unit-tests won't run (and it won't complain)
|
||||
shell: bash
|
||||
run: |
|
||||
python3 unit-tests/run-unit-tests.py --no-color --debug --stdout --not-live --context "linux"
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
U22_ST_Py_DDS_RSUSB_CI: # Ubuntu 2020, Static, Python, DDS, RSUSB, LibCI without executables
|
||||
runs-on: ubuntu-22.04
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Prebuild
|
||||
shell: bash
|
||||
run: |
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
python3 -m pip install numpy
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
./pr_check.sh
|
||||
cd ..
|
||||
mkdir build
|
||||
|
||||
- name: Build
|
||||
# Note: we force RSUSB because, on Linux, the context creation will fail on GHA:
|
||||
# (backend-v4l2.cpp:555) Cannot access /sys/class/video4linux)
|
||||
# And, well, we don't need any specific platform for DDS!
|
||||
shell: bash
|
||||
run: |
|
||||
cd build
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_RUN_CONFIG}} -DBUILD_SHARED_LIBS=false -DBUILD_EXAMPLES=false -DBUILD_TOOLS=false -DBUILD_UNIT_TESTS=false -DCHECK_FOR_UPDATES=false -DBUILD_WITH_DDS=true -DBUILD_PYTHON_BINDINGS=true -DPYTHON_EXECUTABLE=$(which python3) -DFORCE_RSUSB_BACKEND=true
|
||||
cmake --build . -- -j4
|
||||
|
||||
- name: Client for realsense2-all
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir build/rs-all-client
|
||||
cd build/rs-all-client
|
||||
cmake ../../.github/workflows/rs-all-client -DBUILD_WITH_DDS=ON -DFORCE_RSUSB_BACKEND=ON
|
||||
cmake --build . -- -j4
|
||||
./rs-all-client
|
||||
|
||||
- name: LibCI
|
||||
# Note: we specifically disable BUILD_UNIT_TESTS so the executable C++ unit-tests won't run
|
||||
# This is to save time as DDS already lengthens the build...
|
||||
shell: bash
|
||||
run: |
|
||||
python3 unit-tests/run-unit-tests.py --no-color --debug --stdout --not-live --context "dds linux" --tag dds
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
U22_ST_Py_DDS_RSUSB_SEC: # Ubuntu 2020, Static, Python, DDS, RSUSB, additional security checks
|
||||
runs-on: ubuntu-22.04
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
|
||||
- name: Prebuild
|
||||
shell: bash
|
||||
run: |
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
python3 -m pip install numpy
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
./pr_check.sh
|
||||
cd ..
|
||||
mkdir build
|
||||
|
||||
- name: Build
|
||||
# Note: we force RSUSB because, on Linux, the context creation will fail on GHA:
|
||||
# (backend-v4l2.cpp:555) Cannot access /sys/class/video4linux)
|
||||
# And, well, we don't need any specific platform for DDS!
|
||||
shell: bash
|
||||
run: |
|
||||
cd build
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_RUN_CONFIG}} -DBUILD_SHARED_LIBS=false -DBUILD_EXAMPLES=false -DBUILD_TOOLS=false -DBUILD_UNIT_TESTS=false -DCHECK_FOR_UPDATES=false -DBUILD_WITH_DDS=true -DBUILD_PYTHON_BINDINGS=true -DPYTHON_EXECUTABLE=$(which python3) -DFORCE_RSUSB_BACKEND=true -DENABLE_SECURITY_FLAGS=true
|
||||
cmake --build . -- -j4
|
||||
|
||||
- name: Client for realsense2-all
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir build/rs-all-client
|
||||
cd build/rs-all-client
|
||||
cmake ../../.github/workflows/rs-all-client -DBUILD_WITH_DDS=ON -DFORCE_RSUSB_BACKEND=ON
|
||||
cmake --build . -- -j4
|
||||
./rs-all-client
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
U22_U24_SH_Py_DDS_CI: # Ubuntu, Shared, Python, DDS, LibCI without executables
|
||||
runs-on: ${{ matrix.os }}
|
||||
strategy:
|
||||
matrix:
|
||||
os: [ubuntu-22.04, ubuntu-24.04]
|
||||
include:
|
||||
- os: ubuntu-22.04
|
||||
name: U22
|
||||
- os: ubuntu-24.04
|
||||
name: U24
|
||||
name: ${{ matrix.name }}_SH_Py_DDS_CI
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Prebuild
|
||||
shell: bash
|
||||
run: |
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
sudo apt-get install python3-numpy
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
./pr_check.sh
|
||||
cd ..
|
||||
mkdir build
|
||||
|
||||
- name: Build
|
||||
shell: bash
|
||||
run: |
|
||||
cd build
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_RUN_CONFIG}} -DBUILD_SHARED_LIBS=true -DBUILD_EXAMPLES=false -DBUILD_TOOLS=false -DBUILD_UNIT_TESTS=false -DCHECK_FOR_UPDATES=false -DBUILD_WITH_DDS=true -DBUILD_PYTHON_BINDINGS=true -DPYTHON_EXECUTABLE=$(which python3)
|
||||
cmake --build . -- -j4
|
||||
|
||||
- name: LibCI
|
||||
# Note: we specifically disable BUILD_UNIT_TESTS so the executable C++ unit-tests won't run
|
||||
# This is to save time as DDS already lengthens the build...
|
||||
shell: bash
|
||||
run: |
|
||||
python3 unit-tests/run-unit-tests.py --no-color --debug --stdout --not-live --context "dds linux" --tag dds
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
U-Latest_ST_Py_EX_CfU: # Ubuntu latest, Static, Python, Examples & Tools, Check for Updates
|
||||
runs-on: ubuntu-latest
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Prebuild
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts && ./api_check.sh && cd ..
|
||||
mkdir build && cd build
|
||||
export LRS_LOG_LEVEL="DEBUG";
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
|
||||
- name: Build
|
||||
shell: bash
|
||||
run: |
|
||||
cd build
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_RUN_CONFIG}} -DBUILD_SHARED_LIBS=false -DBUILD_EXAMPLES=true -DBUILD_TOOLS=true -DCHECK_FOR_UPDATES=true -DBUILD_PYTHON_BINDINGS=true -DPYTHON_EXECUTABLE=$(which python3)
|
||||
cmake --build . -- -j4
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
|
||||
Mac_cpp:
|
||||
runs-on: macos-14
|
||||
timeout-minutes: 60
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
|
||||
- name: Prebuild
|
||||
run: |
|
||||
mkdir build
|
||||
# install coreutils for greadlink use
|
||||
brew install coreutils
|
||||
brew install homebrew/core/glfw;
|
||||
brew list libusb || brew install libusb;
|
||||
|
||||
- name: Build
|
||||
run: |
|
||||
cd build
|
||||
# `OPENSSL_ROOT_DIR` setting is Used by libcurl for 'CHECK_FOR_UPDATES' capability
|
||||
# We use "greadlink -f" which is mac-os parallel command to "readlink -f" from Linux (-f to convert relative link to absolute link)
|
||||
export OPENSSL_ROOT_DIR=`greadlink -f /usr/local/opt/openssl@1.1`
|
||||
echo "OPENSSL_ROOT_DIR = ${OPENSSL_ROOT_DIR}"
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_BUILD_CONFIG}} -DBUILD_EXAMPLES=true -DBUILD_WITH_OPENMP=false -DHWM_OVER_XU=false -DCHECK_FOR_UPDATES=true
|
||||
cmake --build . -- -j4
|
||||
ls
|
||||
|
||||
|
||||
#--------------------------------------------------------------------------------
|
||||
Android_cpp:
|
||||
runs-on: ubuntu-22.04
|
||||
timeout-minutes: 60
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Check_API
|
||||
shell: bash
|
||||
run: |
|
||||
cd scripts
|
||||
./api_check.sh
|
||||
cd ..
|
||||
- name: Prebuild
|
||||
shell: bash
|
||||
run: |
|
||||
mkdir build
|
||||
wget https://dl.google.com/android/repository/android-ndk-r20b-linux-x86_64.zip;
|
||||
unzip -q android-ndk-r20b-linux-x86_64.zip -d ./;
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
- name: Build
|
||||
run: |
|
||||
cd build
|
||||
cmake .. -DCMAKE_BUILD_TYPE=${{env.LRS_BUILD_CONFIG}} -DCMAKE_TOOLCHAIN_FILE=../android-ndk-r20b/build/cmake/android.toolchain.cmake -DFORCE_RSUSB_BACKEND=true
|
||||
cmake --build . -- -j4
|
||||
ls
|
||||
|
||||
89
librealsense-r-256/.github/workflows/cppcheck-parse.py
vendored
Normal file
89
librealsense-r-256/.github/workflows/cppcheck-parse.py
vendored
Normal file
@@ -0,0 +1,89 @@
|
||||
# Parser for cppcheck_run.log files
|
||||
|
||||
import sys
|
||||
def usage():
|
||||
print( 'usage: python chhpcheck-parse.py [OPTIONS] <path-to-log>' )
|
||||
print( ' --severity <W|E|l> limit which severities are shown (Warnings, Errors, locations; default=WEl)' )
|
||||
sys.exit(1)
|
||||
|
||||
import getopt
|
||||
try:
|
||||
opts, args = getopt.getopt( sys.argv[1:], 'h',
|
||||
longopts=['help', 'severity='] )
|
||||
except getopt.GetoptError as err:
|
||||
print( '-F-', err ) # something like "option -a not recognized"
|
||||
usage()
|
||||
if len(args) != 1:
|
||||
usage()
|
||||
logfile = args[0]
|
||||
|
||||
severities = 'WEl'
|
||||
for opt, arg in opts:
|
||||
if opt in ('--severity'):
|
||||
severities = arg
|
||||
|
||||
|
||||
class LineError( Exception ):
|
||||
def __init__( self, message, line=None ):
|
||||
global line_number, logfile
|
||||
if line is None:
|
||||
line = line_number
|
||||
super().__init__( f'{logfile}+{line}: {message}' )
|
||||
|
||||
|
||||
handle = open( logfile, "r" )
|
||||
line_number = 0
|
||||
def nextline():
|
||||
global handle, line_number
|
||||
line_number += 1
|
||||
line = handle.readline()
|
||||
if not line:
|
||||
raise LineError( 'unexpected end-of-file' )
|
||||
return line.strip()
|
||||
|
||||
while True:
|
||||
line = nextline()
|
||||
if line == '<errors>':
|
||||
break
|
||||
|
||||
import re
|
||||
while True:
|
||||
line = nextline()
|
||||
if line == '</errors>':
|
||||
break
|
||||
if not line.startswith( '<error ' ):
|
||||
raise LineError( 'unexpected line' )
|
||||
|
||||
#print( f'-D-{line_number}- {line}' )
|
||||
e = dict( re.findall( '(\w+)="(.*?)"', line ) )
|
||||
severity = e['severity'][0].capitalize()
|
||||
id = e['id']
|
||||
cwe = e.get( 'cwe', '-' )
|
||||
file0 = e.get( 'file0', '' )
|
||||
msg = e['msg'].replace( ''', "'" )
|
||||
|
||||
line = nextline()
|
||||
printed = False
|
||||
while( line.startswith( '<location ' )):
|
||||
l = dict( re.findall( '(\w+)="(.*?)"', line ) )
|
||||
file = l['file']
|
||||
line = l['line']
|
||||
column = l['column']
|
||||
info = l.get( 'info', '' )
|
||||
if severity in severities:
|
||||
if 'l' in severities:
|
||||
if not printed:
|
||||
print( f'{severity} {id:30} {file0:50} {msg}' )
|
||||
print( f'| {"-":30} {file+"+"+line+"."+column:50} {info}' )
|
||||
elif not printed:
|
||||
print( f'{severity} {id:30} {file+"+"+line:50} {msg}' )
|
||||
printed = True
|
||||
line = nextline()
|
||||
if not printed: # no locations!?
|
||||
if severity in severities:
|
||||
print( f'{severity} {id:30} {file0 or file:50} {msg}' )
|
||||
|
||||
if line != '</error>':
|
||||
raise LineError( 'unknown error line' )
|
||||
|
||||
sys.exit(0)
|
||||
12
librealsense-r-256/.github/workflows/memory-leaks-check/CMakeLists.txt
vendored
Normal file
12
librealsense-r-256/.github/workflows/memory-leaks-check/CMakeLists.txt
vendored
Normal file
@@ -0,0 +1,12 @@
|
||||
# License: Apache 2.0. See LICENSE file in root directory.
|
||||
# Copyright(c) 2025 Intel Corporation. All Rights Reserved.
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
|
||||
project(mem-leak-test)
|
||||
|
||||
add_executable( ${PROJECT_NAME} mem-leak-test.cpp)
|
||||
set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 11)
|
||||
target_link_libraries( ${PROJECT_NAME} ${DEPENDENCIES} )
|
||||
set_target_properties( ${PROJECT_NAME} PROPERTIES FOLDER "Examples" )
|
||||
install( TARGETS ${PROJECT_NAME} RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} )
|
||||
|
||||
118
librealsense-r-256/.github/workflows/memory-leaks-check/mem-leak-test.cpp
vendored
Normal file
118
librealsense-r-256/.github/workflows/memory-leaks-check/mem-leak-test.cpp
vendored
Normal file
@@ -0,0 +1,118 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2025 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include <librealsense2/hpp/rs_internal.hpp>
|
||||
#include <random>
|
||||
#include <iostream>
|
||||
|
||||
const int W = 640;
|
||||
const int H = 480;
|
||||
const int BPP = 2;
|
||||
|
||||
struct synthetic_frame
|
||||
{
|
||||
int x, y, bpp;
|
||||
std::vector<uint8_t> frame;
|
||||
};
|
||||
|
||||
class custom_frame_source
|
||||
{
|
||||
public:
|
||||
custom_frame_source()
|
||||
{
|
||||
synth_frame.x = W;
|
||||
synth_frame.y = H;
|
||||
synth_frame.bpp = BPP;
|
||||
|
||||
std::vector<uint8_t> pixels_depth(synth_frame.x * synth_frame.y * synth_frame.bpp, 0);
|
||||
synth_frame.frame = std::move(pixels_depth);
|
||||
}
|
||||
|
||||
synthetic_frame& get_synthetic_depth()
|
||||
{
|
||||
// Create a random number generator
|
||||
std::random_device rd;
|
||||
std::mt19937 gen(rd());
|
||||
std::uniform_int_distribution<unsigned int> dis(0, 255);
|
||||
|
||||
for (int i = 0; i < synth_frame.y; i++)
|
||||
{
|
||||
for (int j = 0; j < synth_frame.x; j++)
|
||||
{
|
||||
// Generate a random uint8_t value for each pixel
|
||||
synth_frame.frame[i * synth_frame.x + j] = static_cast<uint8_t>(dis(gen));
|
||||
}
|
||||
}
|
||||
return synth_frame;
|
||||
}
|
||||
|
||||
rs2_intrinsics create_depth_intrinsics()
|
||||
{
|
||||
rs2_intrinsics intrinsics = { synth_frame.x, synth_frame.y,
|
||||
(float)synth_frame.x / 2, (float)synth_frame.y / 2,
|
||||
(float)synth_frame.x , (float)synth_frame.y ,
|
||||
RS2_DISTORTION_BROWN_CONRADY ,{ 0,0,0,0,0 } };
|
||||
|
||||
return intrinsics;
|
||||
}
|
||||
|
||||
private:
|
||||
synthetic_frame synth_frame;
|
||||
};
|
||||
|
||||
int main(int argc, char* argv[]) try
|
||||
{
|
||||
rs2::pointcloud pc;
|
||||
rs2::points points;
|
||||
|
||||
custom_frame_source app_data;
|
||||
rs2_intrinsics depth_intrinsics = app_data.create_depth_intrinsics();
|
||||
|
||||
//==================================================//
|
||||
// Declare Software-Only Device //
|
||||
//==================================================//
|
||||
|
||||
rs2::software_device dev; // Create software-only device
|
||||
|
||||
auto depth_sensor = dev.add_sensor("Depth"); // Define single sensor
|
||||
|
||||
auto depth_stream = depth_sensor.add_video_stream({ RS2_STREAM_DEPTH, 0, 0,
|
||||
W, H, 60, BPP,
|
||||
RS2_FORMAT_Z16, depth_intrinsics });
|
||||
|
||||
dev.create_matcher(RS2_MATCHER_DEFAULT); // Compare all streams according to timestamp
|
||||
rs2::syncer sync;
|
||||
|
||||
depth_sensor.open(depth_stream);
|
||||
|
||||
depth_sensor.start(sync);
|
||||
|
||||
synthetic_frame& synth_frame = app_data.get_synthetic_depth();
|
||||
|
||||
rs2_time_t timestamp = (rs2_time_t)1;
|
||||
auto domain = RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK;
|
||||
|
||||
depth_sensor.on_video_frame({ synth_frame.frame.data(), // Frame pixels from capture API
|
||||
[](void*) {}, // Custom deleter (if required)
|
||||
synth_frame.x * synth_frame.bpp, // Stride
|
||||
synth_frame.bpp,
|
||||
timestamp, domain, 1,
|
||||
depth_stream, 0.001f }); // depth unit
|
||||
|
||||
rs2::frameset fset = sync.wait_for_frames();
|
||||
|
||||
return EXIT_SUCCESS;
|
||||
}
|
||||
catch (const rs2::error& e)
|
||||
{
|
||||
std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
catch (const std::exception& e)
|
||||
{
|
||||
std::cerr << e.what() << std::endl;
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
|
||||
|
||||
|
||||
53
librealsense-r-256/.github/workflows/rs-all-client/CMakeLists.txt
vendored
Normal file
53
librealsense-r-256/.github/workflows/rs-all-client/CMakeLists.txt
vendored
Normal file
@@ -0,0 +1,53 @@
|
||||
# License: Apache 2.0. See LICENSE file in root directory.
|
||||
# Copyright(c) 2023 Intel Corporation. All Rights Reserved.
|
||||
cmake_minimum_required( VERSION 3.15 )
|
||||
|
||||
#
|
||||
# This tests whether we can link with realsense2-all and not have any missing external symbols.
|
||||
# Without realsense2-all, we'd need to link with:
|
||||
# realsense2 realsense-file rsutils
|
||||
# Or, if DDS was enabled:
|
||||
# realsense2 realsense-file rsutils fastcdr fastrtps foonathan_memory realdds
|
||||
# And the list gets longer if we add libraries.
|
||||
#
|
||||
# On Windows, no additional special libraries are needed.
|
||||
# On Linux, we have other dependencies:
|
||||
# libusb udev
|
||||
# These are not part of realsense2-all, even though we depend on them!
|
||||
#
|
||||
|
||||
project( rs-all-client )
|
||||
|
||||
option( BUILD_SHARED_LIBS "Build using shared libraries" OFF )
|
||||
|
||||
if( WIN32 )
|
||||
# Take away the other configurations because they'd require we picked another link
|
||||
# directory and target... keep it simple...
|
||||
set( CMAKE_CONFIGURATION_TYPES "Release" )
|
||||
endif()
|
||||
|
||||
add_executable( ${PROJECT_NAME} main.cpp )
|
||||
set_target_properties( ${PROJECT_NAME} PROPERTIES
|
||||
CXX_STANDARD 14
|
||||
MSVC_RUNTIME_LIBRARY MultiThreaded$<$<CONFIG:Debug>:Debug> # New in version 3.15; ignored in Linux
|
||||
)
|
||||
|
||||
target_include_directories( ${PROJECT_NAME} PRIVATE
|
||||
../../../include
|
||||
../../../third-party/rsutils/include
|
||||
)
|
||||
target_link_directories( ${PROJECT_NAME} PRIVATE ${CMAKE_BINARY_DIR}/../Release )
|
||||
|
||||
target_link_libraries( ${PROJECT_NAME} PRIVATE realsense2-all )
|
||||
|
||||
if( NOT WIN32 )
|
||||
find_library( LIBUSB NAMES usb-1.0 )
|
||||
target_link_libraries( ${PROJECT_NAME} PRIVATE pthread ${LIBUSB} )
|
||||
if( NOT FORCE_RSUSB_BACKEND )
|
||||
target_link_libraries( ${PROJECT_NAME} PRIVATE udev )
|
||||
endif()
|
||||
if( BUILD_WITH_DDS )
|
||||
target_link_libraries( ${PROJECT_NAME} PRIVATE ssl crypto rt )
|
||||
endif()
|
||||
endif()
|
||||
|
||||
56
librealsense-r-256/.github/workflows/rs-all-client/main.cpp
vendored
Normal file
56
librealsense-r-256/.github/workflows/rs-all-client/main.cpp
vendored
Normal file
@@ -0,0 +1,56 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2023 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
|
||||
|
||||
#include <rsutils/time/timer.h>
|
||||
#include <iostream> // for cout
|
||||
#include <chrono>
|
||||
#include <thread>
|
||||
|
||||
int main(int argc, char * argv[]) try
|
||||
{
|
||||
rs2::log_to_console( RS2_LOG_SEVERITY_DEBUG );
|
||||
|
||||
rs2::context context;
|
||||
auto devices = context.query_devices();
|
||||
if( devices.size() )
|
||||
{
|
||||
// This can run under GHA, too -- so we don't always have devices
|
||||
// Run for just a little bit, count the frames
|
||||
size_t n_frames = 0;
|
||||
{
|
||||
rs2::pipeline p( context );
|
||||
auto profile = p.start();
|
||||
auto device = profile.get_device();
|
||||
std::cout << "Streaming on " << device.get_info( RS2_CAMERA_INFO_NAME ) << std::endl;
|
||||
|
||||
rsutils::time::timer timer( std::chrono::seconds( 3 ) );
|
||||
while( ! timer.has_expired() )
|
||||
{
|
||||
// Block program until frames arrive
|
||||
rs2::frameset frames = p.wait_for_frames();
|
||||
++n_frames;
|
||||
}
|
||||
}
|
||||
|
||||
std::cout << "Got " << n_frames << " frames" << std::endl;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Allow enough time for DDS enumeration
|
||||
std::this_thread::sleep_for( std::chrono::seconds( 3 ) );
|
||||
}
|
||||
|
||||
return EXIT_SUCCESS;
|
||||
}
|
||||
catch (const rs2::error & e)
|
||||
{
|
||||
std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
catch (const std::exception& e)
|
||||
{
|
||||
std::cerr << e.what() << std::endl;
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
327
librealsense-r-256/.github/workflows/static_analysis.yaml
vendored
Normal file
327
librealsense-r-256/.github/workflows/static_analysis.yaml
vendored
Normal file
@@ -0,0 +1,327 @@
|
||||
name: static_analysis
|
||||
|
||||
on:
|
||||
push:
|
||||
branches: ['**']
|
||||
pull_request:
|
||||
branches: ['**']
|
||||
|
||||
permissions: read-all
|
||||
|
||||
jobs:
|
||||
CppCheck:
|
||||
name: CppCheck
|
||||
timeout-minutes: 30
|
||||
runs-on: ubuntu-22.04
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Install
|
||||
shell: bash
|
||||
run: |
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq cppcheck;
|
||||
|
||||
- name: Run
|
||||
shell: bash
|
||||
#Selected run options:
|
||||
# ./xxx : Folders to scan
|
||||
# --quiet : Don't show current checked configuration in log
|
||||
# --std=c++11 : Use C++11 standard (default but worth mentioning)
|
||||
# --xml : Output in XML format
|
||||
# -j4 : Run parallel jobs for a faster scan. current HW is 2 core (https://docs.github.com/en/actions/using-github-hosted-runners/about-github-hosted-runners) using 4 to future proof
|
||||
# --enable : Additional check to run. options are [all, warning, style, performance, protability, information, unusedFunction, missingInclude]
|
||||
# -I : Include directories
|
||||
# -i : Ignore directories. Ignore third-party libs that we don't want to check
|
||||
# --suppress : Don't issue errors about files matching the expression (when -i for folders is not enough)
|
||||
# --force : Check all configurations, takes a very long time (~2 hours) and did not find additional errors. Removed.
|
||||
# --max-configs=6 : Using less configuration permutations (default is 12) to reduce run time. Detects less errors. Removed.
|
||||
# -Dxxx : preprocessor configuration to use. Relevant flags taken from build on Ubuntu.
|
||||
run: >
|
||||
cppcheck ./src ./include ./common ./tools ./examples ./third-party/realdds ./third-party/rsutils
|
||||
--quiet --std=c++11 --xml -j4 --enable=warning
|
||||
-I./src -I./include -I./third-party/rsutils/include -I./common
|
||||
-i./src/mf -i./src/uvc -i./src/win -i./src/winusb --suppress=*:third-party/json.hpp
|
||||
-DBUILD_WITH_DDS -DHWM_OVER_XU -DRS2_USE_V4L2_BACKEND -DUNICODE -DUSING_UDEV -DCHECK_FOR_UPDATES -D__linux__
|
||||
&> cppcheck_run.log
|
||||
|
||||
- name: Diff
|
||||
id: diff-step
|
||||
continue-on-error: true
|
||||
shell: bash
|
||||
run: |
|
||||
python3 .github/workflows/cppcheck-parse.py --severity E cppcheck_run.log | sort --key 3 > cppcheck_run.parsed.log
|
||||
python3 .github/workflows/cppcheck-parse.py --severity E .github/workflows/cppcheck_run.log | sort --key 3 > cppcheck_run.parsed.golden
|
||||
diff cppcheck_run.parsed.golden cppcheck_run.parsed.log \
|
||||
&& echo "No diffs found in cppcheck_run.log"
|
||||
|
||||
- name: Ensure cppcheck_run.parsed.log was updated
|
||||
id: diff-parsed-step
|
||||
continue-on-error: true
|
||||
shell: bash
|
||||
run: |
|
||||
diff cppcheck_run.parsed.golden .github/workflows/cppcheck_run.parsed.log \
|
||||
&& echo "No diffs found in cppcheck_run.parsed.log"
|
||||
|
||||
- name: Upload logs
|
||||
uses: actions/upload-artifact@c7d193f32edcb7bfad88892161225aeda64e9392 #v4
|
||||
with:
|
||||
name: cppcheck_log
|
||||
path: |
|
||||
cppcheck_run.log
|
||||
cppcheck_run.parsed.log
|
||||
|
||||
- name: Provide correct exit status
|
||||
shell: bash
|
||||
run: |
|
||||
ERROR_COUNT=$(grep cppcheck_run.log -e "severity=\"error\"" -c) || ERROR_COUNT=0
|
||||
EXPECTED_ERROR_COUNT=$(grep .github/workflows/cppcheck_run.log -e "severity=\"error\"" -c) || EXPECTED_ERROR_COUNT=0
|
||||
if [ $ERROR_COUNT -eq $EXPECTED_ERROR_COUNT ]
|
||||
then
|
||||
echo "cppcheck_run succeeded, found" $ERROR_COUNT "errors, as expected"
|
||||
if [ ${{steps.diff-step.outcome}} == "failure" ]
|
||||
then
|
||||
echo "however, the ---> DIFF FAILED <---"
|
||||
elif [ ${{steps.diff-parsed-step.outcome}} == "failure" ]
|
||||
then
|
||||
echo "however, the ---> PARSED log was not UPDATED <---"
|
||||
else
|
||||
exit 0
|
||||
fi
|
||||
elif [ $ERROR_COUNT -lt $EXPECTED_ERROR_COUNT ]
|
||||
then
|
||||
echo "cppcheck_run ---> SUCCEEDED <--- but found" $ERROR_COUNT "errors when expecting" $EXPECTED_ERROR_COUNT
|
||||
else
|
||||
echo "cppcheck_run ---> FAILED <--- with" $ERROR_COUNT "errors; expecting" $EXPECTED_ERROR_COUNT
|
||||
fi
|
||||
echo "see the diff step above, or the 'cppcheck_log' artifact (under Summary) for details"
|
||||
echo "commit all files in the artifact to .github/workflows/ if these are valid results"
|
||||
exit 1
|
||||
#---------------------------------------------------------------------------------------------------#
|
||||
ValgrindCheck:
|
||||
name: Valgrind Memory Leak Check
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Install Valgrind
|
||||
run: |
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
sudo apt-get install -y valgrind
|
||||
|
||||
- name: Move files into examples folder in order to build automaticly
|
||||
run: |
|
||||
sudo mv .github/workflows/memory-leaks-check examples/
|
||||
|
||||
- name: Modify CMakeLists.txt
|
||||
run: |
|
||||
# Path to the CMakeLists.txt file
|
||||
CMAKE_FILE=./examples/CMakeLists.txt
|
||||
|
||||
# Check if the line already exists to avoid duplicates
|
||||
if ! grep -q "add_subdirectory(memory-leaks-check)" "$CMAKE_FILE"; then
|
||||
# Add the line before the first occurrence of 'add_subdirectory(hello-realsense)'
|
||||
sed -i '/add_subdirectory(hello-realsense)/i add_subdirectory(memory-leaks-check)' "$CMAKE_FILE"
|
||||
fi
|
||||
|
||||
- name: Build Application
|
||||
run: |
|
||||
mkdir build
|
||||
cd build
|
||||
cmake .. -DBUILD_EXAMPLES=true
|
||||
make -j$(($(nproc)-1))
|
||||
|
||||
- name: Run Valgrind
|
||||
run: |
|
||||
cd build
|
||||
valgrind --leak-check=yes --show-leak-kinds=all --track-origins=yes --log-file=valgrind-out.txt ./Release/mem-leak-test
|
||||
continue-on-error: true
|
||||
|
||||
- name: Upload Valgrind log
|
||||
uses: actions/upload-artifact@c7d193f32edcb7bfad88892161225aeda64e9392 #v4
|
||||
with:
|
||||
name: valgrind-log
|
||||
path: build/valgrind-out.txt
|
||||
|
||||
- name: Check Valgrind Results
|
||||
run: |
|
||||
if grep -q "ERROR SUMMARY: [^0]" build/valgrind-out.txt; then
|
||||
echo "Valgrind detected errors with backend."
|
||||
exit 1
|
||||
else
|
||||
echo "No errors detected by Valgrind with backend."
|
||||
fi
|
||||
ASANCheck:
|
||||
name: ASAN Memory Leak Check
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Install Dependencies
|
||||
run: |
|
||||
sudo apt-get update;
|
||||
sudo apt-get install -qq build-essential xorg-dev libgl1-mesa-dev libglu1-mesa-dev libglew-dev libglm-dev;
|
||||
sudo apt-get install -qq libusb-1.0-0-dev;
|
||||
sudo apt-get install -qq libgtk-3-dev;
|
||||
sudo apt-get install libglfw3-dev libglfw3;
|
||||
|
||||
- name: Move files into examples folder in order to build automaticly
|
||||
run: |
|
||||
sudo mv .github/workflows/memory-leaks-check examples/
|
||||
|
||||
- name: Modify CMakeLists.txt
|
||||
run: |
|
||||
# Path to the CMakeLists.txt file
|
||||
CMAKE_FILE=./examples/CMakeLists.txt
|
||||
|
||||
# Check if the line already exists to avoid duplicates
|
||||
if ! grep -q "add_subdirectory(memory-leaks-check)" "$CMAKE_FILE"; then
|
||||
# Add the line before the first occurrence of 'add_subdirectory(hello-realsense)'
|
||||
sed -i '/add_subdirectory(hello-realsense)/i add_subdirectory(memory-leaks-check)' "$CMAKE_FILE"
|
||||
fi
|
||||
|
||||
- name: Build Application with ASAN
|
||||
run: |
|
||||
mkdir build
|
||||
cd build
|
||||
cmake .. -DBUILD_EXAMPLES=true -DBUILD_ASAN=true
|
||||
make -j$(($(nproc)-1))
|
||||
|
||||
- name: Run ASAN
|
||||
run: |
|
||||
cd build
|
||||
ASAN_OPTIONS=halt_on_error=0:detect_leaks=1:log_path=asan-out.txt ./Release/mem-leak-test
|
||||
continue-on-error: true
|
||||
|
||||
- name: Upload ASAN log
|
||||
uses: actions/upload-artifact@c7d193f32edcb7bfad88892161225aeda64e9392
|
||||
with:
|
||||
name: asan-log
|
||||
path: build/asan-out.txt*
|
||||
|
||||
- name: Check ASAN Results
|
||||
run: |
|
||||
# Use a wildcard to match the file with any number appended
|
||||
ASAN_FILE=$(ls build/asan-out.txt* 2>/dev/null || true)
|
||||
if [ -n "$ASAN_FILE" ]; then
|
||||
if grep -q "SUMMARY: AddressSanitizer:" "$ASAN_FILE"; then
|
||||
echo "ASAN detected memory leaks."
|
||||
exit 1
|
||||
else
|
||||
echo "No memory leaks detected by ASAN."
|
||||
fi
|
||||
else
|
||||
echo "No ASAN output file found. No errors detected."
|
||||
fi
|
||||
# We verify the minimal CMake version we support is preserved when building with default CMake flags
|
||||
minimal_cmake_version:
|
||||
name: "Minimal CMake version"
|
||||
timeout-minutes: 30
|
||||
runs-on: ubuntu-22.04
|
||||
steps:
|
||||
- name: Checkout
|
||||
uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: "Install Dependencies"
|
||||
run: |
|
||||
work_dir=$(pwd)
|
||||
# Go back from RealSense directory to parent directory
|
||||
cd ..
|
||||
|
||||
git clone https://github.com/nlohmann/cmake_min_version.git
|
||||
cd cmake_min_version
|
||||
# We clone a specific commit which we tested the process as working
|
||||
git checkout 687dc56e1cf52c865cebf6ac94ad67906d6e1369
|
||||
|
||||
echo "Install LibRealSense pre-installed packages requirements"
|
||||
sudo apt-get update
|
||||
sudo apt-get install libglfw3-dev libgl1-mesa-dev libglu1-mesa-dev at
|
||||
|
||||
python3 -mvenv venv
|
||||
venv/bin/pip3 install -r requirements.txt
|
||||
|
||||
- name: "Get Current CMake version"
|
||||
id: cmake_version
|
||||
run: |
|
||||
work_dir=$(pwd)
|
||||
cd ..
|
||||
|
||||
cd cmake_min_version
|
||||
venv/bin/python3 cmake_downloader.py --first_minor
|
||||
output=$(venv/bin/python3 cmake_min_version.py $work_dir)
|
||||
|
||||
# Sample of Expected Output of cmake_min_version.py ***
|
||||
# [ 0%] CMake 3.9.2 ✔ works
|
||||
# [ 12%] CMake 3.2.2 ✘ error
|
||||
# CMakeLists.txt:7 (cmake_minimum_required)
|
||||
# [ 33%] CMake 3.8.0 ✔ works
|
||||
# [ 50%] CMake 3.7.1 ✘ error
|
||||
# CMakeLists.txt:16 (target_compile_features)
|
||||
# [ 80%] CMake 3.7.2 ✘ error
|
||||
# CMakeLists.txt:16 (target_compile_features)
|
||||
# [100%] Minimal working version: CMake 3.8.0
|
||||
|
||||
# cmake_minimum_required(VERSION 3.8.0)
|
||||
|
||||
echo "$output"
|
||||
|
||||
# Retrieve CMake minimal version from the last line of the tool output.
|
||||
current_cmake_version=$(echo ${output} | grep -oP "VERSION \d+\.\d+" || echo "VERSION NOT FOUND")
|
||||
|
||||
if [ "$current_cmake_version" == "VERSION NOT FOUND" ]
|
||||
then
|
||||
echo "Error - CMake version not found."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
current_cmake_major_ver=$(echo $current_cmake_version | grep -oP "\d+\.\d+" | cut -d'.' -f 1)
|
||||
current_cmake_minor_ver=$(echo $current_cmake_version | grep -oP "\d+\.\d+" | cut -d'.' -f 2)
|
||||
|
||||
# Saving cmake output in GitHub output
|
||||
echo "current_cmake_major_ver=$current_cmake_major_ver" >> $GITHUB_OUTPUT
|
||||
echo "current_cmake_minor_ver=$current_cmake_minor_ver" >> $GITHUB_OUTPUT
|
||||
|
||||
- name: "Check minimal CMake version"
|
||||
env:
|
||||
EXPECTED_CMAKE_MAJOR_VER: 3
|
||||
EXPECTED_CMAKE_MINOR_VER: 8
|
||||
CURRENT_CMAKE_MAJOR_VER: ${{ steps.cmake_version.outputs.current_cmake_major_ver }}
|
||||
CURRENT_CMAKE_MINOR_VER: ${{ steps.cmake_version.outputs.current_cmake_minor_ver }}
|
||||
|
||||
run: |
|
||||
if [ $CURRENT_CMAKE_MAJOR_VER -lt ${EXPECTED_CMAKE_MAJOR_VER} ]
|
||||
then
|
||||
STATUS="PASSED"
|
||||
elif [ $CURRENT_CMAKE_MAJOR_VER -eq ${EXPECTED_CMAKE_MAJOR_VER} ] && [ $CURRENT_CMAKE_MINOR_VER -eq ${EXPECTED_CMAKE_MINOR_VER} ]
|
||||
then
|
||||
STATUS="PASSED"
|
||||
elif [ $CURRENT_CMAKE_MAJOR_VER -eq ${EXPECTED_CMAKE_MAJOR_VER} ] && [ $CURRENT_CMAKE_MINOR_VER -lt ${EXPECTED_CMAKE_MINOR_VER} ]
|
||||
then
|
||||
STATUS="PASSED"
|
||||
else
|
||||
STATUS="FAILED"
|
||||
fi
|
||||
|
||||
if [ $STATUS == "PASSED" ]
|
||||
then
|
||||
echo "The test PASSED, current CMake version is $CURRENT_CMAKE_MAJOR_VER.$CURRENT_CMAKE_MINOR_VER and it is not higher than VERSION ${EXPECTED_CMAKE_MAJOR_VER}.${EXPECTED_CMAKE_MINOR_VER}"
|
||||
else
|
||||
echo "Error - The minimal CMake version required for LibRS is ${EXPECTED_CMAKE_MAJOR_VER}.${EXPECTED_CMAKE_MINOR_VER} but on this build the minimal CMake version that works is $CURRENT_CMAKE_MAJOR_VER.$CURRENT_CMAKE_MINOR_VER"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
build_flags_docs:
|
||||
name: "Generate build-flags.html"
|
||||
timeout-minutes: 10
|
||||
runs-on: ubuntu-22.04
|
||||
steps:
|
||||
- name: Checkout
|
||||
uses: actions/checkout@692973e3d937129bcbf40652eb9f2f61becf3332 #v4
|
||||
|
||||
- name: Build docs
|
||||
run: |
|
||||
python3 scripts/lrs_options-to-html.py
|
||||
91
librealsense-r-256/.gitignore
vendored
Normal file
91
librealsense-r-256/.gitignore
vendored
Normal file
@@ -0,0 +1,91 @@
|
||||
bin/
|
||||
lib/
|
||||
|
||||
ubuntu-xenial/
|
||||
ubuntu-xenial-hwe/
|
||||
|
||||
# Docs
|
||||
doc/doxygen/html/
|
||||
*.html.lnk
|
||||
|
||||
# CMake
|
||||
build*/
|
||||
connectivity_check
|
||||
|
||||
# XCode
|
||||
.DS_Store
|
||||
*.pbxuser
|
||||
!default.pbxuser
|
||||
*.mode1v3
|
||||
!default.mode1v3
|
||||
*.mode2v3
|
||||
!default.mode2v3
|
||||
*.perspectivev3
|
||||
!default.perspectivev3
|
||||
xcuserdata
|
||||
*.xccheckout
|
||||
*.moved-aside
|
||||
DerivedData
|
||||
*.xcuserstate
|
||||
librealsense.xc/build
|
||||
|
||||
*~
|
||||
*.TMP
|
||||
*.a
|
||||
*.o
|
||||
*.so
|
||||
*.pyc
|
||||
*.class
|
||||
|
||||
local_ignore/
|
||||
|
||||
#Visual Studio Project
|
||||
.vs/*
|
||||
|
||||
#Clion Project
|
||||
.idea/*
|
||||
|
||||
# QTCreator Project
|
||||
/.qmake.cache
|
||||
/.qmake.stash
|
||||
*.user
|
||||
*.user.*
|
||||
*.moc
|
||||
moc_*.cpp
|
||||
qrc_*.cpp
|
||||
ui_*.h
|
||||
Makefile*
|
||||
*-build-*
|
||||
librealsense-log.txt
|
||||
|
||||
*.pyproj
|
||||
*.orig
|
||||
*.psess
|
||||
*.vspx
|
||||
*.vsp
|
||||
*.bak
|
||||
*.bin
|
||||
*.suo
|
||||
*.tlog
|
||||
*.ilk
|
||||
*.pdb
|
||||
*.exp
|
||||
*.log
|
||||
*.stamp
|
||||
*.depend
|
||||
*.vcxproj
|
||||
*.exe
|
||||
*.cache
|
||||
*.lib
|
||||
*.filters
|
||||
*.db
|
||||
*.opendb
|
||||
*.rule
|
||||
*.check_cache
|
||||
*.dll
|
||||
*.list
|
||||
*.json
|
||||
*.ini
|
||||
*.cxx
|
||||
|
||||
.vscode/*
|
||||
35
librealsense-r-256/CMake/Findfoonathan_memory.cmake
Normal file
35
librealsense-r-256/CMake/Findfoonathan_memory.cmake
Normal file
@@ -0,0 +1,35 @@
|
||||
|
||||
# This is a dummy file, just so CMake does not complain:
|
||||
|
||||
# CMake Error at build/third-party/fastdds/CMakeLists.txt:239 (find_package):
|
||||
# By not providing "Findfoonathan_memory.cmake" in CMAKE_MODULE_PATH this
|
||||
# project has asked CMake to find a package configuration file provided by
|
||||
# "foonathan_memory", but CMake did not find one.
|
||||
#
|
||||
# Could not find a package configuration file provided by "foonathan_memory"
|
||||
# with any of the following names:
|
||||
#
|
||||
# foonathan_memoryConfig.cmake
|
||||
# foonathan_memory-config.cmake
|
||||
#
|
||||
# Add the installation prefix of "foonathan_memory" to CMAKE_PREFIX_PATH or
|
||||
# set "foonathan_memory_DIR" to a directory containing one of the above
|
||||
# files. If "foonathan_memory" provides a separate development package or
|
||||
# SDK, be sure it has been installed.
|
||||
|
||||
# FastDDS requires foonathan_memory and will not find it if we do not provide this
|
||||
# file.
|
||||
#
|
||||
# Since all the variables should already be set by external_foonathan_memory.cmake,
|
||||
# we don't really do anything.
|
||||
|
||||
# This may not be the proper way to do this. But it works...
|
||||
|
||||
|
||||
#message( "In Findfoonathan_memory.cmake" )
|
||||
|
||||
|
||||
#find_package( PkgConfig )
|
||||
#pkg_check_modules( foonathan_memory QUIET foonathan_memory )
|
||||
|
||||
|
||||
33
librealsense-r-256/CMake/android_config.cmake
Normal file
33
librealsense-r-256/CMake/android_config.cmake
Normal file
@@ -0,0 +1,33 @@
|
||||
message(STATUS "Setting Android configurations")
|
||||
message(STATUS "Prepare RealSense SDK for Android OS (${ANDROID_NDK_ABI_NAME})")
|
||||
|
||||
macro(os_set_flags)
|
||||
unset(WIN32)
|
||||
unset(UNIX)
|
||||
unset(APPLE)
|
||||
set(BUILD_UNIT_TESTS OFF)
|
||||
set(BUILD_EXAMPLES OFF)
|
||||
set(BUILD_TOOLS OFF)
|
||||
set(BUILD_WITH_OPENMP OFF)
|
||||
set(BUILD_GRAPHICAL_EXAMPLES OFF)
|
||||
set(ANDROID_STL "c++_static")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fPIC -pedantic -g -D_DEFAULT_SOURCE")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fPIC -pedantic -g -Wno-missing-field-initializers")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-switch -Wno-multichar")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fPIE -pie")
|
||||
set(HWM_OVER_XU ON)
|
||||
|
||||
if(FORCE_RSUSB_BACKEND)
|
||||
set(BACKEND RS2_USE_ANDROID_BACKEND)
|
||||
set(IMPORT_DEPTH_CAM_FW OFF)
|
||||
else()
|
||||
set(BACKEND RS2_USE_V4L2_BACKEND)
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
macro(os_target_config)
|
||||
if(BUILD_SHARED_LIBS)
|
||||
find_library(log-lib log)
|
||||
target_link_libraries(${LRS_TARGET} PRIVATE log)
|
||||
endif()
|
||||
endmacro()
|
||||
19
librealsense-r-256/CMake/catch2-download.cmake.in
Normal file
19
librealsense-r-256/CMake/catch2-download.cmake.in
Normal file
@@ -0,0 +1,19 @@
|
||||
cmake_minimum_required(VERSION 3.6)
|
||||
project(catch2-download NONE)
|
||||
|
||||
include(ExternalProject)
|
||||
ExternalProject_Add(
|
||||
catch2
|
||||
PREFIX .
|
||||
GIT_REPOSITORY https://github.com/catchorg/Catch2.git
|
||||
GIT_TAG v3.4.0
|
||||
GIT_CONFIG advice.detachedHead=false # otherwise we'll get "You are in 'detached HEAD' state..."
|
||||
SOURCE_DIR "${CMAKE_BINARY_DIR}/third-party/catch2"
|
||||
GIT_SHALLOW 1 # No history needed (requires cmake 3.6)
|
||||
# Override default steps with no action, we just want the clone step.
|
||||
CONFIGURE_COMMAND ""
|
||||
BUILD_COMMAND ""
|
||||
INSTALL_COMMAND ""
|
||||
)
|
||||
|
||||
|
||||
12
librealsense-r-256/CMake/connectivity_check.cmake
Normal file
12
librealsense-r-256/CMake/connectivity_check.cmake
Normal file
@@ -0,0 +1,12 @@
|
||||
# License: Apache 2.0. See LICENSE file in root directory.
|
||||
# Copyright(c) 2019 Intel Corporation. All Rights Reserved.
|
||||
message(STATUS "Checking internet connection...")
|
||||
file(DOWNLOAD "https://librealsense.intel.com/Releases/connectivity_check" "${CMAKE_CURRENT_BINARY_DIR}/connectivity_check" SHOW_PROGRESS TIMEOUT 5 STATUS status)
|
||||
list (FIND status "\"No error\"" _index)
|
||||
if (${_index} EQUAL -1)
|
||||
message(STATUS "Failed to identify Internet connection")
|
||||
set(INTERNET_CONNECTION OFF)
|
||||
else()
|
||||
message(STATUS "Internet connection identified")
|
||||
set(INTERNET_CONNECTION ON)
|
||||
endif()
|
||||
15
librealsense-r-256/CMake/cuda_config.cmake
Normal file
15
librealsense-r-256/CMake/cuda_config.cmake
Normal file
@@ -0,0 +1,15 @@
|
||||
info("Building with CUDA requires CMake v3.8+")
|
||||
cmake_minimum_required(VERSION 3.8.0)
|
||||
enable_language( CUDA )
|
||||
|
||||
find_package(CUDA REQUIRED)
|
||||
|
||||
include_directories(${CUDA_INCLUDE_DIRS})
|
||||
SET(ALL_CUDA_LIBS ${CUDA_LIBRARIES} ${CUDA_cusparse_LIBRARY} ${CUDA_cublas_LIBRARY})
|
||||
SET(LIBS ${LIBS} ${ALL_CUDA_LIBS})
|
||||
|
||||
message(STATUS "CUDA_LIBRARIES: ${CUDA_INCLUDE_DIRS} ${ALL_CUDA_LIBS}")
|
||||
|
||||
set(CUDA_PROPAGATE_HOST_FLAGS OFF)
|
||||
set(CUDA_SEPARABLE_COMPILATION ON)
|
||||
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS}; -O3 -gencode arch=compute_53,code=sm_53 -gencode arch=compute_62,code=sm_62;")
|
||||
28
librealsense-r-256/CMake/embedd_udev_rules.cmake
Normal file
28
librealsense-r-256/CMake/embedd_udev_rules.cmake
Normal file
@@ -0,0 +1,28 @@
|
||||
file(READ "config/99-realsense-libusb.rules" contents HEX)
|
||||
|
||||
set(UDEV_HEADER "${CMAKE_CURRENT_BINARY_DIR}/udev-rules.h")
|
||||
|
||||
file(WRITE "${UDEV_HEADER}" "#ifndef __UDEV_RULES_H__\n")
|
||||
file(APPEND "${UDEV_HEADER}" "#define __UDEV_RULES_H__\n")
|
||||
file(APPEND "${UDEV_HEADER}" "#ifdef __cplusplus\n")
|
||||
file(APPEND "${UDEV_HEADER}" "extern \"C\" {\n")
|
||||
file(APPEND "${UDEV_HEADER}" "#endif\n")
|
||||
|
||||
file(APPEND "${UDEV_HEADER}" "const char "
|
||||
"realsense_udev_rules[] = {")
|
||||
|
||||
string(LENGTH "${contents}" contents_length)
|
||||
math(EXPR contents_length "${contents_length} - 1")
|
||||
|
||||
foreach(iter RANGE 0 ${contents_length} 2)
|
||||
string(SUBSTRING ${contents} ${iter} 2 line)
|
||||
file(APPEND "${UDEV_HEADER}" "0x${line},")
|
||||
endforeach()
|
||||
|
||||
file(APPEND "${UDEV_HEADER}" "};\n")
|
||||
|
||||
file(APPEND "${UDEV_HEADER}" "#ifdef __cplusplus\n")
|
||||
file(APPEND "${UDEV_HEADER}" "}\n")
|
||||
file(APPEND "${UDEV_HEADER}" "#endif\n")
|
||||
|
||||
file(APPEND "${UDEV_HEADER}" "#endif//\n")
|
||||
51
librealsense-r-256/CMake/external_catch2.cmake
Normal file
51
librealsense-r-256/CMake/external_catch2.cmake
Normal file
@@ -0,0 +1,51 @@
|
||||
cmake_minimum_required(VERSION 3.10)
|
||||
include(ExternalProject)
|
||||
|
||||
|
||||
# We use a function to enforce a scoped variables creation only for the build
|
||||
# (i.e turn off BUILD_SHARED_LIBS which is used on LRS build as well)
|
||||
function(get_catch2)
|
||||
|
||||
message( STATUS "Fetching Catch2..." )
|
||||
|
||||
# We want to clone the repo and build it here, during configuration, so we can use it.
|
||||
# But ExternalProject_add is limited in that it only does its magic during build.
|
||||
# This is possible in CMake 3.12+ with FetchContent and FetchContent_MakeAvailable in 3.14+ (meaning Ubuntu 20)
|
||||
# but we need to adhere to CMake 3.10 (Ubuntu 18).
|
||||
# So instead, we invoke a new CMake project just to download it:
|
||||
configure_file( CMake/catch2-download.cmake.in
|
||||
${CMAKE_BINARY_DIR}/external-projects/catch2-download/CMakeLists.txt )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" -G "${CMAKE_GENERATOR}" . "--no-warn-unused-cli"
|
||||
-DCMAKE_MAKE_PROGRAM=${CMAKE_MAKE_PROGRAM}
|
||||
-DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE}
|
||||
-DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/catch2-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE configure_ret )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" --build .
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/catch2-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE build_ret )
|
||||
|
||||
if( configure_ret OR build_ret )
|
||||
message( FATAL_ERROR "Failed to download catchorg/catch2" )
|
||||
endif()
|
||||
|
||||
# We use cached variables so the default parameter inside the sub directory will not override the required values
|
||||
# We add "FORCE" so that is a previous cached value is set our assignment will override it.
|
||||
set( CATCH_INSTALL_DOCS OFF CACHE INTERNAL "" FORCE )
|
||||
set( CATCH_INSTALL_EXTRAS OFF CACHE INTERNAL "" FORCE )
|
||||
|
||||
add_subdirectory( "${CMAKE_BINARY_DIR}/third-party/catch2"
|
||||
"${CMAKE_BINARY_DIR}/third-party/catch2/build" )
|
||||
|
||||
# place libraries with other 3rd-party projects
|
||||
set_target_properties( Catch2 Catch2WithMain PROPERTIES
|
||||
FOLDER "3rd Party/catch2" )
|
||||
|
||||
message( STATUS "Fetching Catch2 - Done" )
|
||||
|
||||
endfunction()
|
||||
|
||||
|
||||
get_catch2()
|
||||
79
librealsense-r-256/CMake/external_fastdds.cmake
Normal file
79
librealsense-r-256/CMake/external_fastdds.cmake
Normal file
@@ -0,0 +1,79 @@
|
||||
cmake_minimum_required(VERSION 3.16.3) # same as in FastDDS (U20)
|
||||
include(FetchContent)
|
||||
|
||||
# We use a function to enforce a scoped variables creation only for FastDDS build (i.e turn off BUILD_SHARED_LIBS which is used on LRS build as well)
|
||||
function(get_fastdds)
|
||||
|
||||
# Mark new options from FetchContent as advanced options
|
||||
mark_as_advanced(FETCHCONTENT_QUIET)
|
||||
mark_as_advanced(FETCHCONTENT_BASE_DIR)
|
||||
mark_as_advanced(FETCHCONTENT_FULLY_DISCONNECTED)
|
||||
mark_as_advanced(FETCHCONTENT_UPDATES_DISCONNECTED)
|
||||
|
||||
message(CHECK_START "Fetching fastdds...")
|
||||
list(APPEND CMAKE_MESSAGE_INDENT " ") # Indent outputs
|
||||
|
||||
FetchContent_Declare(
|
||||
fastdds
|
||||
GIT_REPOSITORY https://github.com/eProsima/Fast-DDS.git
|
||||
# 2.10.x is eProsima's last LTS version that still supports U20
|
||||
# 2.10.4 has specific modifications based on support provided, but it has some incompatibility
|
||||
# with the way we clone (which works with v2.11+), so they made a fix and tagged it for us:
|
||||
# Once they have 2.10.5 we should move to it
|
||||
GIT_TAG v2.10.4-realsense
|
||||
GIT_SUBMODULES "" # Submodules will be cloned as part of the FastDDS cmake configure stage
|
||||
GIT_SHALLOW ON # No history needed
|
||||
SOURCE_DIR ${CMAKE_BINARY_DIR}/third-party/fastdds
|
||||
)
|
||||
|
||||
# Set FastDDS internal variables
|
||||
# We use cached variables so the default parameter inside the sub directory will not override the required values
|
||||
# We add "FORCE" so that is a previous cached value is set our assignment will override it.
|
||||
set(THIRDPARTY_Asio FORCE CACHE INTERNAL "" FORCE)
|
||||
set(THIRDPARTY_fastcdr FORCE CACHE INTERNAL "" FORCE)
|
||||
set(THIRDPARTY_TinyXML2 FORCE CACHE INTERNAL "" FORCE)
|
||||
set(COMPILE_TOOLS OFF CACHE INTERNAL "" FORCE)
|
||||
set(BUILD_TESTING OFF CACHE INTERNAL "" FORCE)
|
||||
set(SQLITE3_SUPPORT OFF CACHE INTERNAL "" FORCE)
|
||||
#set(ENABLE_OLD_LOG_MACROS OFF CACHE INTERNAL "" FORCE) doesn't work
|
||||
set(FASTDDS_STATISTICS OFF CACHE INTERNAL "" FORCE)
|
||||
# Enforce NO_TLS to disable SSL: if OpenSSL is found, it will be linked to, and we don't want it!
|
||||
set(NO_TLS ON CACHE INTERNAL "" FORCE)
|
||||
|
||||
# Set special values for FastDDS sub directory
|
||||
set(BUILD_SHARED_LIBS OFF)
|
||||
set(CMAKE_INSTALL_PREFIX ${CMAKE_BINARY_DIR}/fastdds/fastdds_install)
|
||||
set(CMAKE_PREFIX_PATH ${CMAKE_BINARY_DIR}/fastdds/fastdds_install)
|
||||
|
||||
# Get fastdds
|
||||
FetchContent_MakeAvailable(fastdds)
|
||||
|
||||
# Mark new options from FetchContent as advanced options
|
||||
mark_as_advanced(FETCHCONTENT_SOURCE_DIR_FASTDDS)
|
||||
mark_as_advanced(FETCHCONTENT_UPDATES_DISCONNECTED_FASTDDS)
|
||||
|
||||
# place FastDDS project with other 3rd-party projects
|
||||
set_target_properties(fastcdr fastrtps foonathan_memory PROPERTIES
|
||||
FOLDER "3rd Party/fastdds")
|
||||
|
||||
list(POP_BACK CMAKE_MESSAGE_INDENT) # Unindent outputs
|
||||
|
||||
add_library(dds INTERFACE)
|
||||
target_link_libraries( dds INTERFACE fastcdr fastrtps )
|
||||
|
||||
disable_third_party_warnings(fastcdr)
|
||||
disable_third_party_warnings(fastrtps)
|
||||
|
||||
add_definitions(-DBUILD_WITH_DDS)
|
||||
|
||||
install(TARGETS dds EXPORT realsense2Targets)
|
||||
message(CHECK_PASS "Done")
|
||||
endfunction()
|
||||
|
||||
|
||||
pop_security_flags()
|
||||
|
||||
# Trigger the FastDDS build
|
||||
get_fastdds()
|
||||
|
||||
push_security_flags()
|
||||
48
librealsense-r-256/CMake/external_foonathan_memory.cmake
Normal file
48
librealsense-r-256/CMake/external_foonathan_memory.cmake
Normal file
@@ -0,0 +1,48 @@
|
||||
cmake_minimum_required(VERSION 3.11)
|
||||
include(FetchContent)
|
||||
|
||||
# We use a function to enforce a scoped variables creation only for FastDDS build (i.e turn off BUILD_SHARED_LIBS which is used on LRS build as well)
|
||||
function(get_foonathan_memory)
|
||||
|
||||
# Mark new options from FetchContent as advanced options
|
||||
mark_as_advanced(FETCHCONTENT_QUIET)
|
||||
mark_as_advanced(FETCHCONTENT_BASE_DIR)
|
||||
mark_as_advanced(FETCHCONTENT_FULLY_DISCONNECTED)
|
||||
mark_as_advanced(FETCHCONTENT_UPDATES_DISCONNECTED)
|
||||
|
||||
message(CHECK_START "Fetching foonathan_memory...")
|
||||
list(APPEND CMAKE_MESSAGE_INDENT " ")
|
||||
|
||||
FetchContent_Declare(
|
||||
foonathan_memory
|
||||
GIT_REPOSITORY https://github.com/foonathan/memory.git
|
||||
GIT_TAG "v0.7-3"
|
||||
GIT_SHALLOW ON # No history needed
|
||||
SOURCE_DIR ${CMAKE_CURRENT_BINARY_DIR}/third-party/foonathan_memory
|
||||
)
|
||||
|
||||
# Always a static library
|
||||
set( BUILD_SHARED_LIBS OFF )
|
||||
|
||||
# Set foonathan_memory variables
|
||||
# These are exposed options; not internal
|
||||
set( FOONATHAN_MEMORY_BUILD_EXAMPLES OFF )
|
||||
set( FOONATHAN_MEMORY_BUILD_TESTS OFF )
|
||||
set( FOONATHAN_MEMORY_BUILD_TOOLS OFF )
|
||||
|
||||
FetchContent_MakeAvailable( foonathan_memory )
|
||||
|
||||
# Mark new options from FetchContent as advanced options
|
||||
mark_as_advanced(FETCHCONTENT_SOURCE_DIR_FOONATHAN_MEMORY)
|
||||
mark_as_advanced(FETCHCONTENT_UPDATES_DISCONNECTED_FOONATHAN_MEMORY)
|
||||
|
||||
list(POP_BACK CMAKE_MESSAGE_INDENT)
|
||||
message(CHECK_PASS "Done")
|
||||
|
||||
endfunction()
|
||||
|
||||
pop_security_flags()
|
||||
|
||||
get_foonathan_memory()
|
||||
|
||||
push_security_flags()
|
||||
50
librealsense-r-256/CMake/external_json.cmake
Normal file
50
librealsense-r-256/CMake/external_json.cmake
Normal file
@@ -0,0 +1,50 @@
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
include(ExternalProject)
|
||||
|
||||
|
||||
|
||||
# We use a function to enforce a scoped variables creation only for the build
|
||||
# (i.e turn off BUILD_SHARED_LIBS which is used on LRS build as well)
|
||||
function(get_nlohmann_json)
|
||||
|
||||
message( STATUS #CHECK_START
|
||||
"Fetching nlohmann/json..." )
|
||||
#list( APPEND CMAKE_MESSAGE_INDENT " " ) # Indent outputs
|
||||
|
||||
# We want to clone the json repo and build it here, during configuration, so we can use it.
|
||||
# But ExternalProject_add is limited in that it only does its magic during build.
|
||||
# This is possible in CMake 3.12+ with FetchContent and FetchContent_MakeAvailable in 3.14+ (meaning Ubuntu 20)
|
||||
# but we need to adhere to CMake 3.10 (Ubuntu 18).
|
||||
# So instead, we invoke a new CMake project just to download pybind:
|
||||
configure_file( CMake/json-download.cmake.in
|
||||
${CMAKE_BINARY_DIR}/external-projects/json-download/CMakeLists.txt )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" -G "${CMAKE_GENERATOR}" . "--no-warn-unused-cli"
|
||||
-DCMAKE_MAKE_PROGRAM=${CMAKE_MAKE_PROGRAM}
|
||||
-DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE}
|
||||
-DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/json-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE configure_ret )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" --build .
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/json-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE build_ret )
|
||||
|
||||
if( configure_ret OR build_ret )
|
||||
message( FATAL_ERROR "Failed to download nlohmann/json" )
|
||||
endif()
|
||||
|
||||
add_subdirectory( "${CMAKE_BINARY_DIR}/third-party/json"
|
||||
"${CMAKE_BINARY_DIR}/third-party/json/build" )
|
||||
|
||||
# We cannot directly interface with nlohmann_json (doesn't work on bionic)
|
||||
#install( TARGETS nlohmann_json EXPORT realsense2Targets )
|
||||
|
||||
message( STATUS #CHECK_PASS
|
||||
"Fetching nlohmann/json - Done" )
|
||||
#list( POP_BACK CMAKE_MESSAGE_INDENT ) # Unindent outputs (requires cmake 3.15)
|
||||
|
||||
endfunction()
|
||||
|
||||
# Trigger the build
|
||||
get_nlohmann_json()
|
||||
67
librealsense-r-256/CMake/external_libcurl.cmake
Normal file
67
librealsense-r-256/CMake/external_libcurl.cmake
Normal file
@@ -0,0 +1,67 @@
|
||||
if(CHECK_FOR_UPDATES)
|
||||
|
||||
pop_security_flags() # remove security flags
|
||||
|
||||
include(ExternalProject)
|
||||
message(STATUS "Building libcurl enabled")
|
||||
|
||||
set(CURL_FLAGS -DBUILD_CURL_EXE=OFF -DBUILD_SHARED_LIBS=OFF -DUSE_WIN32_LDAP=OFF -DHTTP_ONLY=ON -DCURL_ZLIB=OFF -DCURL_DISABLE_CRYPTO_AUTH=ON -DCURL_USE_LIBSSH2=OFF -DCURL_DISABLE_TESTS=ON )
|
||||
if (WIN32)
|
||||
set(CURL_FLAGS ${CURL_FLAGS} -DCURL_STATIC_CRT=ON )
|
||||
endif()
|
||||
|
||||
# Add SSL library flag
|
||||
if (WIN32)
|
||||
set(CURL_FLAGS ${CURL_FLAGS} -DCURL_USE_SCHANNEL=ON )
|
||||
else()
|
||||
set(CURL_FLAGS ${CURL_FLAGS} -DCURL_USE_OPENSSL=ON )
|
||||
endif()
|
||||
|
||||
ExternalProject_Add(
|
||||
libcurl
|
||||
PREFIX libcurl
|
||||
GIT_REPOSITORY "https://github.com/curl/curl.git"
|
||||
GIT_TAG "curl-8_8_0"
|
||||
SOURCE_DIR ${CMAKE_CURRENT_BINARY_DIR}/third-party/libcurl
|
||||
CMAKE_ARGS -DCMAKE_CXX_FLAGS=${CMAKE_CXX_FLAGS}
|
||||
-DCMAKE_C_FLAGS=${CMAKE_C_FLAGS}
|
||||
-DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}
|
||||
-DCMAKE_C_FLAGS_DEBUG=${CMAKE_C_FLAGS_DEBUG}
|
||||
-DCMAKE_C_FLAGS_MINSIZEREL=${CMAKE_C_FLAGS_MINSIZEREL}
|
||||
-DCMAKE_C_FLAGS_RELEASE=${CMAKE_C_FLAGS_RELEASE}
|
||||
-DCMAKE_C_FLAGS_RELWITHDEBINFO=${CMAKE_C_FLAGS_RELWITHDEBINFO}
|
||||
-DCMAKE_CXX_STANDARD_LIBRARIES=${CMAKE_CXX_STANDARD_LIBRARIES}
|
||||
-DCMAKE_INSTALL_PREFIX=${CMAKE_CURRENT_BINARY_DIR}/libcurl/libcurl_install
|
||||
-DCMAKE_INSTALL_LIBDIR=lib
|
||||
-DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE}
|
||||
-DANDROID_ABI=${ANDROID_ABI}
|
||||
-DANDROID_STL=${ANDROID_STL} ${CURL_FLAGS}
|
||||
UPDATE_COMMAND ""
|
||||
PATCH_COMMAND ""
|
||||
TEST_COMMAND ""
|
||||
)
|
||||
|
||||
set(CURL_DEBUG_TARGET_NAME "libcurl-d")
|
||||
set(CURL_RELEASE_TARGET_NAME "libcurl")
|
||||
add_library(curl INTERFACE)
|
||||
add_definitions(-DCURL_STATICLIB) # Mandatory for building libcurl as static lib
|
||||
|
||||
target_include_directories(curl INTERFACE $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}/libcurl/libcurl_install/include>)
|
||||
|
||||
target_link_libraries(curl INTERFACE debug ${CMAKE_CURRENT_BINARY_DIR}/libcurl/libcurl_install/lib/${CURL_DEBUG_TARGET_NAME}${CMAKE_STATIC_LIBRARY_SUFFIX})
|
||||
target_link_libraries(curl INTERFACE optimized ${CMAKE_CURRENT_BINARY_DIR}/libcurl/libcurl_install/lib/${CURL_RELEASE_TARGET_NAME}${CMAKE_STATIC_LIBRARY_SUFFIX})
|
||||
|
||||
# libcurl required libs per OS
|
||||
# (Linux require that the link dependency will be added after the libcurl link target that use it)
|
||||
if (WIN32)
|
||||
target_link_libraries(curl INTERFACE ws2_32.lib crypt32.lib)
|
||||
else()
|
||||
find_package(OpenSSL REQUIRED)
|
||||
target_link_libraries(curl INTERFACE OpenSSL::SSL OpenSSL::Crypto)
|
||||
if (APPLE)
|
||||
target_link_libraries(curl INTERFACE "-framework CoreFoundation -framework SystemConfiguration")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
push_security_flags()
|
||||
endif() #CHECK_FOR_UPDATES
|
||||
37
librealsense-r-256/CMake/external_libusb.cmake
Normal file
37
librealsense-r-256/CMake/external_libusb.cmake
Normal file
@@ -0,0 +1,37 @@
|
||||
include(ExternalProject)
|
||||
|
||||
ExternalProject_Add(
|
||||
libusb
|
||||
PREFIX libusb
|
||||
GIT_REPOSITORY "https://github.com/libusb/libusb-cmake.git"
|
||||
GIT_TAG "v1.0.27-1" # "v1.0.27-1"
|
||||
|
||||
UPDATE_COMMAND ""
|
||||
PATCH_COMMAND ""
|
||||
|
||||
SOURCE_DIR "third-party/libusb/"
|
||||
CMAKE_ARGS -DCMAKE_CXX_STANDARD_LIBRARIES=${CMAKE_CXX_STANDARD_LIBRARIES}
|
||||
-DCMAKE_TOOLCHAIN_FILE=${CMAKE_TOOLCHAIN_FILE}
|
||||
-DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}
|
||||
-DANDROID_ABI=${ANDROID_ABI}
|
||||
-DANDROID_STL=${ANDROID_STL}
|
||||
-DBUILD_SHARED_LIBS=OFF
|
||||
-DCMAKE_INSTALL_PREFIX=${CMAKE_CURRENT_BINARY_DIR}/libusb_install
|
||||
-DLIBUSB_INSTALL_TARGETS=ON
|
||||
--no-warn-unused-cli
|
||||
TEST_COMMAND ""
|
||||
#BUILD_BYPRODUCTS ${CMAKE_CURRENT_BINARY_DIR}/libusb_install/lib/${CMAKE_STATIC_LIBRARY_PREFIX}usb${CMAKE_STATIC_LIBRARY_SUFFIX}
|
||||
)
|
||||
|
||||
add_library(usb INTERFACE)
|
||||
target_include_directories(usb INTERFACE $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}/third-party/libusb/libusb>)
|
||||
target_link_libraries(usb INTERFACE ${CMAKE_CURRENT_BINARY_DIR}/libusb_install/lib/${CMAKE_STATIC_LIBRARY_PREFIX}libusb-1.0${CMAKE_STATIC_LIBRARY_SUFFIX})
|
||||
set(USE_EXTERNAL_USB ON) # INTERFACE libraries can't have real deps, so targets that link with usb need to also depend on libusb
|
||||
|
||||
set_target_properties( libusb PROPERTIES FOLDER "3rd Party")
|
||||
|
||||
if (APPLE)
|
||||
find_library(corefoundation_lib CoreFoundation)
|
||||
find_library(iokit_lib IOKit)
|
||||
target_link_libraries(usb INTERFACE objc ${corefoundation_lib} ${iokit_lib})
|
||||
endif()
|
||||
142
librealsense-r-256/CMake/external_pybind11.cmake
Normal file
142
librealsense-r-256/CMake/external_pybind11.cmake
Normal file
@@ -0,0 +1,142 @@
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
include(ExternalProject)
|
||||
|
||||
|
||||
|
||||
# We use a function to enforce a scoped variables creation only for the build
|
||||
# (i.e turn off BUILD_SHARED_LIBS which is used on LRS build as well)
|
||||
function(get_pybind11)
|
||||
|
||||
message( STATUS #CHECK_START
|
||||
"Fetching pybind11..." )
|
||||
#list( APPEND CMAKE_MESSAGE_INDENT " " ) # Indent outputs
|
||||
|
||||
# We want to clone the pybind repo and build it here, during configuration, so we can use it.
|
||||
# But ExternalProject_add is limited in that it only does its magic during build.
|
||||
# This is possible in CMake 3.12+ with FetchContent and FetchContent_MakeAvailable in 3.14+ (meaning Ubuntu 20)
|
||||
# but we need to adhere to CMake 3.10 (Ubuntu 18).
|
||||
# So instead, we invoke a new CMake project just to download pybind:
|
||||
configure_file( CMake/pybind11-download.cmake.in
|
||||
${CMAKE_BINARY_DIR}/external-projects/pybind11-download/CMakeLists.txt )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" -G "${CMAKE_GENERATOR}" .
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/pybind11-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE configure_ret )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" --build .
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/pybind11-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE build_ret )
|
||||
|
||||
if( configure_ret OR build_ret )
|
||||
message( FATAL_ERROR "Failed to download pybind11" )
|
||||
endif()
|
||||
|
||||
# Now that it's available, we can refer to it with an actual ExternalProject_add (but notice we're not
|
||||
# downloading anything)
|
||||
ExternalProject_Add( pybind11
|
||||
PREFIX ${CMAKE_BINARY_DIR}/external-projects/pybind11 # just so it doesn't use build/pybind11-prefix
|
||||
SOURCE_DIR ${CMAKE_BINARY_DIR}/third-party/pybind11
|
||||
BINARY_DIR ${CMAKE_BINARY_DIR}/third-party/pybind11/build
|
||||
CMAKE_ARGS
|
||||
-DCMAKE_CXX_STANDARD=${CMAKE_CXX_STANDARD}
|
||||
-DPYTHON_EXECUTABLE=${PYTHON_EXECUTABLE}
|
||||
-DBUILD_SHARED_LIBS=OFF
|
||||
# Suppress warnings that are meant for the author of the CMakeLists.txt files
|
||||
-Wno-dev
|
||||
# Just in case!
|
||||
-DPYBIND11_INSTALL=OFF
|
||||
-DPYBIND11_TEST=OFF
|
||||
|
||||
INSTALL_COMMAND ""
|
||||
UPDATE_COMMAND ""
|
||||
PATCH_COMMAND ""
|
||||
TEST_COMMAND ""
|
||||
)
|
||||
|
||||
add_subdirectory( "${CMAKE_BINARY_DIR}/third-party/pybind11"
|
||||
"${CMAKE_BINARY_DIR}/third-party/pybind11/build" )
|
||||
|
||||
set_target_properties( pybind11 PROPERTIES FOLDER "3rd Party" )
|
||||
|
||||
# Besides pybind11, any python module will also need to be installed using:
|
||||
# install(
|
||||
# TARGETS ${PROJECT_NAME}
|
||||
# EXPORT pyrealsense2Targets
|
||||
# LIBRARY DESTINATION ${PYTHON_INSTALL_DIR}
|
||||
# ARCHIVE DESTINATION ${PYTHON_INSTALL_DIR}
|
||||
# )
|
||||
# But, to do this, we need to define PYTHON_INSTALL_DIR!
|
||||
if( CMAKE_VERSION VERSION_LESS 3.12 )
|
||||
find_package(PythonInterp REQUIRED)
|
||||
find_package(PythonLibs REQUIRED)
|
||||
set( PYTHON_INSTALL_DIR "${CMAKE_INSTALL_LIBDIR}/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/pyrealsense2" CACHE PATH "Installation directory for Python bindings")
|
||||
else()
|
||||
find_package(Python REQUIRED COMPONENTS Interpreter Development)
|
||||
set( PYTHON_INSTALL_DIR "${Python_SITEARCH}/pyrealsense2" CACHE PATH "Installation directory for Python bindings")
|
||||
endif()
|
||||
|
||||
message( STATUS #CHECK_PASS
|
||||
"Fetching pybind11 - Done" )
|
||||
#list( POP_BACK CMAKE_MESSAGE_INDENT ) # Unindent outputs (requires cmake 3.15)
|
||||
|
||||
endfunction()
|
||||
|
||||
|
||||
# We also want a json-compatible pybind interface:
|
||||
function(get_pybind11_json)
|
||||
|
||||
message( STATUS #CHECK_START
|
||||
"Fetching pybind11_json..." )
|
||||
#list( APPEND CMAKE_MESSAGE_INDENT " " ) # Indent outputs
|
||||
|
||||
# We want to clone the pybind repo and build it here, during configuration, so we can use it.
|
||||
# But ExternalProject_add is limited in that it only does its magic during build.
|
||||
# This is possible in CMake 3.12+ with FetchContent and FetchContent_MakeAvailable in 3.14+ (meaning Ubuntu 20)
|
||||
# but we need to adhere to CMake 3.10 (Ubuntu 18).
|
||||
# So instead, we invoke a new CMake project just to download pybind:
|
||||
configure_file( CMake/pybind11-json-download.cmake.in
|
||||
${CMAKE_BINARY_DIR}/external-projects/pybind11-json-download/CMakeLists.txt )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" -G "${CMAKE_GENERATOR}" .
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/pybind11-json-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE configure_ret )
|
||||
execute_process( COMMAND "${CMAKE_COMMAND}" --build .
|
||||
WORKING_DIRECTORY "${CMAKE_BINARY_DIR}/external-projects/pybind11-json-download"
|
||||
OUTPUT_QUIET
|
||||
RESULT_VARIABLE build_ret )
|
||||
|
||||
if( configure_ret OR build_ret )
|
||||
message( FATAL_ERROR "Failed to download pybind11_json" )
|
||||
endif()
|
||||
|
||||
# pybind11_add_module will add the directory automatically (see below)
|
||||
|
||||
message( STATUS #CHECK_PASS
|
||||
"Fetching pybind11_json - Done" )
|
||||
#list( POP_BACK CMAKE_MESSAGE_INDENT ) # Unindent outputs (requires cmake 3.15)
|
||||
|
||||
endfunction()
|
||||
|
||||
# Trigger the build
|
||||
get_pybind11()
|
||||
get_pybind11_json()
|
||||
|
||||
# This function overrides "pybind11_add_module" function, arguments is same as "pybind11_add_module" arguments
|
||||
# pybind11_add_module(<name> SHARED [file, file2, ...] )
|
||||
# Must be declared after pybind11 configuration above
|
||||
function( pybind11_add_module project_name library_type ...)
|
||||
|
||||
# message( STATUS "adding python module --> ${project_name}"
|
||||
|
||||
# "_pybind11_add_module" is calling the origin pybind11 function
|
||||
_pybind11_add_module( ${ARGV})
|
||||
|
||||
# Force Pybind11 not to share pyrealsense2 resources with other pybind modules.
|
||||
# With this definition we force the ABI version to be unique and not risk crashes on different modules.
|
||||
# (workaround for RS5-10582; see also https://github.com/pybind/pybind11/issues/2898)
|
||||
# NOTE: this workaround seems to be needed for debug compilations only
|
||||
target_compile_definitions( ${project_name} PRIVATE -DPYBIND11_COMPILER_TYPE=\"_${project_name}_abi\" )
|
||||
|
||||
target_include_directories( ${project_name} PRIVATE "${CMAKE_BINARY_DIR}/third-party/pybind11-json/include" )
|
||||
|
||||
endfunction()
|
||||
107
librealsense-r-256/CMake/global_config.cmake
Normal file
107
librealsense-r-256/CMake/global_config.cmake
Normal file
@@ -0,0 +1,107 @@
|
||||
# Save the command line compile commands in the build output
|
||||
set(CMAKE_EXPORT_COMPILE_COMMANDS 1)
|
||||
|
||||
# View the makefile commands during build
|
||||
#set(CMAKE_VERBOSE_MAKEFILE on)
|
||||
|
||||
include(GNUInstallDirs)
|
||||
# include librealsense helper macros
|
||||
include(CMake/lrs_macros.cmake)
|
||||
include(CMake/version_config.cmake)
|
||||
|
||||
if(ENABLE_CCACHE)
|
||||
find_program(CCACHE_FOUND ccache)
|
||||
if(CCACHE_FOUND)
|
||||
set_property(GLOBAL PROPERTY RULE_LAUNCH_COMPILE ccache)
|
||||
set_property(GLOBAL PROPERTY RULE_LAUNCH_LINK ccache)
|
||||
endif(CCACHE_FOUND)
|
||||
endif()
|
||||
|
||||
macro(global_set_flags)
|
||||
set(LRS_LIB_NAME ${LRS_TARGET})
|
||||
|
||||
add_definitions(-DELPP_THREAD_SAFE)
|
||||
|
||||
if (BUILD_GLSL_EXTENSIONS)
|
||||
set(LRS_GL_TARGET realsense2-gl)
|
||||
set(LRS_GL_LIB_NAME ${LRS_GL_TARGET})
|
||||
endif()
|
||||
|
||||
if (BUILD_EASYLOGGINGPP)
|
||||
add_definitions(-DBUILD_EASYLOGGINGPP)
|
||||
endif()
|
||||
|
||||
if (ENABLE_EASYLOGGINGPP_ASYNC)
|
||||
add_definitions(-DEASYLOGGINGPP_ASYNC)
|
||||
endif()
|
||||
|
||||
if(TRACE_API)
|
||||
add_definitions(-DTRACE_API)
|
||||
endif()
|
||||
|
||||
if(HWM_OVER_XU)
|
||||
add_definitions(-DHWM_OVER_XU)
|
||||
endif()
|
||||
|
||||
if(COM_MULTITHREADED)
|
||||
add_definitions(-DCOM_MULTITHREADED)
|
||||
endif()
|
||||
|
||||
if (ENFORCE_METADATA)
|
||||
add_definitions(-DENFORCE_METADATA)
|
||||
endif()
|
||||
|
||||
if (BUILD_WITH_CUDA)
|
||||
add_definitions(-DRS2_USE_CUDA)
|
||||
endif()
|
||||
|
||||
if (BUILD_SHARED_LIBS)
|
||||
add_definitions(-DBUILD_SHARED_LIBS)
|
||||
endif()
|
||||
|
||||
if (BUILD_WITH_CUDA)
|
||||
include(CMake/cuda_config.cmake)
|
||||
endif()
|
||||
|
||||
if(BUILD_PYTHON_BINDINGS)
|
||||
include(libusb_config)
|
||||
include(CMake/external_pybind11.cmake)
|
||||
endif()
|
||||
|
||||
if(CHECK_FOR_UPDATES)
|
||||
if (ANDROID_NDK_TOOLCHAIN_INCLUDED)
|
||||
message(STATUS "Android build do not support CHECK_FOR_UPDATES flag, turning it off..")
|
||||
set(CHECK_FOR_UPDATES false)
|
||||
elseif (NOT BUILD_GRAPHICAL_EXAMPLES)
|
||||
message(STATUS "CHECK_FOR_UPDATES depends on BUILD_GRAPHICAL_EXAMPLES flag, turning it off..")
|
||||
set(CHECK_FOR_UPDATES false)
|
||||
else()
|
||||
include(CMake/external_libcurl.cmake)
|
||||
add_definitions(-DCHECK_FOR_UPDATES)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
add_definitions(-D${BACKEND} -DUNICODE)
|
||||
endmacro()
|
||||
|
||||
macro(global_target_config)
|
||||
target_link_libraries(${LRS_TARGET} PRIVATE realsense-file ${CMAKE_THREAD_LIBS_INIT})
|
||||
|
||||
set_target_properties (${LRS_TARGET} PROPERTIES FOLDER Library)
|
||||
|
||||
target_include_directories(${LRS_TARGET}
|
||||
PRIVATE
|
||||
src
|
||||
${ROSBAG_HEADER_DIRS}
|
||||
${BOOST_INCLUDE_PATH}
|
||||
${LZ4_INCLUDE_PATH}
|
||||
${LIBUSB_LOCAL_INCLUDE_PATH}
|
||||
PUBLIC
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||
$<INSTALL_INTERFACE:include>
|
||||
PRIVATE ${USB_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
|
||||
endmacro()
|
||||
|
||||
7
librealsense-r-256/CMake/include_os.cmake
Normal file
7
librealsense-r-256/CMake/include_os.cmake
Normal file
@@ -0,0 +1,7 @@
|
||||
if(ANDROID_NDK_TOOLCHAIN_INCLUDED)
|
||||
include(CMake/android_config.cmake)
|
||||
elseif (WIN32)
|
||||
include(CMake/windows_config.cmake)
|
||||
else()
|
||||
include(CMake/unix_config.cmake)
|
||||
endif()
|
||||
51
librealsense-r-256/CMake/install_config.cmake
Normal file
51
librealsense-r-256/CMake/install_config.cmake
Normal file
@@ -0,0 +1,51 @@
|
||||
# Set CMAKE_INSTALL_* if not defined
|
||||
set(CMAKECONFIG_INSTALL_DIR "${CMAKE_INSTALL_LIBDIR}/cmake/${LRS_TARGET}")
|
||||
|
||||
add_custom_target(uninstall "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake")
|
||||
|
||||
include(CMakePackageConfigHelpers)
|
||||
|
||||
write_basic_package_version_file("${CMAKE_CURRENT_BINARY_DIR}/realsense2ConfigVersion.cmake"
|
||||
VERSION ${REALSENSE_VERSION_STRING} COMPATIBILITY AnyNewerVersion)
|
||||
|
||||
configure_package_config_file(CMake/realsense2Config.cmake.in realsense2Config.cmake
|
||||
INSTALL_DESTINATION ${CMAKECONFIG_INSTALL_DIR}
|
||||
INSTALL_PREFIX ${CMAKE_INSTALL_PREFIX}/bin
|
||||
PATH_VARS CMAKE_INSTALL_INCLUDEDIR
|
||||
)
|
||||
|
||||
configure_file("${CMAKE_CURRENT_SOURCE_DIR}/cmake_uninstall.cmake" "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" IMMEDIATE @ONLY)
|
||||
configure_file(config/librealsense.pc.in config/realsense2.pc @ONLY)
|
||||
|
||||
install(TARGETS ${LRS_TARGET}
|
||||
EXPORT realsense2Targets
|
||||
RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}
|
||||
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
|
||||
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}
|
||||
PUBLIC_HEADER DESTINATION "${CMAKE_INSTALL_PREFIX}/include/librealsense2"
|
||||
)
|
||||
|
||||
install(DIRECTORY ${PROJECT_SOURCE_DIR}/include/librealsense2
|
||||
DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}
|
||||
)
|
||||
|
||||
install(EXPORT realsense2Targets
|
||||
FILE realsense2Targets.cmake
|
||||
NAMESPACE ${LRS_TARGET}::
|
||||
DESTINATION ${CMAKECONFIG_INSTALL_DIR}
|
||||
)
|
||||
|
||||
install(FILES "${CMAKE_CURRENT_BINARY_DIR}/realsense2Config.cmake"
|
||||
DESTINATION ${CMAKECONFIG_INSTALL_DIR}
|
||||
)
|
||||
|
||||
install(FILES "${CMAKE_CURRENT_BINARY_DIR}/realsense2ConfigVersion.cmake"
|
||||
DESTINATION ${CMAKECONFIG_INSTALL_DIR}
|
||||
)
|
||||
|
||||
# Set library pkgconfig file for facilitating 3rd party integration
|
||||
install(FILES "${CMAKE_CURRENT_BINARY_DIR}/config/realsense2.pc"
|
||||
DESTINATION "${CMAKE_INSTALL_LIBDIR}/pkgconfig"
|
||||
)
|
||||
|
||||
install(CODE "execute_process(COMMAND ldconfig)")
|
||||
25
librealsense-r-256/CMake/json-download.cmake.in
Normal file
25
librealsense-r-256/CMake/json-download.cmake.in
Normal file
@@ -0,0 +1,25 @@
|
||||
cmake_minimum_required(VERSION 3.6)
|
||||
project(nlohmann-json-download NONE)
|
||||
|
||||
include(ExternalProject)
|
||||
ExternalProject_Add(
|
||||
nlohmann_json
|
||||
PREFIX .
|
||||
|
||||
# We do not use 'GIT_REPOSITORY' as it doesn't support a shallow clone of a specific commit,
|
||||
# this make the clone step very long, so we clone by ourselves (See https://gitlab.kitware.com/cmake/cmake/-/issues/17770).
|
||||
# Adding detachedHead=false to avoid warnings like: "You are in 'detached HEAD' state..."
|
||||
# 'remove_directory' is working but cound as deprecated from cmake version 3.17,
|
||||
# Once we have a minimal version support of cmake 3.17, we can switch the command to rm -rF
|
||||
DOWNLOAD_COMMAND "${CMAKE_COMMAND}" -E remove_directory "${CMAKE_BINARY_DIR}/third-party/json"
|
||||
COMMAND git clone -c advice.detachedHead=false --branch v3.11.3 https://github.com/nlohmann/json.git --depth 1 json
|
||||
DOWNLOAD_DIR "${CMAKE_BINARY_DIR}/third-party/"
|
||||
|
||||
# Override default steps with no action, we just want the clone step.
|
||||
UPDATE_COMMAND ""
|
||||
CONFIGURE_COMMAND ""
|
||||
BUILD_COMMAND ""
|
||||
INSTALL_COMMAND ""
|
||||
)
|
||||
|
||||
|
||||
14
librealsense-r-256/CMake/libusb_config.cmake
Normal file
14
librealsense-r-256/CMake/libusb_config.cmake
Normal file
@@ -0,0 +1,14 @@
|
||||
if (NOT TARGET usb)
|
||||
find_library(LIBUSB_LIB usb-1.0)
|
||||
find_path(LIBUSB_INC libusb.h HINTS PATH_SUFFIXES libusb-1.0)
|
||||
include(FindPackageHandleStandardArgs)
|
||||
find_package_handle_standard_args(usb "libusb not found; using internal version" LIBUSB_LIB LIBUSB_INC)
|
||||
if (USB_FOUND AND NOT USE_EXTERNAL_USB)
|
||||
add_library(usb INTERFACE)
|
||||
target_include_directories(usb INTERFACE ${LIBUSB_INC})
|
||||
target_link_libraries(usb INTERFACE ${LIBUSB_LIB})
|
||||
else()
|
||||
include(CMake/external_libusb.cmake)
|
||||
endif()
|
||||
install(TARGETS usb EXPORT realsense2Targets)
|
||||
endif()
|
||||
29
librealsense-r-256/CMake/lrs_macros.cmake
Normal file
29
librealsense-r-256/CMake/lrs_macros.cmake
Normal file
@@ -0,0 +1,29 @@
|
||||
macro(info msg)
|
||||
message(STATUS "Info: ${msg}")
|
||||
endmacro()
|
||||
|
||||
macro(infoValue variableName)
|
||||
info("${variableName}=\${${variableName}}")
|
||||
endmacro()
|
||||
|
||||
macro(config_cxx_flags)
|
||||
# We require that the current project (e.g., librealsense) use C++14. However, projects using
|
||||
# the library don't need to be C++14 -- they can use C++11. Hence this is PRIVATE and not PUBLIC:
|
||||
target_compile_features( ${PROJECT_NAME} PRIVATE cxx_std_14 )
|
||||
target_compile_features( ${PROJECT_NAME} INTERFACE cxx_std_11 )
|
||||
#set( CMAKE_CUDA_STANDARD ${LRS_CXX_STANDARD} )
|
||||
endmacro()
|
||||
|
||||
macro(config_crt)
|
||||
if(BUILD_WITH_STATIC_CRT)
|
||||
foreach(flag_var
|
||||
CMAKE_CXX_FLAGS CMAKE_CXX_FLAGS_DEBUG CMAKE_CXX_FLAGS_RELEASE
|
||||
CMAKE_CXX_FLAGS_MINSIZEREL CMAKE_CXX_FLAGS_RELWITHDEBINFO
|
||||
CMAKE_C_FLAGS CMAKE_C_FLAGS_DEBUG CMAKE_C_FLAGS_RELEASE
|
||||
CMAKE_C_FLAGS_MINSIZEREL CMAKE_C_FLAGS_RELWITHDEBINFO)
|
||||
if(${flag_var} MATCHES "/MD")
|
||||
string(REGEX REPLACE "/MD" "/MT" ${flag_var} "${${flag_var}}")
|
||||
endif(${flag_var} MATCHES "/MD")
|
||||
endforeach(flag_var)
|
||||
endif(BUILD_WITH_STATIC_CRT)
|
||||
endmacro()
|
||||
59
librealsense-r-256/CMake/lrs_options.cmake
Normal file
59
librealsense-r-256/CMake/lrs_options.cmake
Normal file
@@ -0,0 +1,59 @@
|
||||
## This file is also being used to generate our build flags document at https://intelrealsense.github.io/librealsense/build-flags-docs/build-flags.html
|
||||
## Formatting notes for this file:
|
||||
## Options are listed as: <name> | <description> [comment] | <value>
|
||||
## regular comments should be ABOVE their relevent option
|
||||
## use double # for comments that should not show in the options doc
|
||||
|
||||
option(ENABLE_CCACHE "Build with ccache." ON)
|
||||
option(BUILD_WITH_CUDA "Enable CUDA" OFF)
|
||||
option(BUILD_GLSL_EXTENSIONS "Build GLSL extensions API" ON)
|
||||
option(BUILD_WITH_OPENMP "Use OpenMP" OFF)
|
||||
option(BUILD_EASYLOGGINGPP "Build EasyLogging++ as a part of the build" ON)
|
||||
option(BUILD_WITH_STATIC_CRT "Build with static link CRT" ON)
|
||||
option(HWM_OVER_XU "Send HWM commands over UVC XU control" ON)
|
||||
option(COM_MULTITHREADED "Set OFF to initialize COM library with COINIT_APARTMENTTHREADED (Windows only)" ON)
|
||||
option(BUILD_SHARED_LIBS "Build shared library" ON)
|
||||
option(BUILD_UNIT_TESTS "Build LibCI unit tests. If enabled, additional test data may be downloaded" OFF)
|
||||
option(BUILD_EXAMPLES "Build examples (not including graphical examples -- see BUILD_GRAPHICAL_EXAMPLES)" ON)
|
||||
option(BUILD_GRAPHICAL_EXAMPLES "Build graphical examples (Viewer & DQT) -- Implies BUILD_GLSL_EXTENSIONS" ON)
|
||||
option(BUILD_CV_EXAMPLES "Build OpenCV examples" OFF)
|
||||
option(BUILD_DLIB_EXAMPLES "Build DLIB examples - requires DLIB_DIR" OFF)
|
||||
option(BUILD_PCL_EXAMPLES "Build PCL examples" OFF)
|
||||
option(BUILD_TOOLS "Build tools (fw-updater, etc.) that are not examples" ON)
|
||||
option(ENFORCE_METADATA "Require WinSDK with Metadata support during compilation. Windows OS Only" OFF)
|
||||
option(BUILD_PYTHON_BINDINGS "Build Python bindings" OFF)
|
||||
option(BUILD_LEGACY_PYBACKEND "Build deprecated Python backend bindings" OFF)
|
||||
option(BUILD_PYTHON_DOCS "Build Documentation for Python bindings" OFF)
|
||||
option(BUILD_CSHARP_BINDINGS "Build C# bindings" OFF)
|
||||
option(BUILD_MATLAB_BINDINGS "Build Matlab bindings" OFF)
|
||||
option(BUILD_UNITY_BINDINGS "Copy the unity project to the build folder with the required dependencies" OFF)
|
||||
option(BUILD_OPENVINO_EXAMPLES "Build Intel OpenVINO Toolkit examples - requires INTEL_OPENVINO_DIR" OFF)
|
||||
option(BUILD_OPEN3D_EXAMPLES "Build Open3D examples" OFF)
|
||||
option(BUILD_OPENNI2_BINDINGS "Build OpenNI bindings" OFF)
|
||||
option(IMPORT_DEPTH_CAM_FW "Download the latest firmware for the depth cameras" ON)
|
||||
option(BUILD_CV_KINFU_EXAMPLE "Build OpenCV KinectFusion example" OFF)
|
||||
option(FORCE_RSUSB_BACKEND "Use RS USB backend, mandatory for Win7/MacOS/Android, optional for Linux" OFF)
|
||||
option(FORCE_LIBUVC "Explicitly turn-on libuvc backend - deprecated, use FORCE_RSUSB_BACKEND instead" OFF)
|
||||
option(FORCE_WINUSB_UVC "Explicitly turn-on winusb_uvc (for win7) backend - deprecated, use FORCE_RSUSB_BACKEND instead" OFF)
|
||||
option(ANDROID_USB_HOST_UVC "Build UVC backend for Android - deprecated, use FORCE_RSUSB_BACKEND instead" OFF)
|
||||
# This feature requires OpenSSL installation on Linux/OSX, OSX normally does not come with OpenSSL integrated(Thats why default is OFF on OSX)
|
||||
if (NOT APPLE)
|
||||
option(CHECK_FOR_UPDATES "Checks for versions updates" ON)
|
||||
else()
|
||||
option(CHECK_FOR_UPDATES "Checks for versions updates" OFF)
|
||||
endif()
|
||||
option(BUILD_WITH_CPU_EXTENSIONS "Enable compiler optimizations using CPU extensions (such as AVX)" ON)
|
||||
set(UNIT_TESTS_ARGS "" CACHE STRING "Command-line arguments to pass to unit-tests-config.py, e.g. '-t <tag> -r <regex>'")
|
||||
#Performance improvement with Ubuntu 18/20
|
||||
if(UNIX AND (NOT ANDROID_NDK_TOOLCHAIN_INCLUDED))
|
||||
option(ENABLE_EASYLOGGINGPP_ASYNC "Switch Logger to Asynchronous Mode (set OFF for Synchronous Mode)" ON)
|
||||
else()
|
||||
option(ENABLE_EASYLOGGINGPP_ASYNC "Switch Logger to Asynchronous Mode (set OFF for Synchronous Mode)" OFF)
|
||||
endif()
|
||||
option(BUILD_PC_STITCHING "Build pointcloud-stitching example" OFF)
|
||||
option(BUILD_WITH_DDS "Access camera devices through DDS topics (requires CMake 3.16.3)" OFF)
|
||||
option(BUILD_RS2_ALL "Build realsense2-all static bundle containing all realsense libraries (with BUILD_SHARED_LIBS=OFF)" ON)
|
||||
option(ENABLE_SECURITY_FLAGS "Enable additional compiler security flags to enhance the build's security" OFF)
|
||||
option(USE_EXTERNAL_LZ4 "Use externally build LZ4 library instead of building and using the in this repo provided version" OFF)
|
||||
option(BUILD_ASAN "Enable AddressSanitizer" OFF)
|
||||
mark_as_advanced(BUILD_ASAN)
|
||||
7
librealsense-r-256/CMake/opengl_config.cmake
Normal file
7
librealsense-r-256/CMake/opengl_config.cmake
Normal file
@@ -0,0 +1,7 @@
|
||||
# The NEW policy flag set OpenGL_GL_PREFERENCE variable to GLVND.
|
||||
if (POLICY CMP0072)
|
||||
cmake_policy(SET CMP0072 NEW)
|
||||
endif()
|
||||
|
||||
find_package(OpenGL REQUIRED)
|
||||
list( APPEND DEPENDENCIES glfw ${OPENGL_LIBRARIES} )
|
||||
19
librealsense-r-256/CMake/pybind11-download.cmake.in
Normal file
19
librealsense-r-256/CMake/pybind11-download.cmake.in
Normal file
@@ -0,0 +1,19 @@
|
||||
cmake_minimum_required(VERSION 3.6)
|
||||
project(pybind11-download NONE)
|
||||
|
||||
include(ExternalProject)
|
||||
ExternalProject_Add(
|
||||
pybind11
|
||||
PREFIX .
|
||||
GIT_REPOSITORY "https://github.com/pybind/pybind11.git"
|
||||
GIT_TAG v2.13.6
|
||||
GIT_CONFIG advice.detachedHead=false # otherwise we'll get "You are in 'detached HEAD' state..."
|
||||
SOURCE_DIR "${CMAKE_BINARY_DIR}/third-party/pybind11"
|
||||
GIT_SHALLOW ON # No history needed (requires cmake 3.6)
|
||||
# Override default steps with no action, we just want the clone step.
|
||||
CONFIGURE_COMMAND ""
|
||||
BUILD_COMMAND ""
|
||||
INSTALL_COMMAND ""
|
||||
)
|
||||
|
||||
|
||||
19
librealsense-r-256/CMake/pybind11-json-download.cmake.in
Normal file
19
librealsense-r-256/CMake/pybind11-json-download.cmake.in
Normal file
@@ -0,0 +1,19 @@
|
||||
cmake_minimum_required(VERSION 3.6)
|
||||
project(pybind11-json-download NONE)
|
||||
|
||||
include(ExternalProject)
|
||||
ExternalProject_Add(
|
||||
pybind11_json
|
||||
PREFIX .
|
||||
GIT_REPOSITORY "https://github.com/pybind/pybind11_json.git"
|
||||
GIT_TAG 0.2.15
|
||||
GIT_CONFIG advice.detachedHead=false # otherwise we'll get "You are in 'detached HEAD' state..."
|
||||
SOURCE_DIR "${CMAKE_BINARY_DIR}/third-party/pybind11-json"
|
||||
GIT_SHALLOW ON # No history needed (requires cmake 3.6)
|
||||
# Override default steps with no action, we just want the clone step.
|
||||
CONFIGURE_COMMAND ""
|
||||
BUILD_COMMAND ""
|
||||
INSTALL_COMMAND ""
|
||||
)
|
||||
|
||||
|
||||
10
librealsense-r-256/CMake/pyrealsense2Config.cmake.in
Normal file
10
librealsense-r-256/CMake/pyrealsense2Config.cmake.in
Normal file
@@ -0,0 +1,10 @@
|
||||
@PACKAGE_INIT@
|
||||
|
||||
set(pyrealsense2_VERSION_MAJOR "@REALSENSE_VERSION_MAJOR@")
|
||||
set(pyrealsense2_VERSION_MINOR "@REALSENSE_VERSION_MINOR@")
|
||||
set(pyrealsense2_VERSION_PATCH "@REALSENSE_VERSION_PATCH@")
|
||||
|
||||
set(pyrealsense2_VERSION ${realsense2_VERSION_MAJOR}.${realsense2_VERSION_MINOR}.${realsense2_VERSION_PATCH})
|
||||
|
||||
include("${CMAKE_CURRENT_LIST_DIR}/pyrealsense2Targets.cmake")
|
||||
set(realsense2_LIBRARY pyrealsense2::pyrealsense2)
|
||||
12
librealsense-r-256/CMake/realsense2-glConfig.cmake.in
Normal file
12
librealsense-r-256/CMake/realsense2-glConfig.cmake.in
Normal file
@@ -0,0 +1,12 @@
|
||||
@PACKAGE_INIT@
|
||||
|
||||
set(realsense2-gl_VERSION_MAJOR "@REALSENSE_VERSION_MAJOR@")
|
||||
set(realsense2-gl_VERSION_MINOR "@REALSENSE_VERSION_MINOR@")
|
||||
set(realsense2-gl_VERSION_PATCH "@REALSENSE_VERSION_PATCH@")
|
||||
|
||||
set(realsense2-gl_VERSION ${realsense2-gl_VERSION_MAJOR}.${realsense2-gl_VERSION_MINOR}.${realsense2-gl_VERSION_PATCH})
|
||||
|
||||
set_and_check(realsense2-gl_INCLUDE_DIR "@PACKAGE_CMAKE_INSTALL_INCLUDEDIR@")
|
||||
|
||||
include("${CMAKE_CURRENT_LIST_DIR}/realsense2-glTargets.cmake")
|
||||
set(realsense2-gl_LIBRARY realsense2-gl::realsense2-gl)
|
||||
12
librealsense-r-256/CMake/realsense2-netConfig.cmake.in
Normal file
12
librealsense-r-256/CMake/realsense2-netConfig.cmake.in
Normal file
@@ -0,0 +1,12 @@
|
||||
@PACKAGE_INIT@
|
||||
|
||||
set(realsense2-net_VERSION_MAJOR "@REALSENSE_VERSION_MAJOR@")
|
||||
set(realsense2-net_VERSION_MINOR "@REALSENSE_VERSION_MINOR@")
|
||||
set(realsense2-net_VERSION_PATCH "@REALSENSE_VERSION_PATCH@")
|
||||
|
||||
set(realsense2-net_VERSION ${realsense2-net_VERSION_MAJOR}.${realsense2-net_VERSION_MINOR}.${realsense2-gl_VERSION_PATCH})
|
||||
|
||||
set_and_check(realsense2-net_INCLUDE_DIR "@PACKAGE_CMAKE_INSTALL_INCLUDEDIR@")
|
||||
|
||||
include("${CMAKE_CURRENT_LIST_DIR}/realsense2-netTargets.cmake")
|
||||
set(realsense2-net_LIBRARY realsense2-net::realsense2-net)
|
||||
12
librealsense-r-256/CMake/realsense2Config.cmake.in
Normal file
12
librealsense-r-256/CMake/realsense2Config.cmake.in
Normal file
@@ -0,0 +1,12 @@
|
||||
@PACKAGE_INIT@
|
||||
|
||||
set(realsense2_VERSION_MAJOR "@REALSENSE_VERSION_MAJOR@")
|
||||
set(realsense2_VERSION_MINOR "@REALSENSE_VERSION_MINOR@")
|
||||
set(realsense2_VERSION_PATCH "@REALSENSE_VERSION_PATCH@")
|
||||
|
||||
set(realsense2_VERSION ${realsense2_VERSION_MAJOR}.${realsense2_VERSION_MINOR}.${realsense2_VERSION_PATCH})
|
||||
|
||||
set_and_check(realsense2_INCLUDE_DIR "@PACKAGE_CMAKE_INSTALL_INCLUDEDIR@")
|
||||
|
||||
include("${CMAKE_CURRENT_LIST_DIR}/realsense2Targets.cmake")
|
||||
set(realsense2_LIBRARY realsense2::realsense2)
|
||||
@@ -0,0 +1,44 @@
|
||||
macro(push_security_flags) # remove security flags
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${SECURITY_COMPILER_FLAGS}")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${SECURITY_COMPILER_FLAGS}")
|
||||
endmacro()
|
||||
|
||||
macro(pop_security_flags) # append security flags
|
||||
string(REPLACE "${SECURITY_COMPILER_FLAGS}" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}")
|
||||
string(REPLACE "${SECURITY_COMPILER_FLAGS}" "" CMAKE_C_FLAGS "${CMAKE_C_FLAGS}")
|
||||
endmacro()
|
||||
|
||||
macro(set_security_flags_for_executable) # replace flag fPIC (Position-Independent Code) with fPIE (Position-Independent Executable)
|
||||
string(REPLACE "-fPIC" "-fPIE" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}")
|
||||
string(REPLACE "-fPIC" "-fPIE" CMAKE_C_FLAGS "${CMAKE_C_FLAGS}")
|
||||
endmacro()
|
||||
|
||||
macro(unset_security_flags_for_executable) # replace flag fPIE (Position-Independent Executable) with fPIC (Position-Independent Code)
|
||||
string(REPLACE "-fPIE" "-fPIC" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}")
|
||||
string(REPLACE "-fPIE" "-fPIC" CMAKE_C_FLAGS "${CMAKE_C_FLAGS}")
|
||||
endmacro()
|
||||
|
||||
macro(disable_third_party_warnings target)
|
||||
if (TARGET ${target}) # Ensure the target exists
|
||||
get_target_property(target_type ${target} TYPE)
|
||||
|
||||
if (target_type STREQUAL "INTERFACE_LIBRARY")
|
||||
if (WIN32)
|
||||
target_compile_options(${target} INTERFACE /W0)
|
||||
else()
|
||||
target_compile_options(${target} INTERFACE -w)
|
||||
endif()
|
||||
else()
|
||||
if (WIN32)
|
||||
target_compile_options(${target} PRIVATE /W0)
|
||||
else()
|
||||
target_compile_options(${target} PRIVATE -w)
|
||||
endif()
|
||||
endif()
|
||||
else()
|
||||
message(WARNING "Target '${target}' does not exist.")
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
|
||||
|
||||
105
librealsense-r-256/CMake/unix_config.cmake
Normal file
105
librealsense-r-256/CMake/unix_config.cmake
Normal file
@@ -0,0 +1,105 @@
|
||||
message(STATUS "Setting Unix configurations")
|
||||
|
||||
macro(os_set_flags)
|
||||
|
||||
# Put all the collaterals together, so we can find when trying to run examples/tests
|
||||
# Note: this puts the outputs under <binary>/<build-type>
|
||||
if( "${CMAKE_BUILD_TYPE}" STREQUAL "" )
|
||||
# This can happen according to the docs -- and in GHA...
|
||||
message( STATUS "No output directory set; using ${CMAKE_BINARY_DIR}/Release/" )
|
||||
set( CMAKE_BUILD_TYPE "Release" )
|
||||
endif()
|
||||
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_BUILD_TYPE})
|
||||
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_BUILD_TYPE})
|
||||
set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/${CMAKE_BUILD_TYPE})
|
||||
|
||||
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -pedantic -D_DEFAULT_SOURCE")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pedantic -Wno-missing-field-initializers")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-switch -Wno-multichar -Wsequence-point -Wformat -Wformat-security")
|
||||
|
||||
execute_process(COMMAND ${CMAKE_C_COMPILER} -dumpmachine OUTPUT_VARIABLE MACHINE)
|
||||
if(${MACHINE} MATCHES "arm64-*" OR ${MACHINE} MATCHES "aarch64-*")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -mstrict-align -ftree-vectorize")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mstrict-align -ftree-vectorize")
|
||||
elseif(${MACHINE} MATCHES "arm-*")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -mfpu=neon -mfloat-abi=hard -ftree-vectorize -latomic")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon -mfloat-abi=hard -ftree-vectorize -latomic")
|
||||
elseif(${MACHINE} MATCHES "powerpc64(le)?-linux-gnu")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -ftree-vectorize")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ftree-vectorize")
|
||||
elseif(${MACHINE} MATCHES "riscv64-*")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -mstrict-align -ftree-vectorize")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mstrict-align -ftree-vectorize")
|
||||
else()
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -mssse3")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mssse3")
|
||||
set(LRS_TRY_USE_AVX true)
|
||||
endif(${MACHINE} MATCHES "arm64-*" OR ${MACHINE} MATCHES "aarch64-*")
|
||||
|
||||
if(BUILD_WITH_OPENMP)
|
||||
find_package(OpenMP REQUIRED)
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
|
||||
else()
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -pthread")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread")
|
||||
endif()
|
||||
|
||||
set(SECURITY_COMPILER_FLAGS "")
|
||||
if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU" AND ENABLE_SECURITY_FLAGS)
|
||||
# Due to security reasons we need to add the following flags for additional security:
|
||||
# Debug & Release:
|
||||
# -Wformat: Checks for format string vulnerabilities.
|
||||
# -Wformat-security: Ensures format strings are not vulnerable to attacks.
|
||||
# -fPIC: Generates position-independent code during the compilation phase.
|
||||
# -fPIE: Generates position-independent executables during the compilation phase.
|
||||
# -D_FORTIFY_SOURCE=2: Adds extra checks for buffer overflows.
|
||||
# -fstack-protector: Adds stack protection to detect buffer overflows.
|
||||
|
||||
# Release only
|
||||
# -Werror: Treats all warnings as errors.
|
||||
# -Werror=format-security: Treats format security warnings as errors.
|
||||
# -z noexecstack: Marks the stack as non-executable to prevent certain types of attacks.
|
||||
# -Wl,-z,relro,-z,now: Enables read-only relocations and immediate binding for security.
|
||||
# -fstack-protector-strong: Provides stronger stack protection than -fstack-protector.
|
||||
|
||||
# Linker flags
|
||||
# -pie: Produces position-independent executables during the linking phase.
|
||||
|
||||
# see https://readthedocs.intel.com/SecureCodingStandards/2023.Q2.0/compiler/c-cpp/ for more details
|
||||
|
||||
set(SECURITY_COMPILER_FLAGS "-Wformat -Wformat-security -fPIC -fstack-protector -Wno-error=stringop-overflow")
|
||||
|
||||
string(FIND "${CMAKE_CXX_FLAGS}" "-D_FORTIFY_SOURCE" _index)
|
||||
if (${_index} EQUAL -1) # Define D_FORTIFY_SOURCE if undefined
|
||||
set(SECURITY_COMPILER_FLAGS "${SECURITY_COMPILER_FLAGS} -D_FORTIFY_SOURCE=2")
|
||||
endif()
|
||||
|
||||
if(CMAKE_BUILD_TYPE STREQUAL "Debug")
|
||||
message(STATUS "Configuring for Debug build")
|
||||
else() # Release, RelWithDebInfo, or multi configuration generator is being used (aka not specifing build type, or building with VS)
|
||||
message(STATUS "Configuring for Release build")
|
||||
set(SECURITY_COMPILER_FLAGS "${SECURITY_COMPILER_FLAGS} -Werror -z noexecstack -Wl,-z,relro,-z,now -fstack-protector-strong")
|
||||
endif()
|
||||
|
||||
push_security_flags()
|
||||
|
||||
set(CMAKE_LINKER_FLAGS "${CMAKE_LINKER_FLAGS} -pie")
|
||||
|
||||
endif()
|
||||
|
||||
if(APPLE)
|
||||
set(FORCE_RSUSB_BACKEND ON)
|
||||
endif()
|
||||
|
||||
if(FORCE_RSUSB_BACKEND)
|
||||
set(BACKEND RS2_USE_LIBUVC_BACKEND)
|
||||
else()
|
||||
set(BACKEND RS2_USE_V4L2_BACKEND)
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
macro(os_target_config)
|
||||
endmacro()
|
||||
28
librealsense-r-256/CMake/version_config.cmake
Normal file
28
librealsense-r-256/CMake/version_config.cmake
Normal file
@@ -0,0 +1,28 @@
|
||||
##################################################################
|
||||
# Parse librealsense version and assign it to CMake variables #
|
||||
# This function parses librealsense public API header file, rs.h #
|
||||
# and retrieves version numbers embedded in the source code. #
|
||||
# Since the function relies on hard-coded variables, it is prone #
|
||||
# for failures should these constants be modified in future #
|
||||
##################################################################
|
||||
function(assign_version_property VER_COMPONENT)
|
||||
file(STRINGS "./include/librealsense2/rs.h" REALSENSE_VERSION_${VER_COMPONENT} REGEX "#define RS2_API_${VER_COMPONENT}_VERSION")
|
||||
separate_arguments(REALSENSE_VERSION_${VER_COMPONENT})
|
||||
list(GET REALSENSE_VERSION_${VER_COMPONENT} -1 tmp)
|
||||
if (tmp LESS 0)
|
||||
message( FATAL_ERROR "Could not obtain valid Librealsense version ${VER_COMPONENT} component - actual value is ${tmp}" )
|
||||
endif()
|
||||
set(REALSENSE_VERSION_${VER_COMPONENT} ${tmp} PARENT_SCOPE)
|
||||
endfunction()
|
||||
|
||||
set(REALSENSE_VERSION_MAJOR -1)
|
||||
set(REALSENSE_VERSION_MINOR -1)
|
||||
set(REALSENSE_VERSION_PATCH -1)
|
||||
assign_version_property(MAJOR)
|
||||
assign_version_property(MINOR)
|
||||
assign_version_property(PATCH)
|
||||
set(REALSENSE_VERSION_STRING ${REALSENSE_VERSION_MAJOR}.${REALSENSE_VERSION_MINOR}.${REALSENSE_VERSION_PATCH})
|
||||
infoValue(REALSENSE_VERSION_STRING)
|
||||
if (BUILD_GLSL_EXTENSIONS)
|
||||
set(REALSENSE-GL_VERSION_STRING ${REALSENSE_VERSION_MAJOR}.${REALSENSE_VERSION_MINOR}.${REALSENSE_VERSION_PATCH})
|
||||
endif()
|
||||
137
librealsense-r-256/CMake/windows_config.cmake
Normal file
137
librealsense-r-256/CMake/windows_config.cmake
Normal file
@@ -0,0 +1,137 @@
|
||||
message(STATUS "Setting Windows configurations")
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
config_crt()
|
||||
|
||||
macro(os_set_flags)
|
||||
set_property(GLOBAL PROPERTY USE_FOLDERS ON)
|
||||
|
||||
# Put all the collaterals together, so we can find when trying to run examples/tests
|
||||
# Note: this puts the outputs under <binary>/<build-type>
|
||||
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR})
|
||||
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR})
|
||||
set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR})
|
||||
|
||||
if(BUILD_WITH_OPENMP)
|
||||
find_package(OpenMP REQUIRED)
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
|
||||
endif()
|
||||
|
||||
## Check for Windows Version ##
|
||||
if(${CMAKE_SYSTEM_VERSION} EQUAL 6.1) # Windows 7
|
||||
set(FORCE_RSUSB_BACKEND ON)
|
||||
endif()
|
||||
|
||||
if(FORCE_RSUSB_BACKEND)
|
||||
set(BACKEND RS2_USE_WINUSB_UVC_BACKEND)
|
||||
else()
|
||||
set(BACKEND RS2_USE_WMF_BACKEND)
|
||||
endif()
|
||||
|
||||
if(MSVC)
|
||||
# Set CMAKE_DEBUG_POSTFIX to "d" to add a trailing "d" to library
|
||||
# built in debug mode. In this Windows user can compile, build and install the
|
||||
# library in both Release and Debug configuration avoiding naming clashes in the
|
||||
# installation directories.
|
||||
set(CMAKE_DEBUG_POSTFIX "d")
|
||||
|
||||
# build with multiple cores
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /MP")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /MP")
|
||||
|
||||
set(SECURITY_COMPILER_FLAGS "")
|
||||
if (ENABLE_SECURITY_FLAGS)
|
||||
# Due to security reasons we need to add the following flags for additional security:
|
||||
# Debug & Release:
|
||||
# /Gy: Enables function-level linking to reduce executable size.
|
||||
# /DYNAMICBASE: Enables Address Space Layout Randomization (ASLR) to improve security.
|
||||
# /GS: Enables buffer security checks to prevent buffer overflows.
|
||||
|
||||
# Release only:
|
||||
# /WX: Treats all warnings as errors.
|
||||
# /sdl: Enables additional security checks.
|
||||
|
||||
# Release only linker flags:
|
||||
# /LTCG (/GL): Enables Link Time Code Generation to improve performance.
|
||||
# /NXCOMPAT: Enables Data Execution Prevention (DEP) to prevent code execution in data areas.
|
||||
|
||||
# see https://readthedocs.intel.com/SecureCodingStandards/2023.Q2.0/compiler/c-cpp/ for more details
|
||||
|
||||
set(SECURITY_COMPILER_FLAGS "/Gy /DYNAMICBASE /GS /wd4101")
|
||||
|
||||
if(CMAKE_BUILD_TYPE STREQUAL "Debug")
|
||||
message(STATUS "Configuring for Debug build")
|
||||
else() # Release, RelWithDebInfo, or multi configuration generator is being used (aka not specifing build type, or building with VS)
|
||||
message(STATUS "Configuring for Release build")
|
||||
set(SECURITY_COMPILER_FLAGS "${SECURITY_COMPILER_FLAGS} /WX /sdl")
|
||||
endif()
|
||||
|
||||
push_security_flags()
|
||||
|
||||
if(NOT CMAKE_BUILD_TYPE STREQUAL "Debug")
|
||||
set(CMAKE_LINKER_FLAGS "${CMAKE_LINKER_FLAGS} /INCREMENTAL:NO /LTCG /NXCOMPAT") # ignoring '/INCREMENTAL' due to '/LTCG' specification
|
||||
endif()
|
||||
|
||||
endif()
|
||||
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /bigobj /wd4819")
|
||||
set(LRS_TRY_USE_AVX true)
|
||||
add_definitions(-D_UNICODE)
|
||||
endif()
|
||||
set(DOTNET_VERSION_LIBRARY "3.5" CACHE STRING ".Net Version, defaulting to '3.5', the Unity wrapper currently supports only .NET 3.5")
|
||||
set(DOTNET_VERSION_EXAMPLES "4.0" CACHE STRING ".Net Version, defaulting to '4.0'")
|
||||
|
||||
# Windows.h will define the min/max macros which will
|
||||
# collide with std's min/max templates, which we want to use.
|
||||
add_definitions(-DNOMINMAX)
|
||||
endmacro()
|
||||
|
||||
macro(os_target_config)
|
||||
add_definitions(-D__SSSE3__ -D_CRT_SECURE_NO_WARNINGS)
|
||||
|
||||
if(FORCE_RSUSB_BACKEND)
|
||||
if (NOT CMAKE_CURRENT_SOURCE_DIR STREQUAL CMAKE_CURRENT_BINARY_DIR)
|
||||
message("Preparing Windows 7 drivers" )
|
||||
make_directory(${CMAKE_CURRENT_BINARY_DIR}/drivers/)
|
||||
file(GLOB DRIVERS RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}/src/win7/drivers/" "${CMAKE_CURRENT_SOURCE_DIR}/src/win7/drivers/*")
|
||||
foreach(item IN LISTS DRIVERS)
|
||||
message("Copying ${CMAKE_CURRENT_SOURCE_DIR}/src/win7/drivers/${item} to ${CMAKE_CURRENT_BINARY_DIR}/drivers/" )
|
||||
configure_file("${CMAKE_CURRENT_SOURCE_DIR}/src/win7/drivers/${item}" "${CMAKE_CURRENT_BINARY_DIR}/drivers/${item}" COPYONLY)
|
||||
endforeach()
|
||||
endif()
|
||||
|
||||
add_custom_target(realsense-driver ALL DEPENDS ${DRIVERS})
|
||||
add_dependencies(${LRS_TARGET} realsense-driver)
|
||||
set_target_properties (realsense-driver PROPERTIES FOLDER Library)
|
||||
endif()
|
||||
|
||||
get_target_property(LRS_FILES ${LRS_TARGET} SOURCES)
|
||||
list(APPEND LRS_HEADERS ${LRS_FILES})
|
||||
list(APPEND LRS_SOURCES ${LRS_FILES})
|
||||
list(FILTER LRS_HEADERS INCLUDE REGEX ".\\.h$|.\\.hpp$|.\\.def$|.\\.cuh$")
|
||||
list(FILTER LRS_SOURCES INCLUDE REGEX ".\\.c$|.\\.cpp$|.\\.cc$|.\\.cu$")
|
||||
|
||||
foreach(_file IN ITEMS ${LRS_HEADERS})
|
||||
string(REPLACE ${CMAKE_CURRENT_SOURCE_DIR}/ "" _relative_file ${_file})
|
||||
get_filename_component(_file_path "${_relative_file}" PATH)
|
||||
string(REPLACE "/" "\\" _file_path_msvc "${_file_path}")
|
||||
source_group("Header Files\\${_file_path_msvc}" FILES "${_relative_file}")
|
||||
endforeach()
|
||||
|
||||
foreach(_file IN ITEMS ${LRS_SOURCES})
|
||||
string(REPLACE ${CMAKE_CURRENT_SOURCE_DIR}/ "" _relative_file ${_file})
|
||||
get_filename_component(_file_path "${_relative_file}" PATH)
|
||||
string(REPLACE "/" "\\" _file_path_msvc "${_file_path}")
|
||||
source_group("Source Files\\${_file_path_msvc}" FILES "${_relative_file}")
|
||||
endforeach()
|
||||
endmacro()
|
||||
|
||||
#modify variable with prefix. Mimics list(TRANSFORM ... PREPEND introduced with cmake 3.12
|
||||
FUNCTION(PREPEND var prefix)
|
||||
SET(listVar "")
|
||||
FOREACH(f ${ARGN})
|
||||
LIST(APPEND listVar "${prefix}/${f}")
|
||||
ENDFOREACH(f)
|
||||
SET(${var} "${listVar}" PARENT_SCOPE)
|
||||
ENDFUNCTION(PREPEND)
|
||||
129
librealsense-r-256/CMakeLists.txt
Normal file
129
librealsense-r-256/CMakeLists.txt
Normal file
@@ -0,0 +1,129 @@
|
||||
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
|
||||
set( LRS_TARGET realsense2 )
|
||||
project( ${LRS_TARGET} LANGUAGES CXX C )
|
||||
|
||||
# Allow librealsense2 and all of the nested project to include the main repo folder
|
||||
set(REPO_ROOT ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
include_directories(${REPO_ROOT})
|
||||
|
||||
include(CMake/lrs_options.cmake)
|
||||
include(CMake/connectivity_check.cmake)
|
||||
#Deprecation message, should be removed in future releases
|
||||
if(${FORCE_LIBUVC} OR ${FORCE_WINUSB_UVC} OR ${ANDROID_USB_HOST_UVC})
|
||||
MESSAGE(DEPRECATION "FORCE_LIBUVC, FORCE_WINUSB_UVC and ANDROID_USB_HOST_UVC are deprecated, use FORCE_RSUSB_BACKEND instead")
|
||||
set(FORCE_RSUSB_BACKEND ON)
|
||||
endif()
|
||||
|
||||
# Checking Internet connection, as DEPTH CAM needs to download the FW from amazon cloud
|
||||
if(IMPORT_DEPTH_CAM_FW AND NOT INTERNET_CONNECTION)
|
||||
message(WARNING "No internet connection, disabling IMPORT_DEPTH_CAM_FW")
|
||||
set(IMPORT_DEPTH_CAM_FW OFF)
|
||||
endif()
|
||||
|
||||
if (BUILD_PC_STITCHING AND NOT BUILD_GLSL_EXTENSIONS)
|
||||
MESSAGE(STATUS "BUILD_PC_STITCHING explicitely depends on BUILD_GLSL_EXTENSIONS, set it ON")
|
||||
SET(BUILD_GLSL_EXTENSIONS ON)
|
||||
endif()
|
||||
|
||||
list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/CMake)
|
||||
|
||||
# include security flags helper functions
|
||||
include(CMake/security_flags_helper_functions.cmake)
|
||||
|
||||
# include librealsense general configuration
|
||||
include(CMake/global_config.cmake)
|
||||
|
||||
# include os specific macros
|
||||
# macro definition located at "CMake/global_config.cmake"
|
||||
include(CMake/include_os.cmake)
|
||||
|
||||
# set os specific configuration flags
|
||||
# macro definition located at "CMake/<OS>_config.cmake"
|
||||
os_set_flags()
|
||||
|
||||
# set global configuration flags
|
||||
# macro definition located at "CMake/global_config.cmake"
|
||||
global_set_flags()
|
||||
|
||||
# If no type is given explicitly the type is STATIC or SHARED based on whether the current value of the variable [BUILD_SHARED_LIBS](https://cmake.org/cmake/help/v3.10/variable/BUILD_SHARED_LIBS.html#variable:BUILD_SHARED_LIBS) is ON
|
||||
add_library(${LRS_TARGET})
|
||||
# Apply ASan flags if enabled
|
||||
if(BUILD_ASAN)
|
||||
message(STATUS "AddressSanitizer is enabled")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fsanitize=address -g")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fsanitize=address -g")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fsanitize=address")
|
||||
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -fsanitize=address")
|
||||
target_compile_options(${LRS_TARGET} PRIVATE -fsanitize=address -g)
|
||||
endif()
|
||||
|
||||
config_cxx_flags()
|
||||
|
||||
# set library version
|
||||
set_target_properties(${LRS_TARGET} PROPERTIES VERSION ${REALSENSE_VERSION_STRING} SOVERSION "${REALSENSE_VERSION_MAJOR}.${REALSENSE_VERSION_MINOR}")
|
||||
|
||||
include(include/CMakeLists.txt)
|
||||
include(src/CMakeLists.txt)
|
||||
include(third-party/CMakeLists.txt)
|
||||
|
||||
target_link_libraries( ${LRS_TARGET} PUBLIC rsutils )
|
||||
|
||||
if(BUILD_WITH_DDS)
|
||||
if (CMAKE_SYSTEM MATCHES "Windows" OR CMAKE_SYSTEM MATCHES "Linux")
|
||||
|
||||
message(STATUS "Building with FastDDS")
|
||||
include(CMake/external_foonathan_memory.cmake)
|
||||
include(CMake/external_fastdds.cmake)
|
||||
|
||||
target_link_libraries( ${LRS_TARGET} PRIVATE realdds )
|
||||
|
||||
else()
|
||||
MESSAGE(STATUS "Turning off `BUILD_WITH_DDS` as it's only supported on Windows & Linux and not on ${CMAKE_SYSTEM}")
|
||||
set(BUILD_WITH_DDS OFF)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
# configure the project according to OS specific requirments
|
||||
# macro definition located at "CMake/<OS>_config.cmake"
|
||||
os_target_config()
|
||||
|
||||
# global project configuration
|
||||
# macro definition located at "CMake/global_config.cmake"
|
||||
global_target_config()
|
||||
|
||||
include(CMake/install_config.cmake)
|
||||
|
||||
add_subdirectory(wrappers)
|
||||
if ( ( BUILD_EXAMPLES OR BUILD_PC_STITCHING ) AND BUILD_GLSL_EXTENSIONS )
|
||||
find_package(glfw3 3.3 QUIET)
|
||||
if(NOT TARGET glfw)
|
||||
message(STATUS "GLFW 3.3 not found; using internal version")
|
||||
set(GLFW_INSTALL ON CACHE BOOL "" FORCE)
|
||||
add_subdirectory(third-party/glfw)
|
||||
endif()
|
||||
add_subdirectory(src/gl)
|
||||
endif()
|
||||
|
||||
if(BUILD_EXAMPLES)
|
||||
add_subdirectory(examples)
|
||||
add_subdirectory(tools)
|
||||
elseif(BUILD_TOOLS)
|
||||
add_subdirectory(tools)
|
||||
endif()
|
||||
|
||||
if(BUILD_UNIT_TESTS)
|
||||
include( CMake/external_catch2.cmake )
|
||||
add_subdirectory(unit-tests)
|
||||
endif()
|
||||
|
||||
if(IMPORT_DEPTH_CAM_FW)
|
||||
add_subdirectory(common/fw)
|
||||
endif()
|
||||
|
||||
include(CMake/embedd_udev_rules.cmake)
|
||||
|
||||
if( BUILD_RS2_ALL )
|
||||
include( src/realsense2-all.cmake )
|
||||
endif()
|
||||
72
librealsense-r-256/CONTRIBUTING.md
Normal file
72
librealsense-r-256/CONTRIBUTING.md
Normal file
@@ -0,0 +1,72 @@
|
||||
# How to Contribute
|
||||
|
||||
This project welcomes third-party code via GitHub pull requests.
|
||||
|
||||
You are welcome to propose and discuss enhancements using project [issues](https://github.com/IntelRealSense/librealsense/issues).
|
||||
|
||||
> **Branching Policy**:
|
||||
> The `master` branch is considered stable, at all times.
|
||||
> The `development` branch is the one where all contributions must be merged before being promoted to master.
|
||||
> If you plan to propose a patch, please commit into the `development` branch, or its own feature branch.
|
||||
|
||||
We recommend enabling [Github Actions](https://docs.github.com/en/actions) on your fork of `librealsense` to make sure the changes compile on all platforms and pass unit-tests.
|
||||
|
||||
In addition, please run `pr_check.sh` and `api_check.sh` under `scripts` directory. These scripts verify compliance with project's standards:
|
||||
|
||||
1. Every example / source file must refer to [LICENSE](https://github.com/IntelRealSense/librealsense/blob/master/LICENSE)
|
||||
2. Every example / source file must include correct copyright notice
|
||||
3. For indentation we are using spaces and not tabs
|
||||
4. Line-endings must be Unix and not DOS style
|
||||
5. Every API header file must be able to compile as the first included header (no implicit dependencies)
|
||||
|
||||
Most common issues can be automatically resolved by running `./pr_check.sh --fix`
|
||||
|
||||
Please familirize yourself with the [Apache License 2.0](https://github.com/IntelRealSense/librealsense/blob/master/LICENSE) before contributing.
|
||||
|
||||
## Step-by-Step
|
||||
|
||||
1. Make sure you have `git` and `cmake` installed on your system. On Windows we recommend using [Git Extensions](https://github.com/gitextensions/gitextensions/releases) for git bash.
|
||||
2. Run `git clone https://github.com/IntelRealSense/librealsense.git` and `cd librealsense`
|
||||
3. To align with latest status of the development branch, run:
|
||||
```
|
||||
git fetch origin
|
||||
git checkout development
|
||||
git reset --hard origin/development
|
||||
```
|
||||
4. `git checkout -b name_of_your_contribution` to create a dedicated branch
|
||||
5. Make your changes to the local repository
|
||||
6. Make sure your local git user is updated, or run `git config --global user.email "email@example.com"` and `git config --global user.user "user"` to set it up. This is the user & email that will appear in GitHub history.
|
||||
7. `git add -p` to select the changes you wish to add
|
||||
8. `git commit -m "Description of the change"`
|
||||
9. Make sure you have a GitHub user and [fork librealsense](https://github.com/IntelRealSense/librealsense#fork-destination-box)
|
||||
10. `git remote add fork https://github.com/username/librealsense.git` with your GitHub `username`
|
||||
11. `git fetch fork`
|
||||
12. `git push fork` to push `name_of_your_contribution` branch to your fork
|
||||
13. Go to your fork on GitHub at `https://github.com/username/librealsense`
|
||||
14. Click the `New pull request` button
|
||||
15. For `base` combo-box select `development`, since you want to submit a PR to that branch
|
||||
16. For `compare` combo-box select `name_of_your_contribution` with your commit
|
||||
17. Review your changes and click `Create pull request`
|
||||
18. Wait for all automated checks to pass
|
||||
19. The PR will be approved / rejected after review from the team and the community
|
||||
|
||||
To continue to new change, goto step 3.
|
||||
To return to your PR (in order to make more changes):
|
||||
1. `git stash`
|
||||
2. `git checkout name_of_your_contribution`
|
||||
3. Repeat items 5-8 from the previous list
|
||||
4. `git push fork`
|
||||
The pull request will be automatically updated
|
||||
|
||||
## Comment about the Wrappers
|
||||
|
||||
> It is very time consuming (and often impossible) for a single developer to test contributed functionality using all of the supported [wrappers](https://github.com/IntelRealSense/librealsense/tree/master/wrappers). There is no expectation of adding new functionality to all of the wrappers. One noteable exception is maintaining parity of public enumerations. Without strict maintanance it is easy for these lists to go out of sync and this can have serious runtime consequences.
|
||||
|
||||
For example, when adding new value to [`rs2_option`](https://github.com/IntelRealSense/librealsense/blob/master/include/librealsense2/h/rs_option.h) enum, please also add it to:
|
||||
1. The list of Matlab options under [`wrappers/matlab/option.m`](https://github.com/IntelRealSense/librealsense/blob/master/wrappers/matlab/option.m#L3-L46)
|
||||
2. The list of options for [Unreal Engine](https://github.com/IntelRealSense/librealsense/blob/v2.32.1/wrappers/unrealengine4/Plugins/RealSense/Source/RealSense/Public/RealSenseTypes.h#L56-L118) integration
|
||||
3. The list of options in the C# wrapper - [`wrappers/csharp/Intel.RealSense/Types/Enums/Option.cs`](https://github.com/IntelRealSense/librealsense/blob/v2.32.1/wrappers/csharp/Intel.RealSense/Types/Enums/Option.cs)
|
||||
4. The list of Java options used for Android integration - [`wrappers/android/librealsense/src/main/java/com/intel/realsense/librealsense/Option.java`](https://github.com/IntelRealSense/librealsense/blob/v2.32.1/wrappers/android/librealsense/src/main/java/com/intel/realsense/librealsense/Option.java#L4-L64)
|
||||
5. The list of options in the [python](https://github.com/IntelRealSense/librealsense/blob/v2.32.1/wrappers/python/pybackend.cpp#L102-L165) wrapper
|
||||
|
||||
Once all are updated [Github Actions](https://docs.github.com/en/actions) will give clear indication that each of the wrappers is still passing compilation.
|
||||
7
librealsense-r-256/Intel Copyright
Normal file
7
librealsense-r-256/Intel Copyright
Normal file
@@ -0,0 +1,7 @@
|
||||
Copyright (2017-2024), Intel Corporation.
|
||||
This "Software" is furnished under license and may only be used or copied in accordance with the terms of that license.
|
||||
No license, express or implied, by estoppel or otherwise, to any intellectual property rights is granted by this document.
|
||||
The Software is subject to change without notice, and should not be construed as a commitment by Intel Corporation to market, license, sell or support any product or technology.
|
||||
Unless otherwise provided for in the license under which this Software is provided, the Software is provided AS IS, with no warranties of any kind, express or implied.
|
||||
Except as expressly permitted by the Software license, neither Intel Corporation nor its suppliers assumes any responsibility or liability for any errors or inaccuracies that may appear herein.
|
||||
Except as expressly permitted by the Software license, no part of the Software may be reproduced, stored in a retrieval system, transmitted in any form, or distributed by any means without the express written consent of Intel Corporation.
|
||||
202
librealsense-r-256/LICENSE
Normal file
202
librealsense-r-256/LICENSE
Normal file
@@ -0,0 +1,202 @@
|
||||
|
||||
Apache License
|
||||
Version 2.0, January 2004
|
||||
http://www.apache.org/licenses/
|
||||
|
||||
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
|
||||
|
||||
1. Definitions.
|
||||
|
||||
"License" shall mean the terms and conditions for use, reproduction,
|
||||
and distribution as defined by Sections 1 through 9 of this document.
|
||||
|
||||
"Licensor" shall mean the copyright owner or entity authorized by
|
||||
the copyright owner that is granting the License.
|
||||
|
||||
"Legal Entity" shall mean the union of the acting entity and all
|
||||
other entities that control, are controlled by, or are under common
|
||||
control with that entity. For the purposes of this definition,
|
||||
"control" means (i) the power, direct or indirect, to cause the
|
||||
direction or management of such entity, whether by contract or
|
||||
otherwise, or (ii) ownership of fifty percent (50%) or more of the
|
||||
outstanding shares, or (iii) beneficial ownership of such entity.
|
||||
|
||||
"You" (or "Your") shall mean an individual or Legal Entity
|
||||
exercising permissions granted by this License.
|
||||
|
||||
"Source" form shall mean the preferred form for making modifications,
|
||||
including but not limited to software source code, documentation
|
||||
source, and configuration files.
|
||||
|
||||
"Object" form shall mean any form resulting from mechanical
|
||||
transformation or translation of a Source form, including but
|
||||
not limited to compiled object code, generated documentation,
|
||||
and conversions to other media types.
|
||||
|
||||
"Work" shall mean the work of authorship, whether in Source or
|
||||
Object form, made available under the License, as indicated by a
|
||||
copyright notice that is included in or attached to the work
|
||||
(an example is provided in the Appendix below).
|
||||
|
||||
"Derivative Works" shall mean any work, whether in Source or Object
|
||||
form, that is based on (or derived from) the Work and for which the
|
||||
editorial revisions, annotations, elaborations, or other modifications
|
||||
represent, as a whole, an original work of authorship. For the purposes
|
||||
of this License, Derivative Works shall not include works that remain
|
||||
separable from, or merely link (or bind by name) to the interfaces of,
|
||||
the Work and Derivative Works thereof.
|
||||
|
||||
"Contribution" shall mean any work of authorship, including
|
||||
the original version of the Work and any modifications or additions
|
||||
to that Work or Derivative Works thereof, that is intentionally
|
||||
submitted to Licensor for inclusion in the Work by the copyright owner
|
||||
or by an individual or Legal Entity authorized to submit on behalf of
|
||||
the copyright owner. For the purposes of this definition, "submitted"
|
||||
means any form of electronic, verbal, or written communication sent
|
||||
to the Licensor or its representatives, including but not limited to
|
||||
communication on electronic mailing lists, source code control systems,
|
||||
and issue tracking systems that are managed by, or on behalf of, the
|
||||
Licensor for the purpose of discussing and improving the Work, but
|
||||
excluding communication that is conspicuously marked or otherwise
|
||||
designated in writing by the copyright owner as "Not a Contribution."
|
||||
|
||||
"Contributor" shall mean Licensor and any individual or Legal Entity
|
||||
on behalf of whom a Contribution has been received by Licensor and
|
||||
subsequently incorporated within the Work.
|
||||
|
||||
2. Grant of Copyright License. Subject to the terms and conditions of
|
||||
this License, each Contributor hereby grants to You a perpetual,
|
||||
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||
copyright license to reproduce, prepare Derivative Works of,
|
||||
publicly display, publicly perform, sublicense, and distribute the
|
||||
Work and such Derivative Works in Source or Object form.
|
||||
|
||||
3. Grant of Patent License. Subject to the terms and conditions of
|
||||
this License, each Contributor hereby grants to You a perpetual,
|
||||
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||
(except as stated in this section) patent license to make, have made,
|
||||
use, offer to sell, sell, import, and otherwise transfer the Work,
|
||||
where such license applies only to those patent claims licensable
|
||||
by such Contributor that are necessarily infringed by their
|
||||
Contribution(s) alone or by combination of their Contribution(s)
|
||||
with the Work to which such Contribution(s) was submitted. If You
|
||||
institute patent litigation against any entity (including a
|
||||
cross-claim or counterclaim in a lawsuit) alleging that the Work
|
||||
or a Contribution incorporated within the Work constitutes direct
|
||||
or contributory patent infringement, then any patent licenses
|
||||
granted to You under this License for that Work shall terminate
|
||||
as of the date such litigation is filed.
|
||||
|
||||
4. Redistribution. You may reproduce and distribute copies of the
|
||||
Work or Derivative Works thereof in any medium, with or without
|
||||
modifications, and in Source or Object form, provided that You
|
||||
meet the following conditions:
|
||||
|
||||
(a) You must give any other recipients of the Work or
|
||||
Derivative Works a copy of this License; and
|
||||
|
||||
(b) You must cause any modified files to carry prominent notices
|
||||
stating that You changed the files; and
|
||||
|
||||
(c) You must retain, in the Source form of any Derivative Works
|
||||
that You distribute, all copyright, patent, trademark, and
|
||||
attribution notices from the Source form of the Work,
|
||||
excluding those notices that do not pertain to any part of
|
||||
the Derivative Works; and
|
||||
|
||||
(d) If the Work includes a "NOTICE" text file as part of its
|
||||
distribution, then any Derivative Works that You distribute must
|
||||
include a readable copy of the attribution notices contained
|
||||
within such NOTICE file, excluding those notices that do not
|
||||
pertain to any part of the Derivative Works, in at least one
|
||||
of the following places: within a NOTICE text file distributed
|
||||
as part of the Derivative Works; within the Source form or
|
||||
documentation, if provided along with the Derivative Works; or,
|
||||
within a display generated by the Derivative Works, if and
|
||||
wherever such third-party notices normally appear. The contents
|
||||
of the NOTICE file are for informational purposes only and
|
||||
do not modify the License. You may add Your own attribution
|
||||
notices within Derivative Works that You distribute, alongside
|
||||
or as an addendum to the NOTICE text from the Work, provided
|
||||
that such additional attribution notices cannot be construed
|
||||
as modifying the License.
|
||||
|
||||
You may add Your own copyright statement to Your modifications and
|
||||
may provide additional or different license terms and conditions
|
||||
for use, reproduction, or distribution of Your modifications, or
|
||||
for any such Derivative Works as a whole, provided Your use,
|
||||
reproduction, and distribution of the Work otherwise complies with
|
||||
the conditions stated in this License.
|
||||
|
||||
5. Submission of Contributions. Unless You explicitly state otherwise,
|
||||
any Contribution intentionally submitted for inclusion in the Work
|
||||
by You to the Licensor shall be under the terms and conditions of
|
||||
this License, without any additional terms or conditions.
|
||||
Notwithstanding the above, nothing herein shall supersede or modify
|
||||
the terms of any separate license agreement you may have executed
|
||||
with Licensor regarding such Contributions.
|
||||
|
||||
6. Trademarks. This License does not grant permission to use the trade
|
||||
names, trademarks, service marks, or product names of the Licensor,
|
||||
except as required for reasonable and customary use in describing the
|
||||
origin of the Work and reproducing the content of the NOTICE file.
|
||||
|
||||
7. Disclaimer of Warranty. Unless required by applicable law or
|
||||
agreed to in writing, Licensor provides the Work (and each
|
||||
Contributor provides its Contributions) on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
|
||||
implied, including, without limitation, any warranties or conditions
|
||||
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
|
||||
PARTICULAR PURPOSE. You are solely responsible for determining the
|
||||
appropriateness of using or redistributing the Work and assume any
|
||||
risks associated with Your exercise of permissions under this License.
|
||||
|
||||
8. Limitation of Liability. In no event and under no legal theory,
|
||||
whether in tort (including negligence), contract, or otherwise,
|
||||
unless required by applicable law (such as deliberate and grossly
|
||||
negligent acts) or agreed to in writing, shall any Contributor be
|
||||
liable to You for damages, including any direct, indirect, special,
|
||||
incidental, or consequential damages of any character arising as a
|
||||
result of this License or out of the use or inability to use the
|
||||
Work (including but not limited to damages for loss of goodwill,
|
||||
work stoppage, computer failure or malfunction, or any and all
|
||||
other commercial damages or losses), even if such Contributor
|
||||
has been advised of the possibility of such damages.
|
||||
|
||||
9. Accepting Warranty or Additional Liability. While redistributing
|
||||
the Work or Derivative Works thereof, You may choose to offer,
|
||||
and charge a fee for, acceptance of support, warranty, indemnity,
|
||||
or other liability obligations and/or rights consistent with this
|
||||
License. However, in accepting such obligations, You may act only
|
||||
on Your own behalf and on Your sole responsibility, not on behalf
|
||||
of any other Contributor, and only if You agree to indemnify,
|
||||
defend, and hold each Contributor harmless for any liability
|
||||
incurred by, or claims asserted against, such Contributor by reason
|
||||
of your accepting any such warranty or additional liability.
|
||||
|
||||
END OF TERMS AND CONDITIONS
|
||||
|
||||
APPENDIX: How to apply the Apache License to your work.
|
||||
|
||||
To apply the Apache License to your work, attach the following
|
||||
boilerplate notice, with the fields enclosed by brackets "[]"
|
||||
replaced with your own identifying information. (Don't include
|
||||
the brackets!) The text should be enclosed in the appropriate
|
||||
comment syntax for the file format. We also recommend that a
|
||||
file or class name and description of purpose be included on the
|
||||
same "printed page" as the copyright notice for easier
|
||||
identification within third-party archives.
|
||||
|
||||
Copyright 2017 Intel Corporation
|
||||
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this project except in compliance with the License.
|
||||
You may obtain a copy of the License at
|
||||
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
||||
1009
librealsense-r-256/NOTICE.md
Normal file
1009
librealsense-r-256/NOTICE.md
Normal file
File diff suppressed because it is too large
Load Diff
6
librealsense-r-256/Security.md
Normal file
6
librealsense-r-256/Security.md
Normal file
@@ -0,0 +1,6 @@
|
||||
# Security Policy
|
||||
Intel is committed to rapidly addressing security vulnerabilities affecting our customers and providing clear guidance on the solution, impact, severity and mitigation.
|
||||
|
||||
## Reporting a Vulnerability
|
||||
Please report any security vulnerabilities in this project [utilizing the guidelines here](https://www.intel.com/content/www/us/en/security-center/vulnerability-handling-guidelines.html).
|
||||
|
||||
34
librealsense-r-256/cmake_uninstall.cmake
Normal file
34
librealsense-r-256/cmake_uninstall.cmake
Normal file
@@ -0,0 +1,34 @@
|
||||
IF(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt")
|
||||
MESSAGE(WARNING "Cannot find install manifest: \"@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt\"")
|
||||
MESSAGE(STATUS "Uninstall targets will be skipped")
|
||||
ELSE(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt")
|
||||
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(NOT "${rm_retval}" STREQUAL 0)
|
||||
ELSEIF(NOT "${CMAKE_VERSION}" STRLESS "2.8.1")
|
||||
IF(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 \"$ENV{DESTDIR}${file}\"")
|
||||
ENDIF(NOT "${rm_retval}" STREQUAL 0)
|
||||
ENDIF(IS_SYMLINK "$ENV{DESTDIR}${file}")
|
||||
ELSE(EXISTS "$ENV{DESTDIR}${file}")
|
||||
MESSAGE(STATUS "File \"$ENV{DESTDIR}${file}\" does not exist.")
|
||||
ENDIF(EXISTS "$ENV{DESTDIR}${file}")
|
||||
ENDFOREACH(file)
|
||||
execute_process(COMMAND ldconfig)
|
||||
ENDIF(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt")
|
||||
77
librealsense-r-256/code-of-conduct.md
Normal file
77
librealsense-r-256/code-of-conduct.md
Normal file
@@ -0,0 +1,77 @@
|
||||
# librealsense Code of Conduct
|
||||
|
||||
## Our Pledge
|
||||
|
||||
In the interest of fostering an open and welcoming environment, we as
|
||||
contributors and maintainers pledge to making participation in our project and
|
||||
our community a harassment-free experience for everyone, regardless of age, body
|
||||
size, disability, ethnicity, sex characteristics, gender identity and expression,
|
||||
level of experience, education, socio-economic status, nationality, personal
|
||||
appearance, race, religion, or sexual identity and orientation.
|
||||
|
||||
## Our Standards
|
||||
|
||||
Examples of behavior that contributes to creating a positive environment
|
||||
include:
|
||||
|
||||
* Using welcoming and inclusive language
|
||||
* Being respectful of differing viewpoints and experiences
|
||||
* Gracefully accepting constructive criticism
|
||||
* Focusing on what is best for the community
|
||||
* Showing empathy towards other community members
|
||||
|
||||
Examples of unacceptable behavior by participants include:
|
||||
|
||||
* The use of sexualized language or imagery and unwelcome sexual attention or
|
||||
advances
|
||||
* Trolling, insulting/derogatory comments, and personal or political attacks
|
||||
* Public or private harassment
|
||||
* Publishing others' private information, such as a physical or electronic
|
||||
address, without explicit permission
|
||||
* Other conduct which could reasonably be considered inappropriate in a
|
||||
professional setting
|
||||
|
||||
## Our Responsibilities
|
||||
|
||||
Project maintainers are responsible for clarifying the standards of acceptable
|
||||
behavior and are expected to take appropriate and fair corrective action in
|
||||
response to any instances of unacceptable behavior.
|
||||
|
||||
Project maintainers have the right and responsibility to remove, edit, or
|
||||
reject comments, commits, code, wiki edits, issues, and other contributions
|
||||
that are not aligned to this Code of Conduct, or to ban temporarily or
|
||||
permanently any contributor for other behaviors that they deem inappropriate,
|
||||
threatening, offensive, or harmful.
|
||||
|
||||
## Scope
|
||||
|
||||
This Code of Conduct applies both within project spaces and in public spaces
|
||||
when an individual is representing the project or its community. Examples of
|
||||
representing a project or community include using an official project e-mail
|
||||
address, posting via an official social media account, or acting as an appointed
|
||||
representative at an online or offline event. Representation of a project may be
|
||||
further defined and clarified by project maintainers.
|
||||
|
||||
## Enforcement
|
||||
|
||||
Instances of abusive, harassing, or otherwise unacceptable behavior may be
|
||||
reported by contacting the project team at [sergey.dorodnicov@intel.com](mailto://sergey.dorodnicov@intel.com). All
|
||||
complaints will be reviewed and investigated and will result in a response that
|
||||
is deemed necessary and appropriate to the circumstances. The project team is
|
||||
obligated to maintain confidentiality with regard to the reporter of an incident.
|
||||
Further details of specific enforcement policies may be posted separately.
|
||||
|
||||
Project maintainers who do not follow or enforce the Code of Conduct in good
|
||||
faith may face temporary or permanent repercussions as determined by other
|
||||
members of the project's leadership.
|
||||
|
||||
## Attribution
|
||||
|
||||
This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4,
|
||||
available at https://www.contributor-covenant.org/version/1/4/code-of-conduct.html
|
||||
|
||||
[homepage]: https://www.contributor-covenant.org
|
||||
|
||||
For answers to common questions about this code of conduct, see
|
||||
https://www.contributor-covenant.org/faq
|
||||
|
||||
89
librealsense-r-256/common/CMakeLists.txt
Normal file
89
librealsense-r-256/common/CMakeLists.txt
Normal file
@@ -0,0 +1,89 @@
|
||||
# License: Apache 2.0. See LICENSE file in root directory.
|
||||
# Copyright(c) 2019 Intel Corporation. All Rights Reserved.
|
||||
|
||||
set(COMMON_SRC
|
||||
"${CMAKE_CURRENT_LIST_DIR}/animated.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/cli.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/float2.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/float3.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/float4.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/matrix4.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/plane.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/rect.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/rendering.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/model-views.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/model-views.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/notifications.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/notifications.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/calibration-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/calibration-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/viewer.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/viewer.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ux-window.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ux-window.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ux-alignment.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ux-alignment.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/opengl3.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/opengl3.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/rs-config.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/rs-config.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/os.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/os.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/fw-update-helper.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/fw-update-helper.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/metadata-helper.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/metadata-helper.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/output-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/output-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/skybox.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/skybox.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/measurement.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/measurement.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/on-chip-calib.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/on-chip-calib.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/d500-on-chip-calib.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/d500-on-chip-calib.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/updates-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/updates-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/option-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/option-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/device-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/device-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/subdevice-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/subdevice-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/processing-block-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/processing-block-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/stream-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/stream-model.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/post-processing-filters.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/post-processing-filters.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/dds-model.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/dds-model.cpp"
|
||||
)
|
||||
|
||||
set(SW_UPDATE_FILES
|
||||
"${CMAKE_CURRENT_LIST_DIR}/sw-update/http-downloader.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/sw-update/http-downloader.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/sw-update/dev-updates-profile.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/sw-update/dev-updates-profile.cpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/sw-update/versions-db-manager.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/sw-update/versions-db-manager.cpp"
|
||||
)
|
||||
|
||||
set(REFLECTIVITY_FILES
|
||||
"${CMAKE_CURRENT_LIST_DIR}/reflectivity/reflectivity.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/reflectivity/reflectivity.cpp"
|
||||
)
|
||||
|
||||
set(UTILITIES_FILES
|
||||
"${CMAKE_CURRENT_LIST_DIR}/utilities/imgui/wrap.h"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/utilities/imgui/wrap.cpp"
|
||||
)
|
||||
|
||||
set(COMMON_SRC
|
||||
${COMMON_SRC}
|
||||
${SW_UPDATE_FILES}
|
||||
${REFLECTIVITY_FILES}
|
||||
${UTILITIES_FILES}
|
||||
)
|
||||
|
||||
66
librealsense-r-256/common/android_helpers.h
Normal file
66
librealsense-r-256/common/android_helpers.h
Normal file
@@ -0,0 +1,66 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <stdlib.h>
|
||||
#include <sstream>
|
||||
#include <ios>
|
||||
#include <android/ndk-version.h>
|
||||
|
||||
#if __NDK_MAJOR__ <= 16
|
||||
namespace std
|
||||
{
|
||||
template <typename T>
|
||||
inline std::string to_string(T value)
|
||||
{
|
||||
std::ostringstream os;
|
||||
os << value;
|
||||
return os.str();
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
inline T stoT(const std::string& value)
|
||||
{
|
||||
char* endptr;
|
||||
auto x = strtoimax(value.c_str(), &endptr, 10);
|
||||
|
||||
return static_cast<T>(x);
|
||||
}
|
||||
|
||||
inline long long stoll(const std::string& value)
|
||||
{
|
||||
return stoT<long long>(value);
|
||||
}
|
||||
|
||||
inline unsigned long stoul(const std::string& value)
|
||||
{
|
||||
return stoT<unsigned long>(value);
|
||||
}
|
||||
|
||||
inline int stoi(const std::string& value)
|
||||
{
|
||||
return stoT<int>(value);
|
||||
}
|
||||
|
||||
inline float stof(const std::string& value)
|
||||
{
|
||||
char* pEnd;
|
||||
return strtof(value.c_str(), &pEnd);
|
||||
}
|
||||
|
||||
inline double stod(const std::string& value)
|
||||
{
|
||||
char* pEnd;
|
||||
return strtod(value.c_str(), &pEnd);
|
||||
}
|
||||
|
||||
inline std::ios_base& hexfloat(std::ios_base& str)
|
||||
{
|
||||
str.setf(std::ios_base::fixed | std::ios_base::scientific, std::ios_base::floatfield);
|
||||
return str;
|
||||
}
|
||||
}
|
||||
#endif // ANDROID_NDK_MAJOR
|
||||
|
||||
74
librealsense-r-256/common/animated.h
Normal file
74
librealsense-r-256/common/animated.h
Normal file
@@ -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 <chrono>
|
||||
|
||||
|
||||
namespace rs2 {
|
||||
|
||||
|
||||
|
||||
inline float clamp( float x, float min, float max )
|
||||
{
|
||||
return std::max( std::min( max, x ), min );
|
||||
}
|
||||
|
||||
inline float smoothstep( float x, float min, float max )
|
||||
{
|
||||
if( max == min )
|
||||
{
|
||||
x = clamp( ( x - min ), 0.0, 1.0 );
|
||||
}
|
||||
else
|
||||
{
|
||||
x = clamp( ( x - min ) / ( max - min ), 0.0, 1.0 );
|
||||
}
|
||||
|
||||
return x * x * ( 3 - 2 * x );
|
||||
}
|
||||
|
||||
|
||||
// Helper class that lets smoothly animate between its values
|
||||
template < class T > class animated
|
||||
{
|
||||
private:
|
||||
T _old, _new;
|
||||
std::chrono::system_clock::time_point _last_update;
|
||||
std::chrono::system_clock::duration _duration;
|
||||
|
||||
public:
|
||||
animated( T def, std::chrono::system_clock::duration duration = std::chrono::milliseconds( 200 ) )
|
||||
: _duration( duration )
|
||||
, _old( def )
|
||||
, _new( def )
|
||||
{
|
||||
static_assert( ( std::is_arithmetic< T >::value ), "animated class supports arithmetic built-in types only" );
|
||||
_last_update = std::chrono::system_clock::now();
|
||||
}
|
||||
animated & operator=( const T & other )
|
||||
{
|
||||
if( other != _new )
|
||||
{
|
||||
_old = get();
|
||||
_new = other;
|
||||
_last_update = std::chrono::system_clock::now();
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
T get() const
|
||||
{
|
||||
auto now = std::chrono::system_clock::now();
|
||||
auto ms = std::chrono::duration_cast< std::chrono::microseconds >( now - _last_update ).count();
|
||||
auto duration_ms = std::chrono::duration_cast< std::chrono::microseconds >( _duration ).count();
|
||||
auto t = (float)ms / duration_ms;
|
||||
t = clamp( smoothstep( t, 0.f, 1.f ), 0.f, 1.f );
|
||||
return static_cast< T >( _old * ( 1.f - t ) + _new * t );
|
||||
}
|
||||
operator T() const { return get(); }
|
||||
T value() const { return _new; }
|
||||
};
|
||||
|
||||
|
||||
} // namespace rs2
|
||||
452
librealsense-r-256/common/calibration-model.cpp
Normal file
452
librealsense-r-256/common/calibration-model.cpp
Normal file
@@ -0,0 +1,452 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2023 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include <rs-config.h>
|
||||
#include "calibration-model.h"
|
||||
#include "device-model.h"
|
||||
#include "os.h"
|
||||
#include "ux-window.h"
|
||||
#include <realsense_imgui.h>
|
||||
|
||||
#include "../src/ds/d400/d400-private.h"
|
||||
|
||||
|
||||
using namespace rs2;
|
||||
|
||||
calibration_model::calibration_model(rs2::device dev, std::shared_ptr<notifications_model> not_model)
|
||||
: dev(dev), _not_model(not_model)
|
||||
{
|
||||
_accept = config_file::instance().get_or_default(configurations::calibration::enable_writing, false);
|
||||
}
|
||||
|
||||
bool calibration_model::supports()
|
||||
{
|
||||
bool is_d400 = dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE) ?
|
||||
std::string(dev.get_info(RS2_CAMERA_INFO_PRODUCT_LINE)) == "D400" : false;
|
||||
|
||||
return dev.is<rs2::auto_calibrated_device>() && is_d400;
|
||||
}
|
||||
|
||||
void calibration_model::draw_float(std::string name, float& x, const float& orig, bool& changed)
|
||||
{
|
||||
if( std::abs( x - orig ) > 0.00001 )
|
||||
ImGui::PushStyleColor( ImGuiCol_FrameBg, regular_blue );
|
||||
else ImGui::PushStyleColor(ImGuiCol_FrameBg, black);
|
||||
if (ImGui::DragFloat(std::string( rsutils::string::from() << "##" << name).c_str(), &x, 0.001f))
|
||||
{
|
||||
changed = true;
|
||||
}
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
|
||||
void calibration_model::draw_float4x4(std::string name, float3x3& feild,
|
||||
const float3x3& original, bool& changed)
|
||||
{
|
||||
ImGui::SetCursorPosX(10);
|
||||
ImGui::Text("%s:", name.c_str()); ImGui::SameLine();
|
||||
ImGui::SetCursorPosX(200);
|
||||
|
||||
ImGui::PushItemWidth(120);
|
||||
ImGui::SetCursorPosX(200);
|
||||
draw_float(name + "_XX", feild.x.x, original.x.x, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float(name + "_XY", feild.x.y, original.x.y, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float(name + "_XZ", feild.x.z, original.x.z, changed);
|
||||
|
||||
ImGui::SetCursorPosX(200);
|
||||
draw_float(name + "_YX", feild.y.x, original.y.x, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float(name + "_YY", feild.y.y, original.y.y, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float(name + "_YZ", feild.y.z, original.y.z, changed);
|
||||
|
||||
ImGui::SetCursorPosX(200);
|
||||
draw_float(name + "_ZX", feild.z.x, original.z.x, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float(name + "_ZY", feild.z.y, original.z.y, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float(name + "_ZZ", feild.z.z, original.z.z, changed);
|
||||
|
||||
ImGui::PopItemWidth();
|
||||
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
}
|
||||
|
||||
void calibration_model::update(ux_window& window, std::string& error_message)
|
||||
{
|
||||
const auto window_name = "Calibration Window";
|
||||
|
||||
if (to_open)
|
||||
{
|
||||
try
|
||||
{
|
||||
_calibration = dev.as<rs2::auto_calibrated_device>().get_calibration_table();
|
||||
_original = _calibration;
|
||||
ImGui::OpenPopup(window_name);
|
||||
}
|
||||
catch(std::exception e)
|
||||
{
|
||||
error_message = e.what();
|
||||
}
|
||||
to_open = false;
|
||||
}
|
||||
|
||||
auto table = (librealsense::ds::d400_coefficients_table*)_calibration.data();
|
||||
auto orig_table = (librealsense::ds::d400_coefficients_table*)_original.data();
|
||||
bool changed = false;
|
||||
|
||||
const float w = 620;
|
||||
const float h = 500;
|
||||
const float x0 = std::max(window.width() - w, 0.f) / 2;
|
||||
const float y0 = std::max(window.height() - h, 0.f) / 2;
|
||||
ImGui::SetNextWindowPos({ x0, y0 });
|
||||
ImGui::SetNextWindowSize({ w, h });
|
||||
|
||||
auto flags = ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoTitleBar |
|
||||
ImGuiWindowFlags_NoCollapse | ImGuiWindowFlags_NoSavedSettings;
|
||||
|
||||
ImGui::PushStyleColor(ImGuiCol_PopupBg, sensor_bg);
|
||||
ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, white);
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, light_grey);
|
||||
ImGui::PushStyleVar(ImGuiStyleVar_WindowPadding, ImVec2(5, 5));
|
||||
ImGui::PushStyleVar(ImGuiStyleVar_WindowRounding, 1);
|
||||
|
||||
if (ImGui::BeginPopupModal(window_name, nullptr, flags))
|
||||
{
|
||||
if (error_message != "") ImGui::CloseCurrentPopup();
|
||||
|
||||
std::string title_message = "CAMERA CALIBRATION";
|
||||
auto title_size = ImGui::CalcTextSize(title_message.c_str());
|
||||
ImGui::SetCursorPosX(w / 2 - title_size.x / 2);
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
ImGui::PushFont(window.get_large_font());
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, white);
|
||||
ImGui::Text("%s", title_message.c_str());
|
||||
ImGui::PopStyleColor();
|
||||
ImGui::PopFont();
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
|
||||
ImGui::SetCursorPosX(w / 2 - 260 / 2);
|
||||
if (ImGui::Button(u8"\uF07C Load...", ImVec2(70, 30)))
|
||||
{
|
||||
try
|
||||
{
|
||||
if (auto fn = file_dialog_open(file_dialog_mode::open_file, "Calibration JSON\0*.json\0", nullptr, nullptr))
|
||||
{
|
||||
config_file cf(fn);
|
||||
table->baseline = cf.get("baseline");
|
||||
|
||||
auto load_float3x4 = [&](std::string name, librealsense::float3x3& m){
|
||||
m.x.x = cf.get(std::string( rsutils::string::from() << name << ".x.x").c_str());
|
||||
m.x.y = cf.get(std::string( rsutils::string::from() << name << ".x.y").c_str());
|
||||
m.x.z = cf.get(std::string( rsutils::string::from() << name << ".x.z").c_str());
|
||||
|
||||
m.y.x = cf.get(std::string( rsutils::string::from() << name << ".y.x").c_str());
|
||||
m.y.y = cf.get(std::string( rsutils::string::from() << name << ".y.y").c_str());
|
||||
m.y.z = cf.get(std::string( rsutils::string::from() << name << ".y.z").c_str());
|
||||
|
||||
m.z.x = cf.get(std::string( rsutils::string::from() << name << ".z.x").c_str());
|
||||
m.z.y = cf.get(std::string( rsutils::string::from() << name << ".z.y").c_str());
|
||||
m.z.z = cf.get(std::string( rsutils::string::from() << name << ".z.z").c_str());
|
||||
};
|
||||
|
||||
load_float3x4("intrinsic_left", table->intrinsic_left);
|
||||
load_float3x4("intrinsic_right", table->intrinsic_right);
|
||||
load_float3x4("world2left_rot", table->world2left_rot);
|
||||
load_float3x4("world2right_rot", table->world2right_rot);
|
||||
|
||||
for (int i = 0; i < librealsense::ds::max_ds_rect_resolutions; i++)
|
||||
{
|
||||
table->rect_params[i].x = cf.get(std::string( rsutils::string::from() << "rectified." << i << ".fx").c_str());
|
||||
table->rect_params[i].y = cf.get(std::string( rsutils::string::from() << "rectified." << i << ".fy").c_str());
|
||||
|
||||
table->rect_params[i].z = cf.get(std::string( rsutils::string::from() << "rectified." << i << ".ppx").c_str());
|
||||
table->rect_params[i].w = cf.get(std::string( rsutils::string::from() << "rectified." << i << ".ppy").c_str());
|
||||
}
|
||||
}
|
||||
|
||||
changed = true;
|
||||
}
|
||||
catch (const std::exception& ex)
|
||||
{
|
||||
error_message = ex.what();
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip("%s", "Load calibration from file");
|
||||
}
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button(u8"\uF0C7 Save As...", ImVec2(100, 30)))
|
||||
{
|
||||
try
|
||||
{
|
||||
if (auto fn = file_dialog_open(file_dialog_mode::save_file, "Calibration JSON\0*.json\0", nullptr, nullptr))
|
||||
{
|
||||
config_file cf(fn);
|
||||
cf.set("baseline", table->baseline);
|
||||
|
||||
auto save_float3x4 = [&](std::string name, librealsense::float3x3& m){
|
||||
cf.set(std::string( rsutils::string::from() << name << ".x.x").c_str(), m.x.x);
|
||||
cf.set(std::string( rsutils::string::from() << name << ".x.y").c_str(), m.x.y);
|
||||
cf.set(std::string( rsutils::string::from() << name << ".x.z").c_str(), m.x.z);
|
||||
|
||||
cf.set(std::string( rsutils::string::from() << name << ".y.x").c_str(), m.y.x);
|
||||
cf.set(std::string( rsutils::string::from() << name << ".y.y").c_str(), m.y.y);
|
||||
cf.set(std::string( rsutils::string::from() << name << ".y.z").c_str(), m.y.z);
|
||||
|
||||
cf.set(std::string( rsutils::string::from() << name << ".z.x").c_str(), m.z.x);
|
||||
cf.set(std::string( rsutils::string::from() << name << ".z.y").c_str(), m.z.y);
|
||||
cf.set(std::string( rsutils::string::from() << name << ".z.z").c_str(), m.z.z);
|
||||
};
|
||||
|
||||
save_float3x4("intrinsic_left", table->intrinsic_left);
|
||||
save_float3x4("intrinsic_right", table->intrinsic_right);
|
||||
save_float3x4("world2left_rot", table->world2left_rot);
|
||||
save_float3x4("world2right_rot", table->world2right_rot);
|
||||
|
||||
for (int i = 0; i < librealsense::ds::max_ds_rect_resolutions; i++)
|
||||
{
|
||||
auto xy = librealsense::ds::resolutions_list[(librealsense::ds::ds_rect_resolutions)i];
|
||||
int w = xy.x; int h = xy.y;
|
||||
|
||||
cf.set(std::string( rsutils::string::from() << "rectified." << i << ".width").c_str(), w);
|
||||
cf.set(std::string( rsutils::string::from() << "rectified." << i << ".height").c_str(), h);
|
||||
|
||||
cf.set(std::string( rsutils::string::from() << "rectified." << i << ".fx").c_str(), table->rect_params[i].x);
|
||||
cf.set(std::string( rsutils::string::from() << "rectified." << i << ".fy").c_str(), table->rect_params[i].y);
|
||||
|
||||
cf.set(std::string( rsutils::string::from() << "rectified." << i << ".ppx").c_str(), table->rect_params[i].z);
|
||||
cf.set(std::string( rsutils::string::from() << "rectified." << i << ".ppy").c_str(), table->rect_params[i].w);
|
||||
}
|
||||
}
|
||||
}
|
||||
catch (const std::exception& ex)
|
||||
{
|
||||
error_message = ex.what();
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip("%s", "Save calibration image to file");
|
||||
}
|
||||
ImGui::SameLine();
|
||||
if (_accept)
|
||||
{
|
||||
if (ImGui::Button(u8"\uF275 Restore Factory", ImVec2(115, 30)))
|
||||
{
|
||||
try
|
||||
{
|
||||
dev.as<rs2::auto_calibrated_device>().reset_to_factory_calibration();
|
||||
_calibration = dev.as<rs2::auto_calibrated_device>().get_calibration_table();
|
||||
_original = _calibration;
|
||||
table = reinterpret_cast< librealsense::ds::d400_coefficients_table * >( _calibration.data() );
|
||||
orig_table = reinterpret_cast< librealsense::ds::d400_coefficients_table * >( _original.data() );
|
||||
changed = true;
|
||||
|
||||
if (auto nm = _not_model.lock())
|
||||
{
|
||||
nm->add_notification({ rsutils::string::from() << "Depth Calibration is reset to Factory Settings",
|
||||
RS2_LOG_SEVERITY_INFO, RS2_NOTIFICATION_CATEGORY_HARDWARE_EVENT });
|
||||
}
|
||||
}
|
||||
catch(const std::exception& ex)
|
||||
{
|
||||
error_message = ex.what();
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip("%s", "Restore calibration in flash to factory settings");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, grey);
|
||||
ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, grey);
|
||||
|
||||
ImGui::Button(u8"\uF275 Restore Factory", ImVec2(115, 30));
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
RsImGui::CustomTooltip("%s", "Write selected calibration table to the device. For advanced users");
|
||||
}
|
||||
|
||||
ImGui::PopStyleColor(2);
|
||||
}
|
||||
|
||||
ImGui::PushStyleColor(ImGuiCol_ChildBg, dark_sensor_bg);
|
||||
|
||||
ImGui::BeginChild("##CalibData",ImVec2(w - 15, h - 110), true);
|
||||
|
||||
ImGui::SetCursorPosX(10);
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
|
||||
ImGui::Text("Stereo Baseline(mm):"); ImGui::SameLine();
|
||||
ImGui::SetCursorPosX(200);
|
||||
|
||||
ImGui::PushItemWidth(120);
|
||||
draw_float("Baseline", table->baseline, orig_table->baseline, changed);
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
ImGui::PopItemWidth();
|
||||
|
||||
draw_float4x4("Left Intrinsics", table->intrinsic_left, orig_table->intrinsic_left, changed);
|
||||
draw_float4x4("Right Intrinsics", table->intrinsic_right, orig_table->intrinsic_right, changed);
|
||||
draw_float4x4("World to Left Rotation", table->world2left_rot, orig_table->world2left_rot, changed);
|
||||
draw_float4x4("World to Right Rotation", table->world2right_rot, orig_table->world2right_rot, changed);
|
||||
|
||||
ImGui::SetCursorPosX(10);
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
|
||||
ImGui::Text("Rectified Resolution:"); ImGui::SameLine();
|
||||
ImGui::SetCursorPosX(200);
|
||||
|
||||
std::vector<std::string> resolution_names;
|
||||
std::vector<const char*> resolution_names_char;
|
||||
std::vector<int> resolution_offset;
|
||||
for (int i = 0; i < librealsense::ds::max_ds_rect_resolutions; i++)
|
||||
{
|
||||
auto xy = librealsense::ds::resolutions_list[(librealsense::ds::ds_rect_resolutions)i];
|
||||
int w = xy.x; int h = xy.y;
|
||||
if (w != 0) {
|
||||
resolution_offset.push_back(i);
|
||||
std::string name = rsutils::string::from() << w << " x " << h;
|
||||
resolution_names.push_back(name);
|
||||
}
|
||||
}
|
||||
for (size_t i = 0; i < resolution_offset.size(); i++)
|
||||
{
|
||||
resolution_names_char.push_back(resolution_names[i].c_str());
|
||||
}
|
||||
|
||||
ImGui::PushItemWidth(120);
|
||||
ImGui::Combo("##RectifiedResolutions", &selected_resolution, resolution_names_char.data(), int(resolution_names_char.size()));
|
||||
|
||||
ImGui::SetCursorPosX(10);
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
|
||||
ImGui::Text("Focal Length:"); ImGui::SameLine();
|
||||
ImGui::SetCursorPosX(200);
|
||||
|
||||
draw_float("FocalX", table->rect_params[selected_resolution].x, orig_table->rect_params[selected_resolution].x, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float("FocalY", table->rect_params[selected_resolution].y, orig_table->rect_params[selected_resolution].y, changed);
|
||||
|
||||
ImGui::SetCursorPosX(10);
|
||||
ImGui::Text("Principal Point:"); ImGui::SameLine();
|
||||
ImGui::SetCursorPosX(200);
|
||||
|
||||
draw_float("PPX", table->rect_params[selected_resolution].z, orig_table->rect_params[selected_resolution].z, changed);
|
||||
ImGui::SameLine();
|
||||
draw_float("PPY", table->rect_params[selected_resolution].w, orig_table->rect_params[selected_resolution].w, changed);
|
||||
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
|
||||
|
||||
ImGui::PopItemWidth();
|
||||
|
||||
if (ImGui::IsWindowHovered()) window.set_hovered_over_input();
|
||||
|
||||
ImGui::EndChild();
|
||||
ImGui::PopStyleColor();
|
||||
|
||||
ImGui::SetCursorScreenPos({ (float)(x0 + 10), (float)(y0 + h - 30) });
|
||||
if (ImGui::Checkbox("I know what I'm doing", &_accept))
|
||||
{
|
||||
config_file::instance().set(configurations::calibration::enable_writing, _accept);
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
RsImGui::CustomTooltip("%s", "Changing calibration will affect depth quality. Changes are persistent.\nThere is an option to get back to factory calibration, but it maybe worse than current calibration\nBefore writing to flash, we strongly recommend to make a file backup");
|
||||
}
|
||||
|
||||
ImGui::SetCursorScreenPos({ (float)(x0 + w - 230), (float)(y0 + h - 30) });
|
||||
|
||||
if (ImGui::Button("Cancel", ImVec2(100, 25)))
|
||||
{
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip("%s", "Close without saving any changes");
|
||||
}
|
||||
ImGui::SameLine();
|
||||
|
||||
auto streams = dev.query_sensors()[0].get_active_streams();
|
||||
if (_accept && streams.size())
|
||||
{
|
||||
if (ImGui::Button(u8"\uF2DB Write Table", ImVec2(120, 25)))
|
||||
{
|
||||
try
|
||||
{
|
||||
auto actual_data = _calibration.data() + sizeof(librealsense::ds::table_header);
|
||||
auto actual_data_size = _calibration.size() - sizeof(librealsense::ds::table_header);
|
||||
auto crc = rsutils::number::calc_crc32( actual_data, actual_data_size );
|
||||
table->header.crc32 = crc;
|
||||
dev.as<rs2::auto_calibrated_device>().set_calibration_table(_calibration);
|
||||
dev.as<rs2::auto_calibrated_device>().write_calibration();
|
||||
_original = _calibration;
|
||||
orig_table = reinterpret_cast< librealsense::ds::d400_coefficients_table * >( _original.data() );
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
catch (const std::exception& ex)
|
||||
{
|
||||
error_message = ex.what();
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip("%s", "Write selected calibration table to the device");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, grey);
|
||||
ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, grey);
|
||||
|
||||
ImGui::Button(u8"\uF2DB Write Table", ImVec2(120, 25));
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
RsImGui::CustomTooltip("%s", "Write selected calibration table to the device. For advanced users");
|
||||
}
|
||||
|
||||
ImGui::PopStyleColor(2);
|
||||
}
|
||||
|
||||
if (changed && streams.size())
|
||||
{
|
||||
try
|
||||
{
|
||||
dev.as<rs2::auto_calibrated_device>().set_calibration_table(_calibration);
|
||||
}
|
||||
catch (const std::exception&)
|
||||
{
|
||||
try
|
||||
{
|
||||
dev.query_sensors()[0].close();
|
||||
dev.query_sensors()[0].open(streams);
|
||||
dev.as<rs2::auto_calibrated_device>().set_calibration_table(_calibration);
|
||||
}
|
||||
catch (const std::exception& ex)
|
||||
{
|
||||
error_message = ex.what();
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (ImGui::IsWindowHovered()) window.set_hovered_over_input();
|
||||
|
||||
ImGui::EndPopup();
|
||||
}
|
||||
ImGui::PopStyleColor(3);
|
||||
ImGui::PopStyleVar(2);
|
||||
}
|
||||
42
librealsense-r-256/common/calibration-model.h
Normal file
42
librealsense-r-256/common/calibration-model.h
Normal file
@@ -0,0 +1,42 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
#include <librealsense2/rs.hpp>
|
||||
#include "notifications.h"
|
||||
#include <rsutils/number/float3.h>
|
||||
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
class ux_window;
|
||||
|
||||
class calibration_model
|
||||
{
|
||||
using float3x3 = rsutils::number::float3x3;
|
||||
|
||||
public:
|
||||
calibration_model(rs2::device dev, std::shared_ptr<notifications_model> not_model);
|
||||
|
||||
bool supports();
|
||||
|
||||
void update(ux_window& window, std::string& error_message);
|
||||
|
||||
void open() { to_open = true; }
|
||||
|
||||
private:
|
||||
void draw_float4x4(std::string name, float3x3 & feild, const float3x3& original, bool& changed);
|
||||
void draw_float(std::string name, float& x, const float& orig, bool& changed);
|
||||
|
||||
rs2::device dev;
|
||||
bool to_open = false;
|
||||
bool _accept = false;
|
||||
|
||||
std::vector<uint8_t> _calibration;
|
||||
std::vector<uint8_t> _original;
|
||||
|
||||
int selected_resolution = 0;
|
||||
|
||||
std::weak_ptr<notifications_model> _not_model;
|
||||
};
|
||||
}
|
||||
260
librealsense-r-256/common/cli.h
Normal file
260
librealsense-r-256/common/cli.h
Normal file
@@ -0,0 +1,260 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
// Command-Line Interface for our tools/examples/etc.
|
||||
// Requires that 'tclap' be added to project dependencies!
|
||||
|
||||
#include <tclap/CmdLine.h>
|
||||
#include <tclap/ValueArg.h>
|
||||
|
||||
#include <librealsense2/rs.h>
|
||||
|
||||
#include <rsutils/os/ensure-console.h>
|
||||
#include <rsutils/json.h>
|
||||
|
||||
|
||||
namespace rs2 {
|
||||
|
||||
|
||||
// Base version of CLI without any context functionality
|
||||
class cli_no_context : public TCLAP::CmdLine
|
||||
{
|
||||
using super = TCLAP::CmdLine;
|
||||
|
||||
rs2_log_severity _default_log_level;
|
||||
|
||||
public:
|
||||
cli_no_context( std::string const & tool_name, std::string const & version_string )
|
||||
: super( tool_name, // The message to be used in the usage output
|
||||
' ', // Separates the argument flag/name from the value; leave default
|
||||
version_string )
|
||||
, debug_arg( "debug", "Turn on librealsense debug logs" )
|
||||
, _default_log_level( RS2_LOG_SEVERITY_ERROR ) // By default, log ERROR messages only
|
||||
{
|
||||
#ifdef BUILD_EASYLOGGINGPP
|
||||
add( debug_arg );
|
||||
#endif
|
||||
// There isn't always a console... so if we need to show an error/usage, we need to enable it:
|
||||
setOutput( &_our_cmdline_output );
|
||||
}
|
||||
cli_no_context( std::string const & tool_name )
|
||||
: cli_no_context( tool_name, RS2_API_FULL_VERSION_STR ) {}
|
||||
|
||||
public:
|
||||
enum _required { required };
|
||||
|
||||
class flag : public TCLAP::SwitchArg
|
||||
{
|
||||
using super = TCLAP::SwitchArg;
|
||||
|
||||
// Override so we push to the back and reverse ordering isn't needed!
|
||||
void addToList( std::list< TCLAP::Arg * > & argList ) const override
|
||||
{ argList.push_back( const_cast< flag * >( this ) ); }
|
||||
|
||||
public:
|
||||
flag( std::string const & long_name, std::string const & description )
|
||||
: flag( long_name, false, description ) {}
|
||||
flag( char short_name, std::string const & long_name, std::string const & description )
|
||||
: flag( short_name, long_name, false, description ) {}
|
||||
// Avoid treating "string" as a boolean
|
||||
flag( std::string const &, char const *, std::string const & ) = delete;
|
||||
flag( std::string const & long_name, bool value, std::string const & description )
|
||||
: super( {}, long_name, description, value ) {}
|
||||
flag( char short_name, std::string const & long_name, bool value, std::string const & description )
|
||||
: super( std::string( 1, short_name ), long_name, description, value ) {}
|
||||
};
|
||||
|
||||
template< class T >
|
||||
class value : public TCLAP::ValueArg< T >
|
||||
{
|
||||
using super = TCLAP::ValueArg< T >;
|
||||
|
||||
// Override so we push to the back and reverse ordering isn't needed!
|
||||
void addToList( std::list< TCLAP::Arg * > & argList ) const override
|
||||
{ argList.push_back( const_cast< value * >( this ) ); }
|
||||
|
||||
public:
|
||||
value( std::string const & long_name, std::string const & type_description, T value, std::string const & description )
|
||||
: super( {}, long_name, description, false /* not required */, value, type_description ) {}
|
||||
value( std::string const & long_name, std::string const & type_description, T value, std::string const & description, cli_no_context::_required )
|
||||
: super( {}, long_name, description, true /* required */, value, type_description ) {}
|
||||
value( char short_name, std::string const & long_name, std::string const & type_description, T value, std::string const & description )
|
||||
: super( std::string( 1, short_name ), long_name, description, false /* not required */, value, type_description ) {}
|
||||
value( char short_name, std::string const & long_name, std::string const & type_description, T value, std::string const & description, cli_no_context::_required )
|
||||
: super( std::string( 1, short_name ), long_name, description, true /* required */, value, type_description ) {}
|
||||
};
|
||||
|
||||
// One-line operation:
|
||||
// auto settings = cli( "description" ).arg( arg1, arg2 ).process( argc, argv );
|
||||
// add() is still available:
|
||||
// cli cmd( "description" );
|
||||
// cmd.add( arg1 );
|
||||
public:
|
||||
template< typename... Rest >
|
||||
cli_no_context & arg( TCLAP::Arg & a )
|
||||
{
|
||||
super::add( a );
|
||||
return *this;
|
||||
}
|
||||
template< typename... Rest >
|
||||
cli_no_context & arg( TCLAP::Arg & a, Rest... rest )
|
||||
{
|
||||
super::add( a );
|
||||
return arg( std::forward< Rest >( rest )... );
|
||||
}
|
||||
|
||||
cli_no_context & default_log_level( rs2_log_severity severity )
|
||||
{
|
||||
_default_log_level = severity;
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Replace parse() with our own process()
|
||||
protected:
|
||||
using super::parse; // don't let user call parse() - enforce using process()
|
||||
|
||||
virtual void apply()
|
||||
{
|
||||
#ifdef BUILD_EASYLOGGINGPP
|
||||
if( debug_arg.getValue() )
|
||||
rsutils::os::ensure_console();
|
||||
if( rsutils::os::has_console() )
|
||||
rs2_log_to_console( debug_arg.getValue() ? RS2_LOG_SEVERITY_DEBUG : _default_log_level, nullptr );
|
||||
#endif
|
||||
}
|
||||
|
||||
virtual rsutils::json build_cli_settings()
|
||||
{
|
||||
return rsutils::json::object();
|
||||
}
|
||||
|
||||
public:
|
||||
rsutils::json process( int argc, const char * const * argv )
|
||||
{
|
||||
parse( argc, argv );
|
||||
apply();
|
||||
return build_cli_settings();
|
||||
}
|
||||
|
||||
protected:
|
||||
// Override basic output methods:
|
||||
// If help is needed, for example, usage() will get called but we have not even ensured we have a console yet!
|
||||
class cmdline_output : public TCLAP::StdOutput
|
||||
{
|
||||
using super = TCLAP::StdOutput;
|
||||
|
||||
public:
|
||||
void usage( TCLAP::CmdLineInterface & c ) override
|
||||
{
|
||||
rsutils::os::ensure_console();
|
||||
super::usage( c );
|
||||
}
|
||||
|
||||
void version( TCLAP::CmdLineInterface & c ) override
|
||||
{
|
||||
rsutils::os::ensure_console();
|
||||
super::version( c );
|
||||
}
|
||||
|
||||
void failure( TCLAP::CmdLineInterface & c, TCLAP::ArgException & e ) override
|
||||
{
|
||||
rsutils::os::ensure_console();
|
||||
super::failure( c, e );
|
||||
}
|
||||
};
|
||||
|
||||
cmdline_output _our_cmdline_output;
|
||||
|
||||
// Public args that can be retrieved by the user
|
||||
public:
|
||||
flag debug_arg;
|
||||
};
|
||||
|
||||
|
||||
// CLI with additional context-controlling behavior:
|
||||
// (none at this time)
|
||||
//
|
||||
class cli_no_dds : public cli_no_context
|
||||
{
|
||||
using super = cli_no_context;
|
||||
|
||||
public:
|
||||
using super::super; // inherit same ctors
|
||||
};
|
||||
|
||||
|
||||
// CLI with additional DDS-controlling behavior:
|
||||
// --eth
|
||||
// --eth-only
|
||||
// --no-eth
|
||||
// --domain-id <0-232>
|
||||
//
|
||||
class cli : public cli_no_dds
|
||||
{
|
||||
using super = cli_no_dds;
|
||||
|
||||
public:
|
||||
cli( std::string const & tool_name, std::string const & version_string )
|
||||
: super( tool_name, version_string )
|
||||
, eth_arg( "eth", "Detect DDS devices, even if disabled in the configuration" )
|
||||
, eth_only_arg( "eth-only", "Use ONLY DDS devices; do not look for USB/MIPI devices" )
|
||||
, no_eth_arg( "no-eth", "Do not detect DDS devices, even if enabled in the configuration" )
|
||||
, domain_id_arg( "domain-id", "0-232", 0, "Domain ID to use with DDS devices" )
|
||||
{
|
||||
#ifdef BUILD_WITH_DDS
|
||||
add( eth_arg );
|
||||
add( eth_only_arg );
|
||||
add( no_eth_arg );
|
||||
add( domain_id_arg );
|
||||
#endif
|
||||
}
|
||||
cli( std::string const & tool_name )
|
||||
: cli( tool_name, RS2_API_FULL_VERSION_STR ) {}
|
||||
|
||||
public:
|
||||
rsutils::json build_cli_settings() override
|
||||
{
|
||||
auto settings = super::build_cli_settings();
|
||||
|
||||
#ifdef BUILD_WITH_DDS
|
||||
if( eth_arg.isSet() + eth_only_arg.isSet() + no_eth_arg.isSet() > 1 )
|
||||
throw TCLAP::CmdLineParseException( "--eth, --eth-only, and --no-eth are mutually exclusive", "FATAL" );
|
||||
if( domain_id_arg.isSet() + no_eth_arg.isSet() > 1 )
|
||||
throw TCLAP::CmdLineParseException( "--domain-id and --no-eth are mutually exclusive", "FATAL" );
|
||||
|
||||
if( eth_arg.isSet() )
|
||||
{
|
||||
settings["dds"]["enabled"] = true;
|
||||
}
|
||||
else if( eth_only_arg.isSet() )
|
||||
{
|
||||
settings["device-mask"] = RS2_PRODUCT_LINE_SW_ONLY | RS2_PRODUCT_LINE_ANY;
|
||||
settings["dds"]["enabled"] = true;
|
||||
}
|
||||
else if( no_eth_arg.isSet() )
|
||||
{
|
||||
settings["dds"]["enabled"] = false;
|
||||
}
|
||||
|
||||
if( domain_id_arg.isSet() )
|
||||
{
|
||||
if( domain_id_arg.getValue() < 0 || domain_id_arg.getValue() > 232 )
|
||||
throw TCLAP::ArgParseException( "expecting [0, 232]", domain_id_arg.toString() );
|
||||
settings["dds"]["domain"] = domain_id_arg.getValue();
|
||||
}
|
||||
#endif
|
||||
|
||||
return settings;
|
||||
}
|
||||
|
||||
// Public args that can be retrieved by the user
|
||||
public:
|
||||
flag eth_arg;
|
||||
flag eth_only_arg;
|
||||
flag no_eth_arg;
|
||||
value< int > domain_id_arg;
|
||||
};
|
||||
|
||||
|
||||
} // namespace rs2
|
||||
345
librealsense-r-256/common/d500-on-chip-calib.cpp
Normal file
345
librealsense-r-256/common/d500-on-chip-calib.cpp
Normal file
@@ -0,0 +1,345 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
|
||||
|
||||
#include <viewer.h>
|
||||
#include "d500-on-chip-calib.h"
|
||||
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
d500_on_chip_calib_manager::d500_on_chip_calib_manager(viewer_model& viewer, std::shared_ptr<subdevice_model> sub,
|
||||
device_model& model, device dev)
|
||||
: process_manager("D500 On-Chip Calibration"),
|
||||
_model(model),
|
||||
_dev(dev),
|
||||
_sub(sub)
|
||||
{
|
||||
if (dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE) &&
|
||||
std::string(dev.get_info(RS2_CAMERA_INFO_PRODUCT_LINE)) != "D500")
|
||||
{
|
||||
throw std::runtime_error("This Calibration Process cannot be processed with this device");
|
||||
}
|
||||
}
|
||||
|
||||
std::string d500_on_chip_calib_manager::convert_action_to_json_string()
|
||||
{
|
||||
std::stringstream ss;
|
||||
if (action == RS2_CALIB_ACTION_ON_CHIP_CALIB)
|
||||
{
|
||||
ss << "{\n calib run }";
|
||||
}
|
||||
else if (action == RS2_CALIB_ACTION_ON_CHIP_CALIB_DRY_RUN)
|
||||
{
|
||||
ss << "{\n calib dry run }";
|
||||
}
|
||||
else if (action == RS2_CALIB_ACTION_ON_CHIP_CALIB_ABORT)
|
||||
{
|
||||
ss << "{\n calib abort }";
|
||||
}
|
||||
return ss.str();
|
||||
}
|
||||
|
||||
void d500_on_chip_calib_manager::process_flow(std::function<void()> cleanup, invoker invoke)
|
||||
{
|
||||
std::string json = convert_action_to_json_string();
|
||||
|
||||
auto calib_dev = _dev.as<auto_calibrated_device>();
|
||||
float health = 0.f;
|
||||
int timeout_ms = 240000; // increased to 4 minutes for additional algo processing
|
||||
auto ans = calib_dev.run_on_chip_calibration(json, &health,
|
||||
[&](const float progress) {_progress = progress; }, timeout_ms);
|
||||
|
||||
// in order to grep new calibration from answer, use:
|
||||
// auto new_calib = std::vector<uint8_t>(ans.begin() + 3, ans.end());
|
||||
|
||||
if (_progress == 100.0)
|
||||
{
|
||||
_done = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
// exception must have been thrown from run_on_chip_calibration call
|
||||
_failed = true;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
bool d500_on_chip_calib_manager::abort()
|
||||
{
|
||||
auto calib_dev = _dev.as<auto_calibrated_device>();
|
||||
float health = 0.f;
|
||||
int timeout_ms = 50000; // 50 seconds
|
||||
std::string json = convert_action_to_json_string();
|
||||
auto ans = calib_dev.run_on_chip_calibration(json, &health,
|
||||
[&](const float progress) {}, timeout_ms);
|
||||
|
||||
// returns 1 on success, 0 on failure
|
||||
return (ans[0] == 1);
|
||||
}
|
||||
|
||||
void d500_on_chip_calib_manager::prepare_for_calibration()
|
||||
{
|
||||
// set depth preset as default preset, turn projector ON and depth AE ON
|
||||
if (_sub->s->supports(RS2_CAMERA_INFO_NAME) &&
|
||||
(std::string(_sub->s->get_info(RS2_CAMERA_INFO_NAME)) == "Stereo Module"))
|
||||
{
|
||||
auto depth_sensor = _sub->s->as <rs2::depth_sensor>();
|
||||
|
||||
// disabling the depth visual preset change for D555 - not needed
|
||||
std::string dev_name = _dev.supports( RS2_CAMERA_INFO_NAME ) ? _dev.get_info( RS2_CAMERA_INFO_NAME ) : "";
|
||||
if( dev_name.find( "D555" ) == std::string::npos )
|
||||
{
|
||||
// set depth preset as default preset
|
||||
set_option_if_needed<rs2::depth_sensor>(depth_sensor, RS2_OPTION_VISUAL_PRESET, 1);
|
||||
}
|
||||
|
||||
// turn projector ON
|
||||
set_option_if_needed<rs2::depth_sensor>(depth_sensor, RS2_OPTION_EMITTER_ENABLED, 1);
|
||||
|
||||
// turn depth AE ON
|
||||
set_option_if_needed<rs2::depth_sensor>(depth_sensor, RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1);
|
||||
}
|
||||
}
|
||||
|
||||
std::string d500_on_chip_calib_manager::get_device_pid() const
|
||||
{
|
||||
std::string pid_str;
|
||||
if (_dev.supports(RS2_CAMERA_INFO_PRODUCT_ID))
|
||||
pid_str = _dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID);
|
||||
return pid_str;
|
||||
}
|
||||
|
||||
d500_autocalib_notification_model::d500_autocalib_notification_model(std::string name,
|
||||
std::shared_ptr<process_manager> manager, bool exp)
|
||||
: process_notification_model(manager)
|
||||
{
|
||||
enable_expand = false;
|
||||
enable_dismiss = true;
|
||||
expanded = exp;
|
||||
if (expanded) visible = false;
|
||||
|
||||
message = name;
|
||||
this->severity = RS2_LOG_SEVERITY_INFO;
|
||||
this->category = RS2_NOTIFICATION_CATEGORY_HARDWARE_EVENT;
|
||||
|
||||
pinned = true;
|
||||
}
|
||||
|
||||
void d500_autocalib_notification_model::draw_content(ux_window& win, int x, int y, float t, std::string& error_message)
|
||||
{
|
||||
const auto bar_width = width - 115;
|
||||
ImGui::SetCursorScreenPos({ float(x + 9), float(y + 4) });
|
||||
|
||||
ImVec4 shadow{ 1.f, 1.f, 1.f, 0.1f };
|
||||
ImGui::GetWindowDrawList()->AddRectFilled({ float(x), float(y) },
|
||||
{ float(x + width), float(y + 25) }, ImColor(shadow));
|
||||
|
||||
if (update_state != RS2_CALIB_STATE_COMPLETE)
|
||||
{
|
||||
if (get_manager().action == d500_on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_CALIB)
|
||||
ImGui::Text("%s", "On-Chip Calibration");
|
||||
else if (get_manager().action == d500_on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_CALIB_DRY_RUN)
|
||||
ImGui::Text("%s", "Dry Run On-Chip Calibration");
|
||||
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, alpha(light_grey, 1.f - t));
|
||||
|
||||
if (update_state == RS2_CALIB_STATE_CALIB_IN_PROCESS)
|
||||
{
|
||||
enable_dismiss = false;
|
||||
ImGui::SetCursorScreenPos({ float(x + 9), float(y + 27) });
|
||||
ImGui::Text("%s", "Camera is being calibrated...\n");
|
||||
draw_abort(win, x, y);
|
||||
}
|
||||
else if (update_state == RS2_CALIB_STATE_ABORT)
|
||||
{
|
||||
get_manager().action = d500_on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_CALIB_ABORT;
|
||||
auto _this = shared_from_this();
|
||||
auto invoke = [_this](std::function<void()> action) {_this->invoke(action); };
|
||||
try
|
||||
{
|
||||
update_state = RS2_CALIB_STATE_ABORT_CALLED;
|
||||
_has_abort_succeeded = get_manager().abort();
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
throw std::runtime_error("Abort could not be performed!");
|
||||
}
|
||||
}
|
||||
else if (update_state == RS2_CALIB_STATE_ABORT_CALLED)
|
||||
{
|
||||
update_ui_after_abort_called(win, x, y);
|
||||
}
|
||||
else if (update_state == RS2_CALIB_STATE_INIT_CALIB ||
|
||||
update_state == RS2_CALIB_STATE_INIT_DRY_RUN)
|
||||
{
|
||||
calibration_button(win, x, y, bar_width);
|
||||
}
|
||||
else if (update_state == RS2_CALIB_STATE_FAILED)
|
||||
{
|
||||
update_ui_on_failure(win, x, y);
|
||||
}
|
||||
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
else
|
||||
{
|
||||
update_ui_on_calibration_complete(win, x, y);
|
||||
}
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
|
||||
|
||||
if (update_manager)
|
||||
{
|
||||
if (update_state == RS2_CALIB_STATE_CALIB_IN_PROCESS)
|
||||
{
|
||||
if (update_manager->done())
|
||||
{
|
||||
update_state = RS2_CALIB_STATE_COMPLETE;
|
||||
enable_dismiss = true;
|
||||
}
|
||||
else if (update_manager->failed())
|
||||
{
|
||||
update_state = RS2_CALIB_STATE_FAILED;
|
||||
enable_dismiss = true;
|
||||
}
|
||||
|
||||
if (!expanded)
|
||||
{
|
||||
if (update_manager->failed())
|
||||
{
|
||||
update_manager->check_error(_error_message);
|
||||
update_state = RS2_CALIB_STATE_FAILED;
|
||||
enable_dismiss = true;
|
||||
}
|
||||
|
||||
draw_progress_bar(win, bar_width);
|
||||
ImGui::SetCursorScreenPos({ float(x + width - 105), float(y + height - 25) });
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, light_grey);
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int d500_autocalib_notification_model::calc_height()
|
||||
{
|
||||
// adjusting the height of the notification window
|
||||
if (update_state == RS2_CALIB_STATE_CALIB_IN_PROCESS ||
|
||||
update_state == RS2_CALIB_STATE_COMPLETE ||
|
||||
update_state == RS2_CALIB_STATE_ABORT_CALLED ||
|
||||
update_state == RS2_CALIB_STATE_FAILED)
|
||||
return 90;
|
||||
return 60;
|
||||
}
|
||||
|
||||
|
||||
void d500_autocalib_notification_model::calibration_button(ux_window& win, int x, int y, int bar_width)
|
||||
{
|
||||
using namespace std;
|
||||
using namespace chrono;
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 9), float(y + height - ImGui::GetTextLineHeightWithSpacing() - 31) });
|
||||
|
||||
auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
|
||||
ImGui::PushStyleColor(ImGuiCol_Button, saturate(sensor_header_light_blue, sat));
|
||||
ImGui::PushStyleColor(ImGuiCol_ButtonHovered, saturate(sensor_header_light_blue, 1.5f));
|
||||
|
||||
std::string activation_cal_str = "Calibrate";
|
||||
if (update_state == RS2_CALIB_STATE_INIT_DRY_RUN)
|
||||
activation_cal_str = "Calibrate Dry Run";
|
||||
|
||||
std::string calibrate_button_name = rsutils::string::from() << activation_cal_str << "##self" << index;
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 28) });
|
||||
if (ImGui::Button(calibrate_button_name.c_str(), { float(bar_width), 20.f }))
|
||||
{
|
||||
get_manager().reset();
|
||||
if (update_state == RS2_CALIB_STATE_INIT_DRY_RUN)
|
||||
{
|
||||
get_manager().action = d500_on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_CALIB_DRY_RUN;
|
||||
}
|
||||
|
||||
get_manager().prepare_for_calibration();
|
||||
|
||||
auto _this = shared_from_this();
|
||||
auto invoke = [_this](std::function<void()> action) {_this->invoke(action); };
|
||||
get_manager().start(invoke);
|
||||
update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS;
|
||||
enable_dismiss = false;
|
||||
}
|
||||
ImGui::PopStyleColor(2);
|
||||
}
|
||||
|
||||
void d500_autocalib_notification_model::draw_abort(ux_window& win, int x, int y)
|
||||
{
|
||||
ImGui::SetCursorScreenPos({ float(x + width - 105), float(y + height - 25) });
|
||||
|
||||
std::string id = rsutils::string::from() << "Abort" << "##" << index;
|
||||
|
||||
|
||||
ImGui::SetNextWindowPos({ float(x + width - 125), float(y + height - 25) });
|
||||
ImGui::SetNextWindowSize({ 120, 70 });
|
||||
|
||||
if (ImGui::Button(id.c_str(), { 100, 20 }))
|
||||
{
|
||||
update_state = RS2_CALIB_STATE_ABORT;
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
RsImGui::CustomTooltip("Abort Calibration Process");
|
||||
}
|
||||
}
|
||||
|
||||
void d500_autocalib_notification_model::update_ui_after_abort_called(ux_window& win, int x, int y)
|
||||
{
|
||||
ImGui::Text("%s", "Calibration Aborting");
|
||||
ImGui::SetCursorScreenPos({ float(x + 10), float(y + 40) });
|
||||
ImGui::PushFont(win.get_large_font());
|
||||
std::string txt = rsutils::string::from() << textual_icons::stop;
|
||||
ImGui::Text("%s", txt.c_str());
|
||||
ImGui::PopFont();
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 40), float(y + 40) });
|
||||
if (_has_abort_succeeded)
|
||||
{
|
||||
ImGui::Text("%s", "Camera Calibration Aborted Successfully");
|
||||
}
|
||||
else
|
||||
{
|
||||
ImGui::Text("%s", "Camera Calibration Could not be Aborted");
|
||||
}
|
||||
enable_dismiss = true;
|
||||
}
|
||||
|
||||
void d500_autocalib_notification_model::update_ui_on_failure(ux_window& win, int x, int y)
|
||||
{
|
||||
ImGui::SetCursorScreenPos({ float(x + 50), float(y + 50) });
|
||||
ImGui::Text("%s", "Calibration Failed");
|
||||
ImGui::SetCursorScreenPos({ float(x + 10), float(y + 50) });
|
||||
ImGui::PushFont(win.get_large_font());
|
||||
std::string txt = rsutils::string::from() << textual_icons::exclamation_triangle;
|
||||
ImGui::Text("%s", txt.c_str());
|
||||
ImGui::PopFont();
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 40), float(y + 50) });
|
||||
|
||||
enable_dismiss = true;
|
||||
}
|
||||
|
||||
void d500_autocalib_notification_model::update_ui_on_calibration_complete(ux_window& win, int x, int y)
|
||||
{
|
||||
ImGui::Text("%s", "Calibration Complete");
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 10), float(y + 35) });
|
||||
ImGui::PushFont(win.get_large_font());
|
||||
std::string txt = rsutils::string::from() << textual_icons::throphy;
|
||||
ImGui::Text("%s", txt.c_str());
|
||||
ImGui::PopFont();
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 40), float(y + 35) });
|
||||
|
||||
ImGui::Text("%s", "Camera Calibration Applied Successfully");
|
||||
}
|
||||
}
|
||||
103
librealsense-r-256/common/d500-on-chip-calib.h
Normal file
103
librealsense-r-256/common/d500-on-chip-calib.h
Normal file
@@ -0,0 +1,103 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "notifications.h"
|
||||
#include <rsutils/concurrency/concurrency.h>
|
||||
#include "../src/algo.h"
|
||||
|
||||
#include <random>
|
||||
#include <string>
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
class viewer_model;
|
||||
class subdevice_model;
|
||||
struct subdevice_ui_selection;
|
||||
|
||||
// On-chip Calibration manager owns the background thread
|
||||
// leading the calibration process
|
||||
// It is controlled by autocalib_notification_model UI object
|
||||
// that invokes the process when needed
|
||||
class d500_on_chip_calib_manager : public process_manager
|
||||
{
|
||||
public:
|
||||
d500_on_chip_calib_manager(viewer_model& viewer, std::shared_ptr<subdevice_model> sub, device_model& model, device dev);
|
||||
|
||||
enum calib_action
|
||||
{
|
||||
RS2_CALIB_ACTION_ON_CHIP_CALIB, // On-Chip calibration
|
||||
RS2_CALIB_ACTION_ON_CHIP_CALIB_DRY_RUN, // Dry Run
|
||||
RS2_CALIB_ACTION_ON_CHIP_CALIB_ABORT // Abort
|
||||
};
|
||||
|
||||
calib_action action = RS2_CALIB_ACTION_ON_CHIP_CALIB;
|
||||
|
||||
std::shared_ptr<subdevice_model> _sub;
|
||||
|
||||
void reset_device() { _dev.hardware_reset(); }
|
||||
bool abort();
|
||||
void prepare_for_calibration();
|
||||
std::string get_device_pid() const;
|
||||
|
||||
private:
|
||||
void process_flow(std::function<void()> cleanup, invoker invoke) override;
|
||||
std::string convert_action_to_json_string();
|
||||
|
||||
template<class T>
|
||||
void set_option_if_needed(T& sensor, rs2_option opt, float required_value);
|
||||
device _dev;
|
||||
device_model& _model;
|
||||
};
|
||||
|
||||
template<class T>
|
||||
void d500_on_chip_calib_manager::set_option_if_needed(T& sensor,
|
||||
rs2_option opt, float required_value)
|
||||
{
|
||||
auto curr_value = sensor.get_option(opt);
|
||||
if (curr_value != required_value)
|
||||
{
|
||||
sensor.set_option(opt, required_value);
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(10));
|
||||
curr_value = sensor.get_option(opt);
|
||||
if (curr_value != required_value)
|
||||
{
|
||||
std::stringstream s;
|
||||
s << "Could not set " << rs2_option_to_string(opt) << " to " << required_value;
|
||||
throw std::runtime_error(s.str().c_str());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Auto-calib notification model is managing the UI state-machine
|
||||
// controling auto-calibration
|
||||
struct d500_autocalib_notification_model : public process_notification_model
|
||||
{
|
||||
enum auto_calib_ui_state
|
||||
{
|
||||
RS2_CALIB_STATE_INIT_CALIB, // First screen
|
||||
RS2_CALIB_STATE_FAILED, // Failed, show _error_message
|
||||
RS2_CALIB_STATE_COMPLETE, // After write, quick blue notification
|
||||
RS2_CALIB_STATE_CALIB_IN_PROCESS,// Calibration in process... Shows progressbar
|
||||
RS2_CALIB_STATE_INIT_DRY_RUN,
|
||||
RS2_CALIB_STATE_ABORT,
|
||||
RS2_CALIB_STATE_ABORT_CALLED
|
||||
};
|
||||
|
||||
d500_autocalib_notification_model(std::string name, std::shared_ptr<process_manager> manager, bool expaned);
|
||||
|
||||
d500_on_chip_calib_manager& get_manager() { return *std::dynamic_pointer_cast<d500_on_chip_calib_manager>(update_manager); }
|
||||
void draw_content(ux_window& win, int x, int y, float t, std::string& error_message) override;
|
||||
int calc_height() override;
|
||||
void calibration_button(ux_window& win, int x, int y, int bar_width);
|
||||
void draw_abort(ux_window& win, int x, int y);
|
||||
void update_ui_after_abort_called(ux_window& win, int x, int y);
|
||||
void update_ui_on_calibration_complete(ux_window& win, int x, int y);
|
||||
void update_ui_on_failure(ux_window& win, int x, int y);
|
||||
std::string _error_message = "";
|
||||
bool reset_called = false;
|
||||
bool _has_abort_succeeded = false;
|
||||
};
|
||||
|
||||
}
|
||||
382
librealsense-r-256/common/dds-model.cpp
Normal file
382
librealsense-r-256/common/dds-model.cpp
Normal file
@@ -0,0 +1,382 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include "dds-model.h"
|
||||
#include "device-model.h"
|
||||
#include "ux-window.h"
|
||||
#include <rsutils/json.h>
|
||||
#include <rsutils/json-config.h>
|
||||
#include <rsutils/os/special-folder.h>
|
||||
#include <rsutils/string/hexdump.h>
|
||||
#include <imgui.h>
|
||||
#include <realsense_imgui.h>
|
||||
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
|
||||
using namespace rs2;
|
||||
using rsutils::json;
|
||||
using rsutils::type::ip_address;
|
||||
|
||||
namespace rs2 {
|
||||
|
||||
uint32_t const GET_ETH_CONFIG = 0xBB;
|
||||
uint32_t const SET_ETH_CONFIG = 0xBA;
|
||||
|
||||
int const CURRENT_VALUES = 0;
|
||||
int const DEFULT_VALUES = 1;
|
||||
}
|
||||
|
||||
dds_model::dds_model( rs2::device dev )
|
||||
: _device( dev )
|
||||
, _window_open( false )
|
||||
, _no_reset( false )
|
||||
, _set_defult( false )
|
||||
, _dds_supported( false )
|
||||
{
|
||||
if( check_DDS_support() )
|
||||
{
|
||||
_defult_config = get_eth_config( DEFULT_VALUES );
|
||||
_current_config = get_eth_config( CURRENT_VALUES );
|
||||
_changed_config = _current_config;
|
||||
_dds_supported = true;
|
||||
}
|
||||
}
|
||||
|
||||
eth_config dds_model::get_eth_config( int curr_or_default )
|
||||
{
|
||||
rs2::debug_protocol dev( _device );
|
||||
auto cmd = dev.build_command( GET_ETH_CONFIG, curr_or_default );
|
||||
auto data = dev.send_and_receive_raw_data( cmd );
|
||||
int32_t const & code = *reinterpret_cast< int32_t const * >( data.data() );
|
||||
data.erase( data.begin(), data.begin() + sizeof( code ) );
|
||||
return eth_config( data );
|
||||
}
|
||||
|
||||
void rs2::dds_model::set_eth_config( eth_config & new_config, std::string & error_message )
|
||||
{
|
||||
rs2::debug_protocol hwm( _device );
|
||||
auto cmd = hwm.build_command( SET_ETH_CONFIG, 0, 0, 0, 0, new_config.build_command() );
|
||||
auto data = hwm.send_and_receive_raw_data( cmd );
|
||||
int32_t const & code = *reinterpret_cast< int32_t const * >( data.data() );
|
||||
if( data.size() != sizeof( code ) )
|
||||
{
|
||||
error_message = rsutils::string::from() << "Failed to change: bad response size " << data.size() << ' '
|
||||
<< rsutils::string::hexdump( data.data(), data.size() );
|
||||
close_window();
|
||||
}
|
||||
if( code != SET_ETH_CONFIG )
|
||||
{
|
||||
error_message = rsutils::string::from() << "Failed to change: bad response " << code;
|
||||
close_window();
|
||||
}
|
||||
if( ! _no_reset )
|
||||
{
|
||||
close_window();
|
||||
_device.hardware_reset();
|
||||
}
|
||||
}
|
||||
|
||||
bool rs2::dds_model::supports_DDS()
|
||||
{
|
||||
return _dds_supported;
|
||||
}
|
||||
|
||||
rs2::dds_model::priority rs2::dds_model::classifyPriority( link_priority & pr )
|
||||
{
|
||||
if( pr == link_priority::usb_only || pr == link_priority::usb_first )
|
||||
{
|
||||
return priority::USB_FIRST;
|
||||
}
|
||||
else if( pr == link_priority::eth_first || pr == link_priority::eth_only )
|
||||
{
|
||||
return priority::ETH_FIRST;
|
||||
}
|
||||
return priority::DYNAMIC;
|
||||
}
|
||||
|
||||
bool dds_model::check_DDS_support()
|
||||
{
|
||||
if( _device.is< rs2::debug_protocol >() )
|
||||
{
|
||||
if( _device.supports( RS2_CAMERA_INFO_NAME ) )
|
||||
{
|
||||
std::string name = _device.get_info( RS2_CAMERA_INFO_NAME );
|
||||
if( name.find( "Recovery" ) != std::string::npos )
|
||||
return false; // Recovery devices don't support HWM.
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
auto dev = debug_protocol( _device );
|
||||
auto cmd = dev.build_command( GET_ETH_CONFIG, CURRENT_VALUES );
|
||||
auto data = dev.send_and_receive_raw_data( cmd );
|
||||
int32_t const & code = *reinterpret_cast< int32_t const * >( data.data() );
|
||||
if( code == GET_ETH_CONFIG )
|
||||
return true;
|
||||
}
|
||||
catch( ... )
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void rs2::dds_model::ipInputText( std::string label, ip_address & ip )
|
||||
{
|
||||
char buffer[16];
|
||||
std::string ip_str = ip.to_string();
|
||||
std::snprintf( buffer, sizeof( buffer ), "%s", ip_str.c_str() );
|
||||
std::string label_name = "##" + label;
|
||||
|
||||
if( ImGui::InputText( label_name.c_str(), buffer, sizeof( buffer ) ) )
|
||||
{
|
||||
std::string new_ip_str( buffer );
|
||||
ip_address new_ip = ip_address( new_ip_str );
|
||||
if( new_ip.is_valid() )
|
||||
{
|
||||
ip = new_ip;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Initialize the ImGui buffer with the current IP address in case of invalid input
|
||||
std::snprintf( buffer, sizeof( buffer ), "%s", ip.to_string().c_str() );
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void dds_model::render_dds_config_window( ux_window & window, std::string & error_message )
|
||||
{
|
||||
const auto window_name = "DDS Configuration";
|
||||
if( _window_open )
|
||||
{
|
||||
try
|
||||
{
|
||||
_current_config = get_eth_config( CURRENT_VALUES );
|
||||
_changed_config = _current_config;
|
||||
ImGui::OpenPopup( window_name );
|
||||
}
|
||||
catch( std::exception e )
|
||||
{
|
||||
error_message = e.what();
|
||||
}
|
||||
_window_open = false;
|
||||
}
|
||||
|
||||
// Calculate window position and size
|
||||
const float w = 620;
|
||||
const float h = 500;
|
||||
const float x0 = std::max( window.width() - w, 0.f ) / 2;
|
||||
const float y0 = std::max( window.height() - h, 0.f ) / 2;
|
||||
ImGui::SetNextWindowPos( { x0, y0 } );
|
||||
ImGui::SetNextWindowSize( { w, h } );
|
||||
|
||||
auto flags = ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoTitleBar | ImGuiWindowFlags_NoCollapse
|
||||
| ImGuiWindowFlags_NoSavedSettings;
|
||||
|
||||
ImGui::PushStyleColor( ImGuiCol_PopupBg, sensor_bg );
|
||||
ImGui::PushStyleColor( ImGuiCol_TextSelectedBg, light_grey );
|
||||
ImGui::PushStyleColor( ImGuiCol_Text, light_grey );
|
||||
ImGui::PushStyleVar( ImGuiStyleVar_WindowPadding, ImVec2( 5, 5 ) );
|
||||
ImGui::PushStyleVar( ImGuiStyleVar_WindowRounding, 1 );
|
||||
ImGui::PushStyleColor( ImGuiCol_Button, button_color );
|
||||
ImGui::PushStyleColor( ImGuiCol_ButtonHovered, button_color + 0.1f );
|
||||
ImGui::PushStyleColor( ImGuiCol_ButtonActive, button_color + 0.1f );
|
||||
|
||||
|
||||
if( ImGui::BeginPopupModal( window_name, nullptr, flags ) )
|
||||
{
|
||||
if( error_message != "" )
|
||||
ImGui::CloseCurrentPopup();
|
||||
|
||||
// Title
|
||||
const char * title_message = window_name;
|
||||
ImVec2 title_size = ImGui::CalcTextSize( title_message );
|
||||
float title_x = ( w - title_size.x - 10 ) / 2.0f;
|
||||
ImGui::SetCursorPos( { title_x, 10.0f } );
|
||||
ImGui::PushFont( window.get_large_font() );
|
||||
ImGui::PushStyleColor( ImGuiCol_Text, white );
|
||||
ImGui::Text( "%s", title_message );
|
||||
ImGui::PopStyleColor();
|
||||
ImGui::PopFont();
|
||||
ImGui::Separator();
|
||||
ImGui::SetCursorPosY( ImGui::GetCursorPosY() + 15 );
|
||||
|
||||
// Main Scrollable Section
|
||||
ImGui::BeginChild( "MainContent", ImVec2( w - 10, h - 100 ), true );
|
||||
ImGui::PushItemWidth( 150.0f );
|
||||
|
||||
// Connection Priority Section
|
||||
priority connection_priority = classifyPriority( _changed_config.link.priority );
|
||||
if( ImGui::CollapsingHeader( "Connection Priority" ) )
|
||||
{
|
||||
ImGui::Text( "Select connection priority:" );
|
||||
ImGui::RadioButton( "Ethernet First", reinterpret_cast< int * >( &connection_priority ), 0 );
|
||||
if( static_cast< int >( connection_priority ) == 0 )
|
||||
{
|
||||
ImGui::SameLine();
|
||||
ImGui::SetCursorPosX( ImGui::GetCursorPosX() + 50 );
|
||||
ImGui::Text( "Link Timeout (seconds)" );
|
||||
ImGui::SameLine();
|
||||
int tempTimeout = static_cast< int >( _changed_config.link.timeout );
|
||||
if( ImGui::InputInt( "##Link Timeout (seconds)", &tempTimeout ) )
|
||||
{
|
||||
_changed_config.link.timeout = static_cast< uint16_t >( std::max( 0, tempTimeout ) );
|
||||
}
|
||||
}
|
||||
ImGui::RadioButton( "USB First", reinterpret_cast< int * >( &connection_priority ), 1 );
|
||||
ImGui::RadioButton( "Dynamic Priority", reinterpret_cast< int * >( &connection_priority ), 2 );
|
||||
switch( connection_priority )
|
||||
{
|
||||
case ETH_FIRST:
|
||||
_changed_config.link.priority = link_priority::eth_first;
|
||||
break;
|
||||
case USB_FIRST:
|
||||
_changed_config.link.priority = link_priority::usb_first;
|
||||
break;
|
||||
case DYNAMIC:
|
||||
_changed_config.link.priority
|
||||
= _current_config.link.speed
|
||||
? link_priority::dynamic_eth_first
|
||||
: link_priority::dynamic_usb_first; // If link speed is not 0 than we are connected by Ethernet
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Network Configuration Section
|
||||
if( ImGui::CollapsingHeader( "Network Configuration" ) )
|
||||
{
|
||||
ImGui::Checkbox( "Enable DHCP", &_changed_config.dhcp.on );
|
||||
if( ! _changed_config.dhcp.on )
|
||||
{
|
||||
ImGui::Text( "Static IP Address" );
|
||||
ImGui::SameLine();
|
||||
float textbox_align = ImGui::GetCursorPosX();
|
||||
ipInputText( "Static IP Address", _changed_config.configured.ip );
|
||||
ImGui::Text( "Subnet Mask" );
|
||||
ImGui::SameLine();
|
||||
ImGui::SetCursorPosX( textbox_align );
|
||||
bool maskStylePushed = false;
|
||||
ipInputText( "Subnet Mask", _changed_config.configured.netmask );
|
||||
ImGui::Text( "Gateway" );
|
||||
ImGui::SameLine();
|
||||
ImGui::SetCursorPosX( textbox_align );
|
||||
ipInputText( "Gateway", _changed_config.configured.gateway );
|
||||
}
|
||||
else
|
||||
{
|
||||
ImGui::Text( "DHCP Timeout (seconds)" );
|
||||
ImGui::SameLine();
|
||||
int tempTimeout = static_cast< int >( _changed_config.dhcp.timeout );
|
||||
if( ImGui::InputInt( "##DHCP Timeout (seconds)", &tempTimeout ) )
|
||||
{
|
||||
_changed_config.dhcp.timeout = static_cast< uint16_t >( std::max( 0, tempTimeout ) );
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ImGui::Text( "Domain ID" );
|
||||
ImGui::SameLine();
|
||||
if( ImGui::InputInt( "##Domain ID", &_changed_config.dds.domain_id ) )
|
||||
{
|
||||
if( _changed_config.dds.domain_id < 0 )
|
||||
_changed_config.dds.domain_id = 0;
|
||||
else if( _changed_config.dds.domain_id > 232 )
|
||||
_changed_config.dds.domain_id = 232;
|
||||
}
|
||||
ImGui::Checkbox( "No Reset after changes", &_no_reset );
|
||||
|
||||
if( ImGui::Checkbox( "Load defult values", &_set_defult ) )
|
||||
{
|
||||
if( _set_defult )
|
||||
_changed_config = _defult_config;
|
||||
else
|
||||
_changed_config = _current_config;
|
||||
}
|
||||
|
||||
ImGui::PopItemWidth();
|
||||
ImGui::EndChild();
|
||||
|
||||
// window buttons
|
||||
float button_width = 115.0f;
|
||||
float spacing = 10.0f;
|
||||
float total_buttons_width = button_width * 4 + spacing * 2;
|
||||
float start_x = ( w - total_buttons_width ) / 2.0f;
|
||||
bool hasChanges = ( _changed_config != _current_config );
|
||||
|
||||
ImGui::SetCursorPosY( ImGui::GetCursorPosY() + 8 );
|
||||
|
||||
ImGui::SetCursorPosX( start_x );
|
||||
|
||||
if( ImGui::Button( "Cancel", ImVec2( button_width, 25 ) ) )
|
||||
{
|
||||
close_window();
|
||||
}
|
||||
if( ImGui::IsItemHovered() )
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip( "%s", "Close without saving any changes" );
|
||||
}
|
||||
ImGui::SameLine();
|
||||
if( ImGui::Button( "Factory Reset", ImVec2( button_width, 25 ) ) )
|
||||
{
|
||||
set_eth_config( _defult_config, error_message );
|
||||
close_window();
|
||||
}
|
||||
if( ImGui::IsItemHovered() )
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip( "%s", "Reset settings back to defult values" );
|
||||
}
|
||||
ImGui::SameLine();
|
||||
RsImGui::RsImButton(
|
||||
[&]()
|
||||
{
|
||||
if( ImGui::ButtonEx( "Revert changes", ImVec2( button_width, 25 ) ) )
|
||||
{
|
||||
_changed_config = _current_config;
|
||||
};
|
||||
},
|
||||
! hasChanges );
|
||||
if( ImGui::IsItemHovered() )
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip( "%s", "Revert to current configuration values" );
|
||||
}
|
||||
ImGui::SameLine();
|
||||
RsImGui::RsImButton(
|
||||
[&]()
|
||||
{
|
||||
if( ImGui::ButtonEx( "Apply", ImVec2( button_width, 25 ) ) )
|
||||
{
|
||||
set_eth_config( _changed_config, error_message );
|
||||
close_window();
|
||||
};
|
||||
},
|
||||
! hasChanges );
|
||||
if( ImGui::IsItemHovered() )
|
||||
{
|
||||
window.link_hovered();
|
||||
RsImGui::CustomTooltip( "%s", "Apply changes" );
|
||||
}
|
||||
if( ImGui::BeginPopupModal( "No Changes Needed", NULL, ImGuiWindowFlags_AlwaysAutoResize ) )
|
||||
{
|
||||
ImGui::Text( "No changes were made to the configuration." );
|
||||
|
||||
if( ImGui::Button( "OK", ImVec2( 100, 25 ) ) )
|
||||
{
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
ImGui::EndPopup();
|
||||
}
|
||||
ImGui::EndPopup();
|
||||
}
|
||||
ImGui::PopStyleColor( 6 );
|
||||
ImGui::PopStyleVar( 2 );
|
||||
}
|
||||
|
||||
void rs2::dds_model::open_dds_tool_window()
|
||||
{
|
||||
_window_open = true;
|
||||
}
|
||||
55
librealsense-r-256/common/dds-model.h
Normal file
55
librealsense-r-256/common/dds-model.h
Normal file
@@ -0,0 +1,55 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
#include <librealsense2/rs.hpp>
|
||||
#include <imgui.h>
|
||||
#include <rsutils/type/eth-config.h>
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
class ux_window;
|
||||
|
||||
class dds_model
|
||||
{
|
||||
|
||||
public:
|
||||
dds_model(rs2::device dev);
|
||||
|
||||
void render_dds_config_window(ux_window& window, std::string& error_message);
|
||||
|
||||
void open_dds_tool_window();
|
||||
|
||||
void close_window() { ImGui::CloseCurrentPopup(); }
|
||||
|
||||
eth_config get_eth_config(int curr_or_default);
|
||||
|
||||
void set_eth_config(eth_config &new_config , std::string& error_message);
|
||||
|
||||
bool supports_DDS();
|
||||
|
||||
|
||||
private:
|
||||
|
||||
enum priority {
|
||||
ETH_FIRST,
|
||||
USB_FIRST,
|
||||
DYNAMIC
|
||||
};
|
||||
|
||||
rs2::device _device;
|
||||
|
||||
eth_config _defult_config;
|
||||
eth_config _current_config;
|
||||
eth_config _changed_config;
|
||||
|
||||
bool _window_open;
|
||||
bool _no_reset;
|
||||
bool _set_defult;
|
||||
bool _dds_supported;
|
||||
|
||||
void ipInputText(std::string label, rsutils::type::ip_address &ip);
|
||||
priority classifyPriority(link_priority &pr);
|
||||
bool check_DDS_support();
|
||||
};
|
||||
}
|
||||
3565
librealsense-r-256/common/device-model.cpp
Normal file
3565
librealsense-r-256/common/device-model.cpp
Normal file
File diff suppressed because it is too large
Load Diff
477
librealsense-r-256/common/device-model.h
Normal file
477
librealsense-r-256/common/device-model.h
Normal file
@@ -0,0 +1,477 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2023 Intel Corporation. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
#include <set>
|
||||
#include "notifications.h"
|
||||
#include "realsense-ui-advanced-mode.h"
|
||||
#include <rsutils/json.h>
|
||||
#include "sw-update/dev-updates-profile.h"
|
||||
#include <rsutils/time/periodic-timer.h>
|
||||
#include "updates-model.h"
|
||||
#include "calibration-model.h"
|
||||
#include "objects-in-frame.h"
|
||||
#include "dds-model.h"
|
||||
|
||||
ImVec4 from_rgba(uint8_t r, uint8_t g, uint8_t b, uint8_t a, bool consistent_color = false);
|
||||
ImVec4 operator+(const ImVec4& c, float v);
|
||||
|
||||
static const ImVec4 light_blue = from_rgba(0, 174, 239, 255, true); // Light blue color for selected elements such as play button glyph when paused
|
||||
static const ImVec4 regular_blue = from_rgba(0, 115, 200, 255, true); // Checkbox mark, slider grabber
|
||||
static const ImVec4 light_grey = from_rgba(0xc3, 0xd5, 0xe5, 0xff, true); // Text
|
||||
static const ImVec4 dark_window_background = from_rgba(9, 11, 13, 255);
|
||||
static const ImVec4 almost_white_bg = from_rgba(230, 230, 230, 255, true);
|
||||
static const ImVec4 black = from_rgba(0, 0, 0, 255, true);
|
||||
static const ImVec4 transparent = from_rgba(0, 0, 0, 0, true);
|
||||
static const ImVec4 white = from_rgba(0xff, 0xff, 0xff, 0xff, true);
|
||||
static const ImVec4 scrollbar_bg = from_rgba(14, 17, 20, 255);
|
||||
static const ImVec4 scrollbar_grab = from_rgba(54, 66, 67, 255);
|
||||
static const ImVec4 grey{ 0.5f,0.5f,0.5f,1.f };
|
||||
static const ImVec4 dark_grey = from_rgba(30, 30, 30, 255);
|
||||
static const ImVec4 sensor_header_light_blue = from_rgba(80, 99, 115, 0xff);
|
||||
static const ImVec4 sensor_bg = from_rgba(36, 44, 51, 0xff);
|
||||
static const ImVec4 redish = from_rgba(255, 46, 54, 255, true);
|
||||
static const ImVec4 light_red = from_rgba(255, 146, 154, 255, true);
|
||||
static const ImVec4 dark_red = from_rgba(200, 46, 54, 255, true);
|
||||
static const ImVec4 button_color = from_rgba(62, 77, 89, 0xff);
|
||||
static const ImVec4 header_window_bg = from_rgba(36, 44, 54, 0xff);
|
||||
static const ImVec4 header_color = from_rgba(62, 77, 89, 255);
|
||||
static const ImVec4 title_color = from_rgba(27, 33, 38, 255);
|
||||
static const ImVec4 device_info_color = from_rgba(33, 40, 46, 255);
|
||||
static const ImVec4 yellow = from_rgba(229, 195, 101, 255, true);
|
||||
static const ImVec4 yellowish = from_rgba(255, 253, 191, 255, true);
|
||||
static const ImVec4 green = from_rgba(0x20, 0xe0, 0x20, 0xff, true);
|
||||
static const ImVec4 dark_sensor_bg = from_rgba(0x1b, 0x21, 0x25, 170);
|
||||
static const ImVec4 red = from_rgba(233, 0, 0, 255, true);
|
||||
static const ImVec4 greenish = from_rgba(67, 163, 97, 255);
|
||||
static const ImVec4 orange = from_rgba(255, 157, 0, 255, true);
|
||||
|
||||
inline ImVec4 operator*(const ImVec4& color, float t)
|
||||
{
|
||||
return ImVec4(color.x * t, color.y * t, color.z * t, color.w * t);
|
||||
}
|
||||
inline ImVec4 operator+(const ImVec4& a, const ImVec4& b)
|
||||
{
|
||||
return ImVec4(a.x + b.x, a.y + b.y, a.z + b.z, a.w + b.w);
|
||||
}
|
||||
|
||||
inline ImVec4 blend(const ImVec4& c, float a)
|
||||
{
|
||||
return{ c.x, c.y, c.z, a * c.w };
|
||||
}
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
void imgui_easy_theming(ImFont*& font_dynamic, ImFont*& font_18, ImFont*& monofont, int& font_size);
|
||||
|
||||
constexpr const char* server_versions_db_url = "https://librealsense.intel.com/Releases/rs_versions_db.json";
|
||||
|
||||
typedef std::vector<std::unique_ptr<device_model>> device_models_list;
|
||||
|
||||
void open_issue(const device_models_list& devices);
|
||||
|
||||
struct textual_icon
|
||||
{
|
||||
explicit constexpr textual_icon(const char(&unicode_icon)[4]) :
|
||||
_icon{ unicode_icon[0], unicode_icon[1], unicode_icon[2], unicode_icon[3] }
|
||||
{
|
||||
}
|
||||
operator const char* () const
|
||||
{
|
||||
return _icon.data();
|
||||
}
|
||||
private:
|
||||
std::array<char, 5> _icon;
|
||||
};
|
||||
|
||||
inline std::ostream& operator<<(std::ostream& os, const textual_icon& i)
|
||||
{
|
||||
return os << static_cast<const char*>(i);
|
||||
}
|
||||
|
||||
namespace configurations
|
||||
{
|
||||
namespace record
|
||||
{
|
||||
static const char* file_save_mode{ "record.file_save_mode" };
|
||||
static const char* default_path{ "record.default_path" };
|
||||
static const char* compression_mode{ "record.compression" };
|
||||
}
|
||||
namespace update
|
||||
{
|
||||
static const char* allow_rc_firmware{ "update.allow_rc_firmware" };
|
||||
static const char* recommend_updates{ "update.recommend_updates" };
|
||||
static const char* recommend_calibration{ "update.recommend_calibration" };
|
||||
static const char* sw_updates_url{ "update.sw_update_url" };
|
||||
static const char* sw_updates_official_server{ "update.sw_update_official_server" };
|
||||
}
|
||||
namespace calibration
|
||||
{
|
||||
static const char* enable_writing{ "calibration.enable_writing" };
|
||||
}
|
||||
namespace dds
|
||||
{
|
||||
static const char* enable_dds{ "context.dds.enabled" };
|
||||
static const char* domain_id{ "context.dds.domain" };
|
||||
}
|
||||
namespace viewer
|
||||
{
|
||||
static const char* is_3d_view{ "viewer_model.is_3d_view" };
|
||||
static const char* ground_truth_r{ "viewer_model.ground_truth_r" };
|
||||
static const char* target_width_r{ "viewer_model.target_width_r" };
|
||||
static const char* target_height_r{ "viewer_model.target_height_r" };
|
||||
static const char* continue_with_ui_not_aligned{ "viewer_model.continue_with_ui_not_aligned" };
|
||||
static const char* continue_with_current_fw{ "viewer_model.continue_with_current_fw" };
|
||||
static const char* settings_tab{ "viewer_model.settings_tab" };
|
||||
static const char* sdk_version{ "viewer_model.sdk_version" };
|
||||
static const char* last_calib_notice{ "viewer_model.last_calib_notice" };
|
||||
static const char* is_measuring{ "viewer_model.is_measuring" };
|
||||
static const char* output_open{ "viewer_model.output_open" };
|
||||
static const char* dashboard_open{ "viewer_model.dashboard_open" };
|
||||
static const char* search_term{ "viewer_model.search_term" };
|
||||
|
||||
static const char* log_to_console{ "viewer_model.log_to_console" };
|
||||
static const char* log_to_file{ "viewer_model.log_to_file" };
|
||||
static const char* log_filename{ "viewer_model.log_filename" };
|
||||
static const char* log_severity{ "viewer_model.log_severity" };
|
||||
static const char* post_processing{ "viewer_model.post_processing" };
|
||||
static const char* show_map_ruler{ "viewer_model.show_map_ruler" };
|
||||
static const char* show_stream_details{ "viewer_model.show_stream_details" };
|
||||
static const char* metric_system{ "viewer_model.metric_system" };
|
||||
static const char* shading_mode{ "viewer_model.shading_mode" };
|
||||
static const char* commands_xml{ "viewer_model.commands_xml" };
|
||||
static const char* hwlogger_xml{ "viewer_model.hwlogger_xml" };
|
||||
|
||||
static const char* last_ip{ "viewer_model.last_ip" };
|
||||
}
|
||||
namespace window
|
||||
{
|
||||
static const char* is_fullscreen{ "window.is_fullscreen" };
|
||||
static const char* saved_pos{ "window.saved_pos" };
|
||||
static const char* position_x{ "window.position_x" };
|
||||
static const char* position_y{ "window.position_y" };
|
||||
static const char* saved_size{ "window.saved_size" };
|
||||
static const char* width{ "window.width" };
|
||||
static const char* height{ "window.height" };
|
||||
static const char* maximized{ "window.maximized" };
|
||||
static const char* font_size{ "window.font_size" };
|
||||
}
|
||||
namespace performance
|
||||
{
|
||||
static const char* glsl_for_rendering{ "performance.glsl_for_rendering.v2" };
|
||||
static const char* glsl_for_processing{ "performance.glsl_for_processing.v3" };
|
||||
static const char* enable_msaa{ "performance.msaa" };
|
||||
static const char* msaa_samples{ "performance.msaa_samples" };
|
||||
static const char* show_fps{ "performance.show_fps" };
|
||||
static const char* vsync{ "performance.vsync" };
|
||||
static const char* font_oversample{ "performance.font_oversample.v2" };
|
||||
static const char* show_skybox{ "performance.show_skybox" };
|
||||
static const char* occlusion_invalidation{ "performance.occlusion_invalidation" };
|
||||
}
|
||||
namespace ply
|
||||
{
|
||||
static const char* mesh{ "ply.mesh" };
|
||||
static const char* use_normals{ "ply.normals" };
|
||||
static const char* encoding{ "ply.encoding" };
|
||||
|
||||
enum encoding_types
|
||||
{
|
||||
textual = 0,
|
||||
binary = 1
|
||||
};
|
||||
}
|
||||
}
|
||||
|
||||
namespace textual_icons
|
||||
{
|
||||
// A note to a maintainer - preserve order when adding values to avoid duplicates
|
||||
static const textual_icon file_movie{ u8"\uf008" };
|
||||
static const textual_icon times{ u8"\uf00d" };
|
||||
static const textual_icon download{ u8"\uf019" };
|
||||
static const textual_icon refresh{ u8"\uf021" };
|
||||
static const textual_icon lock{ u8"\uf023" };
|
||||
static const textual_icon camera{ u8"\uf030" };
|
||||
static const textual_icon video_camera{ u8"\uf03d" };
|
||||
static const textual_icon edit{ u8"\uf044" };
|
||||
static const textual_icon step_backward{ u8"\uf048" };
|
||||
static const textual_icon play{ u8"\uf04b" };
|
||||
static const textual_icon pause{ u8"\uf04c" };
|
||||
static const textual_icon stop{ u8"\uf04d" };
|
||||
static const textual_icon step_forward{ u8"\uf051" };
|
||||
static const textual_icon plus_circle{ u8"\uf055" };
|
||||
static const textual_icon question_mark{ u8"\uf059" };
|
||||
static const textual_icon info_circle{ u8"\uf05a" };
|
||||
static const textual_icon fix_up{ u8"\uf062" };
|
||||
static const textual_icon minus{ u8"\uf068" };
|
||||
static const textual_icon exclamation_triangle{ u8"\uf071" };
|
||||
static const textual_icon shopping_cart{ u8"\uf07a" };
|
||||
static const textual_icon bar_chart{ u8"\uf080" };
|
||||
static const textual_icon upload{ u8"\uf093" };
|
||||
static const textual_icon square_o{ u8"\uf096" };
|
||||
static const textual_icon unlock{ u8"\uf09c" };
|
||||
static const textual_icon floppy{ u8"\uf0c7" };
|
||||
static const textual_icon square{ u8"\uf0c8" };
|
||||
static const textual_icon bars{ u8"\uf0c9" };
|
||||
static const textual_icon caret_down{ u8"\uf0d7" };
|
||||
static const textual_icon repeat{ u8"\uf0e2" };
|
||||
static const textual_icon circle{ u8"\uf111" };
|
||||
static const textual_icon check_square_o{ u8"\uf14a" };
|
||||
static const textual_icon cubes{ u8"\uf1b3" };
|
||||
static const textual_icon toggle_off{ u8"\uf204" };
|
||||
static const textual_icon toggle_on{ u8"\uf205" };
|
||||
static const textual_icon connectdevelop{ u8"\uf20e" };
|
||||
static const textual_icon usb_type{ u8"\uf287" };
|
||||
static const textual_icon braille{ u8"\uf2a1" };
|
||||
static const textual_icon window_maximize{ u8"\uf2d0" };
|
||||
static const textual_icon window_restore{ u8"\uf2d2" };
|
||||
static const textual_icon grid{ u8"\uf1cb" };
|
||||
static const textual_icon exit{ u8"\uf011" };
|
||||
static const textual_icon see_less{ u8"\uf070" };
|
||||
static const textual_icon dotdotdot{ u8"\uf141" };
|
||||
static const textual_icon link{ u8"\uf08e" };
|
||||
static const textual_icon throphy{ u8"\uF091" };
|
||||
static const textual_icon metadata{ u8"\uF0AE" };
|
||||
static const textual_icon check{ u8"\uF00C" };
|
||||
static const textual_icon mail{ u8"\uF01C" };
|
||||
static const textual_icon cube{ u8"\uf1b2" };
|
||||
static const textual_icon measure{ u8"\uf545" };
|
||||
static const textual_icon wifi{ u8"\uf1eb" };
|
||||
}
|
||||
|
||||
class viewer_model;
|
||||
class ux_window;
|
||||
class subdevice_model;
|
||||
|
||||
class syncer_model
|
||||
{
|
||||
public:
|
||||
syncer_model() :
|
||||
_active(true) {}
|
||||
|
||||
std::shared_ptr<rs2::asynchronous_syncer> create_syncer()
|
||||
{
|
||||
stop();
|
||||
std::lock_guard<std::mutex> lock(_mutex);
|
||||
auto shared_syncer = std::make_shared<rs2::asynchronous_syncer>();
|
||||
|
||||
// This queue stores the output from the syncer, and has to be large enough to deal with
|
||||
// slowdowns on the processing/rendering threads of the Viewer to avoid frame drops. Frame
|
||||
// drops can be pretty noticeable to the user!
|
||||
//
|
||||
// The syncer may also give out frames in bursts. This commonly happens, for example, when
|
||||
// streams have different FPS, and is a known issue. Even with same-FPS streams, the actual
|
||||
// FPS may change depending on a number of variables (e.g., exposure). When FPS is not the
|
||||
// same between the streams, a latency is introduced and bursts from the syncer are the
|
||||
// result.
|
||||
//
|
||||
// Bursts are so fast the other threads will never have a chance to pull them in time. For
|
||||
// example, the syncer output can be the following, all one after the other:
|
||||
//
|
||||
// [Color: timestamp 100 (arrived @ 105), Infrared: timestamp 100 (arrived at 150)]
|
||||
// [Color: timestamp 116 (arrived @ 120)]
|
||||
// [Color: timestamp 132 (arrived @ 145)]
|
||||
//
|
||||
// They are received one at a time & pushed into the syncer, which will wait and keep all of
|
||||
// them inside until a match with Infrared is possible. Once that happens, it will output
|
||||
// everything it has as a burst.
|
||||
//
|
||||
// The queue size must therefore be big enough to deal with expected latency: the more
|
||||
// latency, the bigger the burst.
|
||||
//
|
||||
// Another option is to use an aggregator, similar to the behavior inside the pipeline.
|
||||
// But this still doesn't solve the issue of the bursts: we'll get frame drops in the fast
|
||||
// stream instead of the slow.
|
||||
//
|
||||
rs2::frame_queue q(10);
|
||||
|
||||
_syncers.push_back({ shared_syncer,q });
|
||||
shared_syncer->start([this, q](rs2::frame f)
|
||||
{
|
||||
q.enqueue(f);
|
||||
on_frame();
|
||||
});
|
||||
start();
|
||||
return shared_syncer;
|
||||
}
|
||||
|
||||
void remove_syncer(std::shared_ptr<rs2::asynchronous_syncer> s)
|
||||
{
|
||||
stop();
|
||||
std::lock_guard<std::mutex> lock(_mutex);
|
||||
_syncers.erase(std::remove_if(_syncers.begin(), _syncers.end(),
|
||||
[s](std::pair<std::shared_ptr<rs2::asynchronous_syncer>, rs2::frame_queue> pair)
|
||||
{
|
||||
return pair.first.get() == s.get();
|
||||
}), _syncers.end());
|
||||
start();
|
||||
}
|
||||
|
||||
std::vector<rs2::frameset> try_wait_for_frames()
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(_mutex);
|
||||
|
||||
std::vector<rs2::frameset> result;
|
||||
for (auto&& s = _syncers.begin(); s != _syncers.end() && _active; s++)
|
||||
{
|
||||
rs2::frameset f;
|
||||
if (s->second.try_wait_for_frame(&f, 1))
|
||||
{
|
||||
result.push_back(f);
|
||||
}
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
void stop()
|
||||
{
|
||||
_active.exchange(false);
|
||||
}
|
||||
|
||||
void start()
|
||||
{
|
||||
_active.exchange(true);
|
||||
}
|
||||
|
||||
std::function<void()> on_frame = [] {};
|
||||
private:
|
||||
std::vector<std::pair<std::shared_ptr<rs2::asynchronous_syncer>, rs2::frame_queue>> _syncers;
|
||||
std::mutex _mutex;
|
||||
std::atomic<bool> _active;
|
||||
};
|
||||
|
||||
class device_model
|
||||
{
|
||||
public:
|
||||
typedef std::function<void(std::function<void()> load)> json_loading_func;
|
||||
|
||||
void reset();
|
||||
explicit device_model(device& dev, std::string& error_message, viewer_model& viewer, bool new_device_connected = true, bool allow_remove=true);
|
||||
~device_model();
|
||||
void start_recording(const std::string& path, std::string& error_message);
|
||||
void stop_recording(viewer_model& viewer);
|
||||
void pause_record();
|
||||
void resume_record();
|
||||
|
||||
void refresh_notifications(viewer_model& viewer);
|
||||
bool check_for_bundled_fw_update( const rs2::context & ctx,
|
||||
std::shared_ptr< notifications_model > not_model,
|
||||
bool reset_delay = false );
|
||||
|
||||
int draw_playback_panel(ux_window& window, ImFont* font, viewer_model& view);
|
||||
bool draw_advanced_controls(viewer_model& view, ux_window& window, std::string& error_message);
|
||||
void draw_controls(float panel_width, float panel_height,
|
||||
ux_window& window,
|
||||
std::string& error_message,
|
||||
device_model*& device_to_remove,
|
||||
viewer_model& viewer, float windows_width,
|
||||
std::vector<std::function<void()>>& draw_later,
|
||||
bool load_json_if_streaming = false,
|
||||
json_loading_func json_loading = [](std::function<void()> load) {load(); },
|
||||
bool draw_device_outline = true);
|
||||
void handle_hardware_events(const std::string& serialized_data);
|
||||
void begin_update(std::vector<uint8_t> data,
|
||||
viewer_model& viewer, std::string& error_message);
|
||||
void begin_update_unsigned(viewer_model& viewer, std::string& error_message);
|
||||
void check_for_device_updates(viewer_model& viewer, bool activated_by_user = false);
|
||||
bool disable_record_button_logic(bool is_streaming, bool is_playback_device);
|
||||
std::string get_record_button_hover_text(bool is_streaming);
|
||||
|
||||
|
||||
std::shared_ptr< atomic_objects_in_frame > get_detected_objects() const { return _detected_objects; }
|
||||
|
||||
std::vector<std::shared_ptr<subdevice_model>> subdevices;
|
||||
std::shared_ptr<syncer_model> syncer;
|
||||
std::shared_ptr<rs2::asynchronous_syncer> dev_syncer;
|
||||
bool is_streaming() const;
|
||||
bool metadata_supported = false;
|
||||
bool get_curr_advanced_controls = true;
|
||||
device dev;
|
||||
std::string id;
|
||||
bool is_recording = false;
|
||||
int seek_pos = 0;
|
||||
int playback_speed_index = 2;
|
||||
bool _playback_repeat = true;
|
||||
bool _should_replay = false;
|
||||
bool show_device_info = false;
|
||||
bool _allow_remove = true;
|
||||
bool show_depth_only = false;
|
||||
bool show_stream_selection = true;
|
||||
std::vector<std::pair<std::string, std::string>> infos;
|
||||
std::vector<std::string> restarting_device_info;
|
||||
std::set<std::string> advanced_mode_settings_file_names;
|
||||
std::string selected_file_preset;
|
||||
|
||||
std::vector<std::shared_ptr<notification_model>> related_notifications;
|
||||
|
||||
private:
|
||||
// This class is in charge of camera accuracy health window parameters,
|
||||
// Needed as a member for reseting the window memory on device disconnection.
|
||||
|
||||
|
||||
void draw_info_icon(ux_window& window, ImFont* font, const ImVec2& size);
|
||||
int draw_seek_bar();
|
||||
int draw_playback_controls(ux_window& window, ImFont* font, viewer_model& view);
|
||||
advanced_mode_control amc;
|
||||
std::string pretty_time(std::chrono::nanoseconds duration);
|
||||
float draw_device_panel(float panel_width,
|
||||
ux_window& window,
|
||||
std::string& error_message,
|
||||
viewer_model& viewer);
|
||||
void play_defaults(viewer_model& view);
|
||||
float draw_preset_panel(float panel_width,
|
||||
ux_window& window,
|
||||
std::string& error_message,
|
||||
viewer_model& viewer,
|
||||
bool update_read_only_options,
|
||||
bool load_json_if_streaming,
|
||||
json_loading_func json_loading);
|
||||
bool prompt_toggle_advanced_mode(bool enable_advanced_mode, const std::string& message_text,
|
||||
std::vector<std::string>& restarting_device_info,
|
||||
viewer_model& view,
|
||||
ux_window& window,
|
||||
const std::string& error_message);
|
||||
|
||||
void load_viewer_configurations(const std::string& json_str);
|
||||
void save_viewer_configurations(std::ofstream& outfile, rsutils::json& j);
|
||||
void handle_online_sw_update(
|
||||
std::shared_ptr< notifications_model > nm,
|
||||
std::shared_ptr< sw_update::dev_updates_profile::update_profile > update_profile,
|
||||
bool reset_delay = false );
|
||||
|
||||
bool handle_online_fw_update(
|
||||
const context & ctx,
|
||||
std::shared_ptr< notifications_model > nm,
|
||||
std::shared_ptr< sw_update::dev_updates_profile::update_profile > update_profile,
|
||||
bool reset_delay = false );
|
||||
|
||||
void draw_device_panel_auto_calib(viewer_model& viewer, bool& something_to_show, std::string& error_message);
|
||||
bool draw_device_panel_auto_calib_d400(viewer_model& viewer, bool& something_to_show, std::string& error_message);
|
||||
bool draw_device_panel_auto_calib_d500(viewer_model& viewer, bool& something_to_show, std::string& error_message);
|
||||
|
||||
std::shared_ptr<recorder> _recorder;
|
||||
std::vector<std::shared_ptr<subdevice_model>> live_subdevices;
|
||||
rsutils::time::periodic_timer _update_readonly_options_timer;
|
||||
bool pause_required = false;
|
||||
std::shared_ptr< atomic_objects_in_frame > _detected_objects;
|
||||
std::shared_ptr<updates_model> _updates;
|
||||
std::shared_ptr<sw_update::dev_updates_profile::update_profile >_updates_profile;
|
||||
calibration_model _calib_model;
|
||||
dds_model _dds_model;
|
||||
};
|
||||
|
||||
std::pair<std::string, std::string> get_device_name(const device& dev);
|
||||
|
||||
std::vector<std::pair<std::string, std::string>> get_devices_names(const device_list& list);
|
||||
|
||||
class device_changes
|
||||
{
|
||||
public:
|
||||
explicit device_changes(rs2::context& ctx);
|
||||
bool try_get_next_changes(event_information& removed_and_connected);
|
||||
private:
|
||||
void add_changes(const event_information& c);
|
||||
std::queue<event_information> _changes;
|
||||
std::mutex _mtx;
|
||||
};
|
||||
}
|
||||
14
librealsense-r-256/common/float2.h
Normal file
14
librealsense-r-256/common/float2.h
Normal file
@@ -0,0 +1,14 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
#include <rsutils/number/float3.h>
|
||||
|
||||
|
||||
namespace rs2 {
|
||||
|
||||
|
||||
using rsutils::number::float2;
|
||||
|
||||
|
||||
} // namespace rs2
|
||||
14
librealsense-r-256/common/float3.h
Normal file
14
librealsense-r-256/common/float3.h
Normal file
@@ -0,0 +1,14 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2024 Intel Corporation. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
#include <rsutils/number/float3.h>
|
||||
|
||||
|
||||
namespace rs2 {
|
||||
|
||||
|
||||
using rsutils::number::float3;
|
||||
|
||||
|
||||
} // namespace rs2
|
||||
15
librealsense-r-256/common/float4.h
Normal file
15
librealsense-r-256/common/float4.h
Normal file
@@ -0,0 +1,15 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2021 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace rs2 {
|
||||
|
||||
|
||||
struct float4
|
||||
{
|
||||
float x, y, z, w;
|
||||
};
|
||||
|
||||
|
||||
}
|
||||
683
librealsense-r-256/common/fw-update-helper.cpp
Normal file
683
librealsense-r-256/common/fw-update-helper.cpp
Normal file
@@ -0,0 +1,683 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include "fw-update-helper.h"
|
||||
#include "model-views.h"
|
||||
#include "viewer.h"
|
||||
#include <realsense_imgui.h>
|
||||
#include "ux-window.h"
|
||||
|
||||
#include <rsutils/os/special-folder.h>
|
||||
#include "os.h"
|
||||
|
||||
#include <rsutils/easylogging/easyloggingpp.h>
|
||||
#include <map>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
#include <thread>
|
||||
#include <condition_variable>
|
||||
|
||||
#ifdef INTERNAL_FW
|
||||
#include "common/fw/D4XX_FW_Image.h"
|
||||
#else
|
||||
#define FW_D4XX_FW_IMAGE_VERSION ""
|
||||
const char* fw_get_D4XX_FW_Image(int) { return NULL; }
|
||||
|
||||
|
||||
#endif // INTERNAL_FW
|
||||
|
||||
constexpr const char* recommended_fw_url = "https://dev.intelrealsense.com/docs/firmware-updates";
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
enum firmware_update_ui_state
|
||||
{
|
||||
RS2_FWU_STATE_INITIAL_PROMPT = 0,
|
||||
RS2_FWU_STATE_IN_PROGRESS = 1,
|
||||
RS2_FWU_STATE_COMPLETE = 2,
|
||||
RS2_FWU_STATE_FAILED = 3,
|
||||
};
|
||||
|
||||
bool is_recommended_fw_available(const std::string& product_line, const std::string& pid)
|
||||
{
|
||||
auto pl = parse_product_line(product_line);
|
||||
auto fv = get_available_firmware_version(pl, pid);
|
||||
return !(fv == "");
|
||||
}
|
||||
|
||||
int parse_product_line(const std::string& product_line)
|
||||
{
|
||||
if (product_line == "D400") return RS2_PRODUCT_LINE_D400;
|
||||
else return -1;
|
||||
}
|
||||
|
||||
std::string get_available_firmware_version(int product_line, const std::string& pid)
|
||||
{
|
||||
if (product_line == RS2_PRODUCT_LINE_D400) return FW_D4XX_FW_IMAGE_VERSION;
|
||||
else return "";
|
||||
}
|
||||
|
||||
std::vector< uint8_t > get_default_fw_image( int product_line, const std::string & pid )
|
||||
{
|
||||
std::vector< uint8_t > image;
|
||||
|
||||
switch( product_line )
|
||||
{
|
||||
case RS2_PRODUCT_LINE_D400:
|
||||
{
|
||||
bool allow_rc_firmware = config_file::instance().get_or_default( configurations::update::allow_rc_firmware, false );
|
||||
if( strlen( FW_D4XX_FW_IMAGE_VERSION ) && ! allow_rc_firmware )
|
||||
{
|
||||
int size = 0;
|
||||
auto hex = fw_get_D4XX_FW_Image( size );
|
||||
image = std::vector< uint8_t >( hex, hex + size );
|
||||
}
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return image;
|
||||
}
|
||||
|
||||
bool is_upgradeable(const std::string& curr, const std::string& available)
|
||||
{
|
||||
if (curr == "" || available == "") return false;
|
||||
return rsutils::version( curr ) < rsutils::version( available );
|
||||
}
|
||||
|
||||
bool firmware_update_manager::check_for(
|
||||
std::function<bool()> action, std::function<void()> cleanup,
|
||||
std::chrono::system_clock::duration delta)
|
||||
{
|
||||
using namespace std;
|
||||
using namespace std::chrono;
|
||||
|
||||
auto start = system_clock::now();
|
||||
auto now = system_clock::now();
|
||||
do
|
||||
{
|
||||
try
|
||||
{
|
||||
|
||||
if (action()) return true;
|
||||
}
|
||||
catch (const error& e)
|
||||
{
|
||||
fail(error_to_string(e));
|
||||
cleanup();
|
||||
return false;
|
||||
}
|
||||
catch (const std::exception& ex)
|
||||
{
|
||||
fail(ex.what());
|
||||
cleanup();
|
||||
return false;
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
fail("Unknown error during update.\nPlease reconnect the camera to exit recovery mode");
|
||||
cleanup();
|
||||
return false;
|
||||
}
|
||||
|
||||
now = system_clock::now();
|
||||
this_thread::sleep_for(milliseconds(100));
|
||||
} while (now - start < delta);
|
||||
return false;
|
||||
}
|
||||
|
||||
void firmware_update_manager::process_mipi()
|
||||
{
|
||||
bool is_mipi_recovery = !(strcmp(_dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID), "BBCD"));
|
||||
if (!_is_signed)
|
||||
{
|
||||
fail("Signed FW update for MIPI device - This FW file is not signed ");
|
||||
return;
|
||||
}
|
||||
if (!is_mipi_recovery)
|
||||
{
|
||||
auto dev_updatable = _dev.as<updatable>();
|
||||
if(!(dev_updatable && dev_updatable.check_firmware_compatibility(_fw)))
|
||||
{
|
||||
std::stringstream ss;
|
||||
ss << "The firmware version is not compatible with ";
|
||||
ss << _dev.get_info(RS2_CAMERA_INFO_NAME) << std::endl;
|
||||
fail(ss.str());
|
||||
return;
|
||||
}
|
||||
}
|
||||
log("Burning Signed Firmware on MIPI device");
|
||||
if (!is_mipi_recovery)
|
||||
{
|
||||
// Enter DFU mode
|
||||
auto device_debug = _dev.as<rs2::debug_protocol>();
|
||||
uint32_t dfu_opcode = 0x1e;
|
||||
device_debug.build_command(dfu_opcode, 1);
|
||||
}
|
||||
_progress = 30;
|
||||
rs2_camera_info _dfu_port_info = (is_mipi_recovery)?(RS2_CAMERA_INFO_PHYSICAL_PORT):(RS2_CAMERA_INFO_DFU_DEVICE_PATH);
|
||||
// Write signed firmware to appropriate file descriptor
|
||||
std::ofstream fw_path_in_device(_dev.get_info(_dfu_port_info), std::ios::binary);
|
||||
if (fw_path_in_device)
|
||||
{
|
||||
fw_path_in_device.write(reinterpret_cast<const char*>(_fw.data()), _fw.size());
|
||||
}
|
||||
else
|
||||
{
|
||||
fail("Firmware Update failed - wrong path or permissions missing");
|
||||
return;
|
||||
}
|
||||
log("FW update process completed successfully.");
|
||||
LOG_INFO("FW update process completed successfully.");
|
||||
fw_path_in_device.close();
|
||||
|
||||
_progress = 100;
|
||||
if (is_mipi_recovery)
|
||||
{
|
||||
log("For GMSL MIPI device please reboot, or reload d4xx driver\n"\
|
||||
"sudo rmmod d4xx && sudo modprobe d4xx\n"\
|
||||
"and restart the realsense-viewer");
|
||||
LOG_INFO("For GMSL MIPI device please reboot, or reload d4xx driver\n"\
|
||||
"sudo rmmod d4xx && sudo modprobe d4xx\n"\
|
||||
"and restart the realsense-viewer");
|
||||
}
|
||||
_done = true;
|
||||
// Restart the device to reconstruct with the new version information
|
||||
_dev.hardware_reset();
|
||||
}
|
||||
|
||||
void firmware_update_manager::process_flow(
|
||||
std::function<void()> cleanup,
|
||||
invoker invoke)
|
||||
{
|
||||
// if device is MIPI device, and fw is signed - using mipi specific procedure
|
||||
if (_is_signed
|
||||
&& (!strcmp(_dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID), "ABCD")
|
||||
|| !strcmp(_dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID), "BBCD")
|
||||
|| !strcmp(_dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID), "ABCE"))
|
||||
)
|
||||
{
|
||||
process_mipi();
|
||||
return;
|
||||
}
|
||||
|
||||
std::string serial = "";
|
||||
if (_dev.supports(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID))
|
||||
serial = _dev.get_info(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID);
|
||||
else
|
||||
serial = _dev.query_sensors().front().get_info(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID);
|
||||
|
||||
// Clear FW update related notification to avoid dismissing the notification on ~device_model()
|
||||
// We want the notification alive during the whole process.
|
||||
_model.related_notifications.erase(
|
||||
std::remove_if( _model.related_notifications.begin(),
|
||||
_model.related_notifications.end(),
|
||||
[]( std::shared_ptr< notification_model > n ) {
|
||||
return n->is< fw_update_notification_model >();
|
||||
} ) , end(_model.related_notifications));
|
||||
|
||||
for (auto&& n : _model.related_notifications)
|
||||
{
|
||||
if (n->is< fw_update_notification_model >()
|
||||
|| n->is< sw_recommended_update_alert_model >())
|
||||
n->dismiss(false);
|
||||
}
|
||||
|
||||
_progress = 5;
|
||||
|
||||
int next_progress = 10;
|
||||
|
||||
update_device dfu{};
|
||||
|
||||
if (auto upd = _dev.as<updatable>())
|
||||
{
|
||||
// checking firmware version compatibility with device
|
||||
if (_is_signed)
|
||||
{
|
||||
if (!upd.check_firmware_compatibility(_fw))
|
||||
{
|
||||
std::stringstream ss;
|
||||
ss << "The firmware version is not compatible with ";
|
||||
ss << _dev.get_info(RS2_CAMERA_INFO_NAME) << std::endl;
|
||||
fail(ss.str());
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
log( "Trying to back-up camera flash memory" );
|
||||
|
||||
std::string log_backup_status;
|
||||
try
|
||||
{
|
||||
auto flash = upd.create_flash_backup( [&]( const float progress )
|
||||
{
|
||||
_progress = ( ( ceil( progress * 5 ) / 5 ) * ( 30 - next_progress ) ) + next_progress;
|
||||
} );
|
||||
|
||||
// Not all cameras supports this feature
|
||||
if( !flash.empty() )
|
||||
{
|
||||
auto temp = rsutils::os::get_special_folder( rsutils::os::special_folder::app_data );
|
||||
temp += serial + "." + get_timestamped_file_name() + ".bin";
|
||||
|
||||
{
|
||||
std::ofstream file( temp.c_str(), std::ios::binary );
|
||||
file.write( (const char*)flash.data(), flash.size() );
|
||||
log_backup_status = "Backup completed and saved as '" + temp + "'";
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
log_backup_status = "Backup flash is not supported";
|
||||
}
|
||||
}
|
||||
catch( const std::exception& e )
|
||||
{
|
||||
if( auto not_model_protected = get_protected_notification_model() )
|
||||
{
|
||||
log_backup_status = "WARNING: backup failed; continuing without it...";
|
||||
not_model_protected->output.add_log( RS2_LOG_SEVERITY_WARN,
|
||||
__FILE__,
|
||||
__LINE__,
|
||||
log_backup_status + ", Error: " + e.what() );
|
||||
}
|
||||
}
|
||||
catch( ... )
|
||||
{
|
||||
if( auto not_model_protected = get_protected_notification_model() )
|
||||
{
|
||||
log_backup_status = "WARNING: backup failed; continuing without it...";
|
||||
not_model_protected->add_log( log_backup_status + ", Unknown error occurred" );
|
||||
}
|
||||
}
|
||||
|
||||
if ( !log_backup_status.empty() )
|
||||
log(log_backup_status);
|
||||
|
||||
next_progress = static_cast<int>(_progress) + 10;
|
||||
|
||||
if (_is_signed)
|
||||
{
|
||||
log("Requesting to switch to recovery mode");
|
||||
|
||||
// in order to update device to DFU state, it will be disconnected then switches to DFU state
|
||||
// if querying devices is called while device still switching to DFU state, an exception will be thrown
|
||||
// to prevent that, a blocking is added to make sure device is updated before continue to next step of querying device
|
||||
upd.enter_update_state();
|
||||
|
||||
if (!check_for([this, serial, &dfu]() {
|
||||
auto devs = _ctx.query_devices();
|
||||
|
||||
for (uint32_t j = 0; j < devs.size(); j++)
|
||||
{
|
||||
try
|
||||
{
|
||||
auto d = devs[j];
|
||||
if (d.is<update_device>())
|
||||
{
|
||||
if (d.supports(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID))
|
||||
{
|
||||
if (serial == d.get_info(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID))
|
||||
{
|
||||
log( "DFU device '" + serial + "' found" );
|
||||
dfu = d;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
catch (std::exception &e) {
|
||||
if (auto not_model_protected = get_protected_notification_model())
|
||||
{
|
||||
not_model_protected->output.add_log(RS2_LOG_SEVERITY_WARN,
|
||||
__FILE__,
|
||||
__LINE__,
|
||||
rsutils::string::from() << "Exception caught in FW Update process-flow: " << e.what() << "; Retrying...");
|
||||
}
|
||||
}
|
||||
catch (...) {}
|
||||
}
|
||||
|
||||
return false;
|
||||
}, cleanup, std::chrono::seconds(60)))
|
||||
{
|
||||
fail("Recovery device did not connect in time!");
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
dfu = _dev.as<update_device>();
|
||||
}
|
||||
|
||||
if (dfu)
|
||||
{
|
||||
_progress = float(next_progress);
|
||||
|
||||
log("Recovery device connected, starting update..\n"
|
||||
"Internal write is in progress\n"
|
||||
"Please DO NOT DISCONNECT the camera");
|
||||
|
||||
dfu.update(_fw, [&](const float progress)
|
||||
{
|
||||
_progress = ((ceil(progress * 10) / 10 * (90 - next_progress)) + next_progress);
|
||||
});
|
||||
|
||||
log( "Firmware Download completed, await DFU transition event" );
|
||||
std::this_thread::sleep_for( std::chrono::seconds( 3 ) );
|
||||
}
|
||||
else
|
||||
{
|
||||
auto upd = _dev.as<updatable>();
|
||||
upd.update_unsigned(_fw, [&](const float progress)
|
||||
{
|
||||
_progress = (ceil(progress * 10) / 10 * (90 - next_progress)) + next_progress;
|
||||
});
|
||||
log("Firmware Update completed, waiting for device to reconnect");
|
||||
}
|
||||
|
||||
if (!check_for([this, serial]() {
|
||||
auto devs = _ctx.query_devices();
|
||||
|
||||
for (uint32_t j = 0; j < devs.size(); j++)
|
||||
{
|
||||
try
|
||||
{
|
||||
auto d = devs[j];
|
||||
|
||||
if (d.query_sensors().size() && d.query_sensors().front().supports(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID))
|
||||
{
|
||||
auto s = d.query_sensors().front().get_info(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID);
|
||||
if (s == serial)
|
||||
{
|
||||
log("Discovered connection of the original device");
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
catch (...) {}
|
||||
}
|
||||
|
||||
return false;
|
||||
}, cleanup, std::chrono::seconds(60)))
|
||||
{
|
||||
fail("Original device did not reconnect in time!");
|
||||
return;
|
||||
}
|
||||
|
||||
log( "Device reconnected successfully!\n"
|
||||
"FW update process completed successfully" );
|
||||
|
||||
_progress = 100;
|
||||
|
||||
_done = true;
|
||||
}
|
||||
|
||||
void fw_update_notification_model::draw_content(ux_window& win, int x, int y, float t, std::string& error_message)
|
||||
{
|
||||
using namespace std;
|
||||
using namespace chrono;
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 9), float(y + 4) });
|
||||
|
||||
ImVec4 shadow{ 1.f, 1.f, 1.f, 0.1f };
|
||||
ImGui::GetWindowDrawList()->AddRectFilled({ float(x), float(y) },
|
||||
{ float(x + width), float(y + 25) }, ImColor(shadow));
|
||||
|
||||
if (update_state != RS2_FWU_STATE_COMPLETE)
|
||||
{
|
||||
ImGui::Text("Firmware Update Recommended!");
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 5), float(y + 27) });
|
||||
|
||||
draw_text(get_title().c_str(), x, y, height - 50);
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 9), float(y + height - 67) });
|
||||
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, alpha(light_grey, 1.f - t));
|
||||
|
||||
if (update_state == RS2_FWU_STATE_INITIAL_PROMPT)
|
||||
ImGui::Text("Firmware updates offer critical bug fixes and\nunlock new camera capabilities.");
|
||||
else
|
||||
ImGui::Text("Firmware update is underway...\nPlease do not disconnect the device");
|
||||
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
else
|
||||
{
|
||||
//ImGui::PushStyleColor(ImGuiCol_Text, alpha(light_blue, 1.f - t));
|
||||
ImGui::Text("Update Completed");
|
||||
//ImGui::PopStyleColor();
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 10), float(y + 35) });
|
||||
ImGui::PushFont(win.get_large_font());
|
||||
std::string txt = rsutils::string::from() << textual_icons::throphy;
|
||||
ImGui::Text("%s", txt.c_str());
|
||||
ImGui::PopFont();
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 40), float(y + 35) });
|
||||
ImGui::Text("Camera Firmware Updated Successfully");
|
||||
}
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
|
||||
|
||||
const auto bar_width = width - 115;
|
||||
|
||||
if (update_manager)
|
||||
{
|
||||
if (update_state == RS2_FWU_STATE_INITIAL_PROMPT)
|
||||
{
|
||||
auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
|
||||
ImGui::PushStyleColor(ImGuiCol_Button, saturate(sensor_header_light_blue, sat));
|
||||
ImGui::PushStyleColor(ImGuiCol_ButtonHovered, saturate(sensor_header_light_blue, 1.5f));
|
||||
std::string button_name = rsutils::string::from() << "Install" << "##fwupdate" << index;
|
||||
|
||||
if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f }) || update_manager->started())
|
||||
{
|
||||
// stopping stream before starting fw update
|
||||
auto fw_update_manager = dynamic_cast<firmware_update_manager*>(update_manager.get());
|
||||
if( ! fw_update_manager )
|
||||
throw std::runtime_error( "Cannot convert firmware_update_manager" );
|
||||
std::for_each(fw_update_manager->get_device_model().subdevices.begin(),
|
||||
fw_update_manager->get_device_model().subdevices.end(),
|
||||
[&](const std::shared_ptr<subdevice_model>& sm)
|
||||
{
|
||||
if (sm->streaming)
|
||||
{
|
||||
try
|
||||
{
|
||||
sm->stop(fw_update_manager->get_protected_notification_model());
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
// avoiding exception that can be sent by stop method
|
||||
// this could happen if the sensor is not streaming and the stop method is called - for example
|
||||
}
|
||||
}
|
||||
});
|
||||
|
||||
auto _this = shared_from_this();
|
||||
auto invoke = [_this](std::function<void()> action) {
|
||||
_this->invoke(action);
|
||||
};
|
||||
|
||||
if (!update_manager->started())
|
||||
update_manager->start(invoke);
|
||||
|
||||
update_state = RS2_FWU_STATE_IN_PROGRESS;
|
||||
enable_dismiss = false;
|
||||
_progress_bar.last_progress_time = system_clock::now();
|
||||
}
|
||||
ImGui::PopStyleColor(2);
|
||||
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
RsImGui::CustomTooltip("%s", "New firmware will be flashed to the device");
|
||||
}
|
||||
}
|
||||
else if (update_state == RS2_FWU_STATE_IN_PROGRESS)
|
||||
{
|
||||
if (update_manager->done())
|
||||
{
|
||||
update_state = RS2_FWU_STATE_COMPLETE;
|
||||
pinned = false;
|
||||
_progress_bar.last_progress_time = last_interacted = system_clock::now();
|
||||
}
|
||||
|
||||
if (!expanded)
|
||||
{
|
||||
if (update_manager->failed())
|
||||
{
|
||||
update_manager->check_error(error_message);
|
||||
update_state = RS2_FWU_STATE_FAILED;
|
||||
pinned = false;
|
||||
dismiss(false);
|
||||
}
|
||||
|
||||
draw_progress_bar(win, bar_width);
|
||||
|
||||
ImGui::SetCursorScreenPos({ float(x + width - 105), float(y + height - 25) });
|
||||
|
||||
string id = rsutils::string::from() << "Expand" << "##" << index;
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, light_grey);
|
||||
if (ImGui::Button(id.c_str(), { 100, 20 }))
|
||||
{
|
||||
expanded = true;
|
||||
}
|
||||
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
std::string button_name = rsutils::string::from() << "Learn More..." << "##" << index;
|
||||
|
||||
if (ImGui::Button(button_name.c_str(), { float(bar_width), 20 }))
|
||||
{
|
||||
open_url(recommended_fw_url);
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
win.link_hovered();
|
||||
RsImGui::CustomTooltip("%s", "Internet connection required");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void fw_update_notification_model::draw_expanded(ux_window& win, std::string& error_message)
|
||||
{
|
||||
if (update_manager->started() && update_state == RS2_FWU_STATE_INITIAL_PROMPT)
|
||||
update_state = RS2_FWU_STATE_IN_PROGRESS;
|
||||
|
||||
auto flags = ImGuiWindowFlags_NoResize |
|
||||
ImGuiWindowFlags_NoMove |
|
||||
ImGuiWindowFlags_NoCollapse;
|
||||
|
||||
ImGui::PushStyleColor(ImGuiCol_WindowBg, { 0, 0, 0, 0 });
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, light_grey);
|
||||
ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, white);
|
||||
ImGui::PushStyleColor(ImGuiCol_PopupBg, sensor_bg);
|
||||
|
||||
ImGui::PushStyleVar(ImGuiStyleVar_WindowMinSize, ImVec2(500, 100));
|
||||
ImGui::PushStyleVar(ImGuiStyleVar_WindowPadding, ImVec2(5, 5));
|
||||
ImGui::PushStyleVar(ImGuiStyleVar_WindowRounding, 0);
|
||||
|
||||
std::string title = "Firmware Update";
|
||||
if (update_manager->failed()) title += " Failed";
|
||||
|
||||
ImGui::OpenPopup(title.c_str());
|
||||
if (ImGui::BeginPopupModal(title.c_str(), nullptr, flags))
|
||||
{
|
||||
ImGui::SetCursorPosX(200);
|
||||
std::string progress_str = rsutils::string::from() << "Progress: " << update_manager->get_progress() << "%";
|
||||
ImGui::Text("%s", progress_str.c_str());
|
||||
|
||||
ImGui::SetCursorPosX(5);
|
||||
|
||||
draw_progress_bar(win, 490);
|
||||
|
||||
ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, regular_blue);
|
||||
auto s = update_manager->get_log();
|
||||
ImGui::InputTextMultiline("##fw_update_log", const_cast<char*>(s.c_str()),
|
||||
s.size() + 1, { 490,100 }, ImGuiInputTextFlags_AutoSelectAll | ImGuiInputTextFlags_ReadOnly);
|
||||
ImGui::PopStyleColor();
|
||||
|
||||
ImGui::SetCursorPosX(190);
|
||||
if (visible || update_manager->done() || update_manager->failed())
|
||||
{
|
||||
if (ImGui::Button("OK", ImVec2(120, 0)))
|
||||
{
|
||||
if (update_manager->done() || update_manager->failed())
|
||||
{
|
||||
update_state = RS2_FWU_STATE_FAILED;
|
||||
pinned = false;
|
||||
dismiss(false);
|
||||
}
|
||||
expanded = false;
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ImGui::PushStyleColor(ImGuiCol_Button, transparent);
|
||||
ImGui::PushStyleColor(ImGuiCol_ButtonActive, transparent);
|
||||
ImGui::PushStyleColor(ImGuiCol_ButtonHovered, transparent);
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, transparent);
|
||||
ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, transparent);
|
||||
ImGui::Button("OK", ImVec2(120, 0));
|
||||
ImGui::PopStyleColor(5);
|
||||
}
|
||||
|
||||
ImGui::EndPopup();
|
||||
}
|
||||
|
||||
ImGui::PopStyleVar(3);
|
||||
ImGui::PopStyleColor(4);
|
||||
|
||||
error_message = "";
|
||||
}
|
||||
|
||||
int fw_update_notification_model::calc_height()
|
||||
{
|
||||
if (update_state != RS2_FWU_STATE_COMPLETE) return 150;
|
||||
else return 65;
|
||||
}
|
||||
|
||||
void fw_update_notification_model::set_color_scheme(float t) const
|
||||
{
|
||||
notification_model::set_color_scheme(t);
|
||||
|
||||
ImGui::PopStyleColor(1);
|
||||
|
||||
ImVec4 c;
|
||||
|
||||
if (update_state == RS2_FWU_STATE_COMPLETE)
|
||||
{
|
||||
c = alpha(saturate(light_blue, 0.7f), 1 - t);
|
||||
ImGui::PushStyleColor(ImGuiCol_WindowBg, c);
|
||||
}
|
||||
else
|
||||
{
|
||||
c = alpha(sensor_bg, 1 - t);
|
||||
ImGui::PushStyleColor(ImGuiCol_WindowBg, c);
|
||||
}
|
||||
}
|
||||
|
||||
fw_update_notification_model::fw_update_notification_model(std::string name,
|
||||
std::shared_ptr<firmware_update_manager> manager, bool exp)
|
||||
: process_notification_model(manager)
|
||||
{
|
||||
enable_expand = false;
|
||||
expanded = exp;
|
||||
if (expanded) visible = false;
|
||||
|
||||
message = name;
|
||||
this->severity = RS2_LOG_SEVERITY_INFO;
|
||||
this->category = RS2_NOTIFICATION_CATEGORY_FIRMWARE_UPDATE_RECOMMENDED;
|
||||
pinned = true;
|
||||
forced = true;
|
||||
}
|
||||
}
|
||||
57
librealsense-r-256/common/fw-update-helper.h
Normal file
57
librealsense-r-256/common/fw-update-helper.h
Normal file
@@ -0,0 +1,57 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "notifications.h"
|
||||
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
class viewer_model;
|
||||
|
||||
int parse_product_line(const std::string& product_line);
|
||||
std::string get_available_firmware_version(int product_line, const std::string& pid);
|
||||
|
||||
std::vector<uint8_t> get_default_fw_image(int product_line, const std::string& pid);
|
||||
bool is_upgradeable(const std::string& curr, const std::string& available);
|
||||
bool is_recommended_fw_available(const std::string& product_line, const std::string& pid);
|
||||
|
||||
class firmware_update_manager : public process_manager
|
||||
{
|
||||
public:
|
||||
firmware_update_manager(std::shared_ptr<notifications_model> not_model, device_model& model, device dev, context ctx, std::vector<uint8_t> fw, bool is_signed)
|
||||
: process_manager("Firmware Update"), _not_model(not_model), _model(model),
|
||||
_fw(fw), _is_signed(is_signed), _dev(dev), _ctx(ctx) {}
|
||||
|
||||
const device_model& get_device_model() const { return _model; }
|
||||
std::shared_ptr<notifications_model> get_protected_notification_model() { return _not_model.lock(); };
|
||||
|
||||
protected:
|
||||
void process_flow(std::function<void()> cleanup,
|
||||
invoker invoke) override;
|
||||
void process_mipi();
|
||||
bool check_for(
|
||||
std::function<bool()> action, std::function<void()> cleanup,
|
||||
std::chrono::system_clock::duration delta);
|
||||
|
||||
std::weak_ptr<notifications_model> _not_model;
|
||||
device _dev;
|
||||
context _ctx;
|
||||
std::vector<uint8_t> _fw;
|
||||
bool _is_signed;
|
||||
device_model& _model;
|
||||
bool _is_d500_device = false;
|
||||
};
|
||||
|
||||
struct fw_update_notification_model : public process_notification_model
|
||||
{
|
||||
fw_update_notification_model(std::string name,
|
||||
std::shared_ptr<firmware_update_manager> manager, bool expaned);
|
||||
|
||||
void set_color_scheme(float t) const override;
|
||||
void draw_content(ux_window& win, int x, int y, float t, std::string& error_message) override;
|
||||
void draw_expanded(ux_window& win, std::string& error_message) override;
|
||||
int calc_height() override;
|
||||
};
|
||||
}
|
||||
75
librealsense-r-256/common/fw/CMakeLists.txt
Normal file
75
librealsense-r-256/common/fw/CMakeLists.txt
Normal file
@@ -0,0 +1,75 @@
|
||||
# License: Apache 2.0. See LICENSE file in root directory.
|
||||
# Copyright(c) 2019-2024 Intel Corporation. All Rights Reserved.
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
|
||||
project(fw)
|
||||
|
||||
file(READ "firmware-version.h" ver)
|
||||
|
||||
message(STATUS "Fetching recommended firmwares:")
|
||||
|
||||
set(REALSENSE_FIRMWARE_URL "https://librealsense.intel.com" CACHE STRING
|
||||
"URL to download firmware binaries from")
|
||||
|
||||
string(REGEX MATCH "D4XX_RECOMMENDED_FIRMWARE_VERSION \"([0-9]+.[0-9]+.[0-9]+.[0-9]+)\"" _ ${ver})
|
||||
set(D4XX_FW_VERSION ${CMAKE_MATCH_1})
|
||||
#message(STATUS "D4XX_FW_VERSION: ${D4XX_FW_VERSION}")
|
||||
set(D4XX_FW_SHA1 e7a67224fd0bd823df03dc7f1135a59db93746fd)
|
||||
set(D4XX_FW_URL "${REALSENSE_FIRMWARE_URL}/Releases/RS4xx/FW")
|
||||
|
||||
add_library(${PROJECT_NAME} STATIC empty.c)
|
||||
|
||||
# disable link time optimization for fw by adding -fno-lto to disable -flto flag
|
||||
# jammy debian has build errors without it
|
||||
if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
|
||||
message(STATUS "disable link time optimization for fw project")
|
||||
target_compile_options(${PROJECT_NAME} PRIVATE -fno-lto)
|
||||
endif()
|
||||
|
||||
if (MSVC)
|
||||
# lib.exe can't handle multiple .res files, so include them in one.
|
||||
# even then, the linker won't grab a .res out of a .lib object, so it needs to be explicitly listed
|
||||
# and to find the name of the .res file (across cmake generators) we need to create our own rule. :(
|
||||
add_custom_command(TARGET ${PROJECT_NAME} BYPRODUCTS ${PROJECT_NAME}.res COMMAND ${CMAKE_RC_COMPILER} ${CMAKE_RC_FLAGS} /I . /fo "${PROJECT_NAME}.res" "${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}.rc")
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.res")
|
||||
endif()
|
||||
|
||||
target_include_directories(${PROJECT_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
|
||||
set_target_properties (${PROJECT_NAME} PROPERTIES FOLDER Resources)
|
||||
|
||||
function(target_binary url version sha1 symbol ext)
|
||||
set(binary "${CMAKE_CURRENT_BINARY_DIR}/${symbol}-${version}${ext}")
|
||||
message(STATUS "... ${url}/${symbol}-${version}${ext}")
|
||||
file(DOWNLOAD "${url}/${symbol}-${version}${ext}" "${binary}"
|
||||
EXPECTED_HASH SHA1=${sha1}
|
||||
STATUS status)
|
||||
list(GET status 0 error_code)
|
||||
if (NOT ${error_code} EQUAL 0)
|
||||
message(FATAL_ERROR "FAILED with status ${status}")
|
||||
else()
|
||||
#message(STATUS "Download firmware ${status} for ${symbol}-${version}${ext}")
|
||||
endif()
|
||||
string(TOUPPER ${symbol} SYMBOL)
|
||||
string(REPLACE "." "," version_commas ${version})
|
||||
string(REPLACE "\\" "\\\\" binary_escaped "${binary}")
|
||||
configure_file(fw.c.in "${CMAKE_CURRENT_BINARY_DIR}/${symbol}.c" @ONLY)
|
||||
configure_file(fw.h.in "${CMAKE_CURRENT_BINARY_DIR}/${symbol}.h" @ONLY)
|
||||
configure_file(fw.rc.in "${CMAKE_CURRENT_BINARY_DIR}/${symbol}.rc" @ONLY)
|
||||
if (MSVC)
|
||||
enable_language(RC)
|
||||
set_source_files_properties("${PROJECT_NAME}.rc" OBJECT_DEPENDS "${CMAKE_CURRENT_BINARY_DIR}/${symbol}.rc")
|
||||
set_source_files_properties("${CMAKE_CURRENT_BINARY_DIR}/${symbol}.rc" OBJECT_DEPENDS "${binary}")
|
||||
else()
|
||||
set_source_files_properties("${CMAKE_CURRENT_BINARY_DIR}/${symbol}.c" OBJECT_DEPENDS "${binary}")
|
||||
endif()
|
||||
target_sources(${PROJECT_NAME} PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/${symbol}.c")
|
||||
endfunction()
|
||||
|
||||
target_binary( "${D4XX_FW_URL}" "${D4XX_FW_VERSION}" "${D4XX_FW_SHA1}" D4XX_FW_Image .bin)
|
||||
|
||||
|
||||
install(TARGETS ${PROJECT_NAME} EXPORT realsense2Targets
|
||||
RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}
|
||||
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
|
||||
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR})
|
||||
|
||||
1
librealsense-r-256/common/fw/empty.c
Normal file
1
librealsense-r-256/common/fw/empty.c
Normal file
@@ -0,0 +1 @@
|
||||
int fw_empty; // avoid warnings about empty.o being an empty object
|
||||
7
librealsense-r-256/common/fw/firmware-version.h
Normal file
7
librealsense-r-256/common/fw/firmware-version.h
Normal file
@@ -0,0 +1,7 @@
|
||||
/* License: Apache 2.0. See LICENSE file in root directory.
|
||||
Copyright(c) 2017-24 Intel Corporation. All Rights Reserved. */
|
||||
|
||||
#pragma once
|
||||
|
||||
#define D4XX_RECOMMENDED_FIRMWARE_VERSION "5.17.0.10"
|
||||
|
||||
25
librealsense-r-256/common/fw/fw.c.in
Normal file
25
librealsense-r-256/common/fw/fw.c.in
Normal file
@@ -0,0 +1,25 @@
|
||||
// All included firmware files are
|
||||
// INTEL CORPORATION PROPRIETARY INFORMATION
|
||||
// Copyright(c) 2019 Intel Corporation. All Rights Reserved
|
||||
const int fw_@symbol@_version[4] = {@version_commas@};
|
||||
#ifndef _MSC_VER
|
||||
__asm__(
|
||||
"#version @sha1@\n"
|
||||
#ifdef __APPLE__
|
||||
".const_data\n"
|
||||
#define _ "_"
|
||||
#else
|
||||
".section .rodata\n"
|
||||
#define _ ""
|
||||
#endif
|
||||
".global "_"fw_@symbol@_data\n"
|
||||
_"fw_@symbol@_data:\n"
|
||||
".incbin \"@binary_escaped@\"\n"
|
||||
".global "_"fw_@symbol@_size\n"
|
||||
_"fw_@symbol@_size:\n"
|
||||
"1:\n"
|
||||
".int 1b - "_"fw_@symbol@_data\n"
|
||||
".previous"
|
||||
);
|
||||
#undef _
|
||||
#endif
|
||||
25
librealsense-r-256/common/fw/fw.h.in
Normal file
25
librealsense-r-256/common/fw/fw.h.in
Normal file
@@ -0,0 +1,25 @@
|
||||
#pragma once
|
||||
|
||||
#define FW_@SYMBOL@_VERSION "@version@"
|
||||
|
||||
extern "C" const unsigned char fw_@symbol@_data[];
|
||||
extern "C" const int fw_@symbol@_size;
|
||||
extern "C" const int fw_@symbol@_version[4];
|
||||
|
||||
#ifdef _MSC_VER
|
||||
#include <windows.h>
|
||||
extern "C" IMAGE_DOS_HEADER __ImageBase;
|
||||
#endif
|
||||
|
||||
static inline const unsigned char *fw_get_@symbol@(int &size)
|
||||
{
|
||||
#ifdef _MSC_VER
|
||||
HRSRC rc = ::FindResourceA((HMODULE)&__ImageBase, "@SYMBOL@_DATA" , "@SYMBOL@_RC");
|
||||
HGLOBAL data = ::LoadResource((HMODULE)&__ImageBase, rc);
|
||||
size = ::SizeofResource((HMODULE)&__ImageBase, rc);
|
||||
return static_cast<const unsigned char*>(::LockResource(data));
|
||||
#else
|
||||
size = fw_@symbol@_size;
|
||||
return fw_@symbol@_data;
|
||||
#endif
|
||||
}
|
||||
2
librealsense-r-256/common/fw/fw.rc
Normal file
2
librealsense-r-256/common/fw/fw.rc
Normal file
@@ -0,0 +1,2 @@
|
||||
#include "D4XX_FW_Image.rc"
|
||||
|
||||
1
librealsense-r-256/common/fw/fw.rc.in
Normal file
1
librealsense-r-256/common/fw/fw.rc.in
Normal file
@@ -0,0 +1 @@
|
||||
@SYMBOL@_DATA @SYMBOL@_RC "@binary_escaped@"
|
||||
118
librealsense-r-256/common/graph-model.cpp
Normal file
118
librealsense-r-256/common/graph-model.cpp
Normal file
@@ -0,0 +1,118 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2025 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include "graph-model.h"
|
||||
|
||||
using namespace rs2;
|
||||
|
||||
void graph_model::process_frame(rs2::frame f)
|
||||
{
|
||||
write_shared_data(
|
||||
[&]()
|
||||
{
|
||||
if (!_paused && f && f.is< rs2::motion_frame >()
|
||||
&& (f.as< rs2::motion_frame >()).get_profile().stream_type() == _stream_type)
|
||||
{
|
||||
double ts = glfwGetTime();
|
||||
|
||||
if (_update_timer) // Check if timer expired
|
||||
{
|
||||
rs2::motion_frame frame = f.as< rs2::motion_frame >();
|
||||
|
||||
// Update motion data values
|
||||
_x_value = frame.get_motion_data().x;
|
||||
_y_value = frame.get_motion_data().y;
|
||||
_z_value = frame.get_motion_data().z;
|
||||
if(_show_n_value)
|
||||
_n_value = std::sqrt(_x_value * _x_value + _y_value * _y_value + _z_value * _z_value);
|
||||
|
||||
if (_x_history.size() >= VECTOR_SIZE)
|
||||
_x_history.erase(_x_history.begin());
|
||||
if (_y_history.size() >= VECTOR_SIZE)
|
||||
_y_history.erase(_y_history.begin());
|
||||
if (_z_history.size() >= VECTOR_SIZE)
|
||||
_z_history.erase(_z_history.begin());
|
||||
if (_show_n_value && _n_history.size() >= VECTOR_SIZE)
|
||||
_n_history.erase(_n_history.begin());
|
||||
|
||||
_x_history.push_back(_x_value);
|
||||
_y_history.push_back(_y_value);
|
||||
_z_history.push_back(_z_value);
|
||||
_n_history.push_back(_n_value);
|
||||
|
||||
}
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
void graph_model::draw(rect stream_rect)
|
||||
{
|
||||
ImGui::SetCursorScreenPos({ stream_rect.x, stream_rect.y });
|
||||
if (_x_history.empty()) return;
|
||||
|
||||
// Set the time array
|
||||
std::vector<float> time_index(_x_history.size());
|
||||
for (size_t i = 0; i < time_index.size(); ++i)
|
||||
time_index[i] = static_cast<float>(i);
|
||||
|
||||
// Read shared history data
|
||||
auto x_hist = read_shared_data<std::vector<float>>([&]() { return _x_history; });
|
||||
auto y_hist = read_shared_data<std::vector<float>>([&]() { return _y_history; });
|
||||
auto z_hist = read_shared_data<std::vector<float>>([&]() { return _z_history; });
|
||||
|
||||
std::vector<float> n_hist;
|
||||
if(_show_n_value)
|
||||
n_hist = read_shared_data<std::vector<float>>([&]() { return _n_history; });
|
||||
|
||||
ImGui::BeginChild(_name.c_str(), ImVec2(stream_rect.w + 2, stream_rect.h));
|
||||
|
||||
if (ImPlot::BeginPlot(_name.c_str(), ImVec2(stream_rect.w + 2, stream_rect.h)))
|
||||
{
|
||||
ImPlot::SetupAxes("Time", "Value");
|
||||
|
||||
ImPlot::PlotLine("X", time_index.data(), x_hist.data(), static_cast<int>(x_hist.size()));
|
||||
ImPlot::PlotLine("Y", time_index.data(), y_hist.data(), static_cast<int>(y_hist.size()));
|
||||
ImPlot::PlotLine("Z", time_index.data(), z_hist.data(), static_cast<int>(z_hist.size()));
|
||||
if (_show_n_value)
|
||||
ImPlot::PlotLine("N", time_index.data(), n_hist.data(), static_cast<int>(n_hist.size()));
|
||||
|
||||
ImPlot::EndPlot();
|
||||
}
|
||||
ImGui::EndChild();
|
||||
}
|
||||
|
||||
void graph_model::clear()
|
||||
{
|
||||
write_shared_data(
|
||||
[&]()
|
||||
{
|
||||
_x_history.clear();
|
||||
_y_history.clear();
|
||||
_z_history.clear();
|
||||
if (_show_n_value)
|
||||
_n_history.clear();
|
||||
for (int i = 0; i < VECTOR_SIZE; i++)
|
||||
{
|
||||
_x_history.push_back(0);
|
||||
_y_history.push_back(0);
|
||||
_z_history.push_back(0);
|
||||
if(_show_n_value)
|
||||
_n_history.push_back(0);
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
void graph_model::pause()
|
||||
{
|
||||
_paused = true;
|
||||
}
|
||||
|
||||
void graph_model::resume()
|
||||
{
|
||||
_paused = false;
|
||||
}
|
||||
|
||||
bool graph_model::is_paused()
|
||||
{
|
||||
return _paused;
|
||||
}
|
||||
64
librealsense-r-256/common/graph-model.h
Normal file
64
librealsense-r-256/common/graph-model.h
Normal file
@@ -0,0 +1,64 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2025 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <imgui.h>
|
||||
#include <implot.h>
|
||||
#include <mutex>
|
||||
#include <vector>
|
||||
#include <GLFW/glfw3.h>
|
||||
#include <rsutils/time/periodic-timer.h>
|
||||
#include "rect.h"
|
||||
|
||||
#include <librealsense2/rs.hpp>
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
class graph_model
|
||||
{
|
||||
public:
|
||||
graph_model(std::string name, rs2_stream stream, bool show_n_value = true)
|
||||
: _name(name),
|
||||
_stream_type(stream),
|
||||
_show_n_value(show_n_value),
|
||||
_update_timer{ std::chrono::milliseconds(_update_rate) }
|
||||
{
|
||||
clear();
|
||||
}
|
||||
|
||||
void process_frame(rs2::frame f);
|
||||
void draw(rect r);
|
||||
void clear();
|
||||
void pause();
|
||||
void resume();
|
||||
bool is_paused();
|
||||
protected:
|
||||
template<class T>
|
||||
T read_shared_data(std::function<T()> action)
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(_m);
|
||||
T res = action();
|
||||
return res;
|
||||
}
|
||||
void write_shared_data(std::function<void()> action)
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(_m);
|
||||
action();
|
||||
}
|
||||
private:
|
||||
float _x_value = 0.0f, _y_value = 0.0f, _z_value = 0.0f, _n_value = 0.0f;
|
||||
bool _show_n_value;
|
||||
int _update_rate = 50;
|
||||
rsutils::time::periodic_timer _update_timer;
|
||||
bool _paused = false;
|
||||
|
||||
const int VECTOR_SIZE = 300;
|
||||
std::vector< float > _x_history, _y_history, _z_history, _n_history;
|
||||
|
||||
std::mutex _m;
|
||||
std::string _name;
|
||||
|
||||
rs2_stream _stream_type;
|
||||
};
|
||||
}
|
||||
196
librealsense-r-256/common/matrix4.h
Normal file
196
librealsense-r-256/common/matrix4.h
Normal file
@@ -0,0 +1,196 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2021 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <librealsense2/h/rs_types.h> // rs2_quaternion
|
||||
#include "float4.h"
|
||||
|
||||
#include <cmath> // sqrt
|
||||
#include <cstring> // memset
|
||||
|
||||
|
||||
namespace rs2 {
|
||||
|
||||
|
||||
struct matrix4
|
||||
{
|
||||
float mat[4][4];
|
||||
|
||||
operator float*() const
|
||||
{
|
||||
return (float*)&mat;
|
||||
}
|
||||
|
||||
static matrix4 identity()
|
||||
{
|
||||
matrix4 m;
|
||||
for (int i = 0; i < 4; i++)
|
||||
m.mat[i][i] = 1.f;
|
||||
return m;
|
||||
}
|
||||
|
||||
matrix4()
|
||||
{
|
||||
std::memset(mat, 0, sizeof(mat));
|
||||
}
|
||||
|
||||
matrix4(float vals[4][4])
|
||||
{
|
||||
std::memcpy(mat,vals,sizeof(mat));
|
||||
}
|
||||
|
||||
// convert glGetFloatv output to matrix4
|
||||
//
|
||||
// float m[16] = { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 };
|
||||
// into
|
||||
// rs2::matrix4 m = { {0, 1, 2, 3}, {4, 5, 6, 7}, {8, 9, 10, 11}, {12, 13, 14, 15} };
|
||||
// 0 1 2 3
|
||||
// 4 5 6 7
|
||||
// 8 9 10 11
|
||||
// 12 13 14 15
|
||||
matrix4(float vals[16])
|
||||
{
|
||||
for (int i = 0; i < 4; i++)
|
||||
{
|
||||
for (int j = 0; j < 4; j++)
|
||||
{
|
||||
mat[i][j] = vals[i * 4 + j];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
float& operator()(int i, int j) { return mat[i][j]; }
|
||||
const float& operator()(int i, int j) const { return mat[i][j]; }
|
||||
|
||||
//init rotation matrix from quaternion
|
||||
matrix4(const rs2_quaternion& q)
|
||||
{
|
||||
mat[0][0] = 1 - 2*q.y*q.y - 2*q.z*q.z; mat[0][1] = 2*q.x*q.y - 2*q.z*q.w; mat[0][2] = 2*q.x*q.z + 2*q.y*q.w; mat[0][3] = 0.0f;
|
||||
mat[1][0] = 2*q.x*q.y + 2*q.z*q.w; mat[1][1] = 1 - 2*q.x*q.x - 2*q.z*q.z; mat[1][2] = 2*q.y*q.z - 2*q.x*q.w; mat[1][3] = 0.0f;
|
||||
mat[2][0] = 2*q.x*q.z - 2*q.y*q.w; mat[2][1] = 2*q.y*q.z + 2*q.x*q.w; mat[2][2] = 1 - 2*q.x*q.x - 2*q.y*q.y; mat[2][3] = 0.0f;
|
||||
mat[3][0] = 0.0f; mat[3][1] = 0.0f; mat[3][2] = 0.0f; mat[3][3] = 1.0f;
|
||||
}
|
||||
|
||||
//init translation matrix from vector
|
||||
matrix4(const rs2_vector& t)
|
||||
{
|
||||
mat[0][0] = 1.0f; mat[0][1] = 0.0f; mat[0][2] = 0.0f; mat[0][3] = t.x;
|
||||
mat[1][0] = 0.0f; mat[1][1] = 1.0f; mat[1][2] = 0.0f; mat[1][3] = t.y;
|
||||
mat[2][0] = 0.0f; mat[2][1] = 0.0f; mat[2][2] = 1.0f; mat[2][3] = t.z;
|
||||
mat[3][0] = 0.0f; mat[3][1] = 0.0f; mat[3][2] = 0.0f; mat[3][3] = 1.0f;
|
||||
}
|
||||
|
||||
rs2_quaternion normalize(rs2_quaternion a)
|
||||
{
|
||||
float norm = sqrtf(a.x*a.x + a.y*a.y + a.z*a.z + a.w*a.w);
|
||||
rs2_quaternion res = a;
|
||||
res.x /= norm;
|
||||
res.y /= norm;
|
||||
res.z /= norm;
|
||||
res.w /= norm;
|
||||
return res;
|
||||
}
|
||||
|
||||
rs2_quaternion to_quaternion()
|
||||
{
|
||||
float tr[4];
|
||||
rs2_quaternion res;
|
||||
tr[0] = (mat[0][0] + mat[1][1] + mat[2][2]);
|
||||
tr[1] = (mat[0][0] - mat[1][1] - mat[2][2]);
|
||||
tr[2] = (-mat[0][0] + mat[1][1] - mat[2][2]);
|
||||
tr[3] = (-mat[0][0] - mat[1][1] + mat[2][2]);
|
||||
if (tr[0] >= tr[1] && tr[0] >= tr[2] && tr[0] >= tr[3])
|
||||
{
|
||||
float s = 2 * sqrt(tr[0] + 1);
|
||||
res.w = s / 4;
|
||||
res.x = (mat[2][1] - mat[1][2]) / s;
|
||||
res.y = (mat[0][2] - mat[2][0]) / s;
|
||||
res.z = (mat[1][0] - mat[0][1]) / s;
|
||||
}
|
||||
else if (tr[1] >= tr[2] && tr[1] >= tr[3]) {
|
||||
float s = 2 * sqrt(tr[1] + 1);
|
||||
res.w = (mat[2][1] - mat[1][2]) / s;
|
||||
res.x = s / 4;
|
||||
res.y = (mat[1][0] + mat[0][1]) / s;
|
||||
res.z = (mat[2][0] + mat[0][2]) / s;
|
||||
}
|
||||
else if (tr[2] >= tr[3]) {
|
||||
float s = 2 * sqrt(tr[2] + 1);
|
||||
res.w = (mat[0][2] - mat[2][0]) / s;
|
||||
res.x = (mat[1][0] + mat[0][1]) / s;
|
||||
res.y = s / 4;
|
||||
res.z = (mat[1][2] + mat[2][1]) / s;
|
||||
}
|
||||
else {
|
||||
float s = 2 * sqrt(tr[3] + 1);
|
||||
res.w = (mat[1][0] - mat[0][1]) / s;
|
||||
res.x = (mat[0][2] + mat[2][0]) / s;
|
||||
res.y = (mat[1][2] + mat[2][1]) / s;
|
||||
res.z = s / 4;
|
||||
}
|
||||
return normalize(res);
|
||||
}
|
||||
|
||||
void to_column_major(float column_major[16])
|
||||
{
|
||||
column_major[0] = mat[0][0];
|
||||
column_major[1] = mat[1][0];
|
||||
column_major[2] = mat[2][0];
|
||||
column_major[3] = mat[3][0];
|
||||
column_major[4] = mat[0][1];
|
||||
column_major[5] = mat[1][1];
|
||||
column_major[6] = mat[2][1];
|
||||
column_major[7] = mat[3][1];
|
||||
column_major[8] = mat[0][2];
|
||||
column_major[9] = mat[1][2];
|
||||
column_major[10] = mat[2][2];
|
||||
column_major[11] = mat[3][2];
|
||||
column_major[12] = mat[0][3];
|
||||
column_major[13] = mat[1][3];
|
||||
column_major[14] = mat[2][3];
|
||||
column_major[15] = mat[3][3];
|
||||
}
|
||||
};
|
||||
|
||||
inline matrix4 operator*(const matrix4& a, const matrix4& b)
|
||||
{
|
||||
matrix4 res;
|
||||
for (int i = 0; i < 4; i++)
|
||||
{
|
||||
for (int j = 0; j < 4; j++)
|
||||
{
|
||||
float sum = 0.0f;
|
||||
for (int k = 0; k < 4; k++)
|
||||
{
|
||||
sum += a.mat[i][k] * b.mat[k][j];
|
||||
}
|
||||
res.mat[i][j] = sum;
|
||||
}
|
||||
}
|
||||
return res;
|
||||
}
|
||||
|
||||
inline float4 operator*(const matrix4& a, const float4& b)
|
||||
{
|
||||
float4 res;
|
||||
int i = 0;
|
||||
res.x = a(i, 0) * b.x + a(i, 1) * b.y + a(i, 2) * b.z + a(i, 3) * b.w; i++;
|
||||
res.y = a(i, 0) * b.x + a(i, 1) * b.y + a(i, 2) * b.z + a(i, 3) * b.w; i++;
|
||||
res.z = a(i, 0) * b.x + a(i, 1) * b.y + a(i, 2) * b.z + a(i, 3) * b.w; i++;
|
||||
res.w = a(i, 0) * b.x + a(i, 1) * b.y + a(i, 2) * b.z + a(i, 3) * b.w; i++;
|
||||
return res;
|
||||
}
|
||||
|
||||
|
||||
inline matrix4 identity_matrix()
|
||||
{
|
||||
matrix4 data;
|
||||
for( int i = 0; i < 4; i++ )
|
||||
for( int j = 0; j < 4; j++ )
|
||||
data.mat[i][j] = (i == j) ? 1.f : 0.f;
|
||||
return data;
|
||||
}
|
||||
|
||||
|
||||
} // namespace rs2
|
||||
678
librealsense-r-256/common/measurement.cpp
Normal file
678
librealsense-r-256/common/measurement.cpp
Normal file
@@ -0,0 +1,678 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include "measurement.h"
|
||||
#include "ux-window.h"
|
||||
#include <rs-config.h>
|
||||
#include <librealsense2/hpp/rs_export.hpp>
|
||||
|
||||
#include "opengl3.h"
|
||||
|
||||
|
||||
using namespace rs2;
|
||||
|
||||
void measurement::enable() {
|
||||
measurement_active = true;
|
||||
config_file::instance().set(configurations::viewer::is_measuring, true);
|
||||
}
|
||||
void measurement::disable() {
|
||||
state.points.clear();
|
||||
state.edges.clear();
|
||||
state.polygons.clear();
|
||||
measurement_active = false;
|
||||
config_file::instance().set(configurations::viewer::is_measuring, false);
|
||||
}
|
||||
bool measurement::is_enabled() const { return measurement_active; }
|
||||
|
||||
bool measurement::display_mouse_picked_tooltip() const{
|
||||
return !(measurement_active && state.points.size() == 1) && !measurement_point_hovered;
|
||||
}
|
||||
|
||||
bool measurement::manipulating() const { return dragging_measurement_point; }
|
||||
|
||||
std::vector<int> measurement_state::find_path(int from, int to)
|
||||
{
|
||||
std::map<int, int> parents;
|
||||
std::deque<int> q;
|
||||
|
||||
q.push_back(from);
|
||||
for (int i = 0; i < points.size(); i++)
|
||||
{
|
||||
parents[i] = -1;
|
||||
}
|
||||
|
||||
while (q.size())
|
||||
{
|
||||
auto vert = q.front();
|
||||
q.pop_front();
|
||||
|
||||
for (auto&& pair : edges)
|
||||
{
|
||||
int next = -1;
|
||||
if (pair.first == vert) next = pair.second;
|
||||
if (pair.second == vert) next = pair.first;
|
||||
if (next >= 0 && parents[next] == -1)
|
||||
{
|
||||
parents[next] = vert;
|
||||
q.push_back(next);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
std::vector<int> path;
|
||||
parents[from] = -1;
|
||||
|
||||
if (parents[to] != -1)
|
||||
{
|
||||
auto p = to;
|
||||
while (p != -1)
|
||||
{
|
||||
path.push_back(p);
|
||||
p = parents[p];
|
||||
}
|
||||
}
|
||||
|
||||
return path;
|
||||
}
|
||||
|
||||
void measurement::add_point(interest_point p)
|
||||
{
|
||||
ImGuiIO& io = ImGui::GetIO();
|
||||
auto shift = io.KeysDown[GLFW_KEY_LEFT_SHIFT] || io.KeysDown[GLFW_KEY_RIGHT_SHIFT];
|
||||
|
||||
if (is_enabled())
|
||||
{
|
||||
commit_state();
|
||||
|
||||
if (state.points.size() >= 2 && !shift)
|
||||
{
|
||||
state.points.clear();
|
||||
state.edges.clear();
|
||||
state.polygons.clear();
|
||||
}
|
||||
|
||||
int last = int(state.points.size());
|
||||
if (current_hovered_point == -1 ||
|
||||
current_hovered_point >= state.points.size())
|
||||
{
|
||||
state.points.push_back(p);
|
||||
}
|
||||
else
|
||||
{
|
||||
last = current_hovered_point;
|
||||
}
|
||||
|
||||
int prev = last - 1;
|
||||
if (last_hovered_point >= 0 && last_hovered_point < state.points.size())
|
||||
prev = last_hovered_point;
|
||||
|
||||
if (state.edges.size())
|
||||
{
|
||||
auto path = state.find_path(prev, last);
|
||||
if (path.size())
|
||||
{
|
||||
state.polygons.push_back(path);
|
||||
|
||||
std::vector<float3> poly;
|
||||
for (auto&& idx : path) poly.push_back(state.points[idx].pos);
|
||||
|
||||
auto area = calculate_area(poly);
|
||||
log_function( rsutils::string::from() << "Measured area of " << area_to_string(area));
|
||||
}
|
||||
}
|
||||
|
||||
if (state.points.size() >= 2)
|
||||
{
|
||||
auto dist = state.points[last].pos - state.points[prev].pos;
|
||||
state.edges.push_back(std::make_pair(last, prev));
|
||||
log_function( rsutils::string::from() << "Measured distance of " << length_to_string(dist.length()));
|
||||
}
|
||||
|
||||
last_hovered_point = int(state.points.size() - 1);
|
||||
|
||||
commit_state();
|
||||
}
|
||||
}
|
||||
|
||||
std::string measurement::area_to_string(float area)
|
||||
{
|
||||
return rsutils::string::from() << std::setprecision(2) << area << " m";
|
||||
}
|
||||
|
||||
std::string measurement::length_to_string(float distance)
|
||||
{
|
||||
std::string label;
|
||||
if (is_metric())
|
||||
{
|
||||
if (distance < 0.01f)
|
||||
{
|
||||
label = rsutils::string::from() << std::setprecision(3) << distance * 1000.f << " mm";
|
||||
} else if (distance < 1.f) {
|
||||
label = rsutils::string::from() << std::setprecision(3) << distance * 100.f << " cm";
|
||||
} else {
|
||||
label = rsutils::string::from() << std::setprecision(3) << distance << " m";
|
||||
}
|
||||
} else
|
||||
{
|
||||
if (distance < 0.0254f)
|
||||
{
|
||||
label = rsutils::string::from() << std::setprecision(3) << distance * 1000.f << " mm";
|
||||
} else if (distance < 0.3048f) {
|
||||
label = rsutils::string::from() << std::setprecision(3) << distance / 0.0254 << " in";
|
||||
} else if (distance < 0.9144) {
|
||||
label = rsutils::string::from() << std::setprecision(3) << distance / 0.3048f << " ft";
|
||||
} else {
|
||||
label = rsutils::string::from() << std::setprecision(3) << distance / 0.9144 << " yd";
|
||||
}
|
||||
}
|
||||
return label;
|
||||
}
|
||||
|
||||
float measurement::calculate_area(std::vector<float3> poly)
|
||||
{
|
||||
if (poly.size() < 3) return 0.f;
|
||||
|
||||
float3 total{ 0.f, 0.f, 0.f };
|
||||
|
||||
for (int i = 0; i < poly.size(); i++)
|
||||
{
|
||||
auto v1 = poly[i];
|
||||
auto v2 = poly[(i+1) % poly.size()];
|
||||
auto prod = cross(v1, v2);
|
||||
total = total + prod;
|
||||
}
|
||||
|
||||
auto a = poly[1] - poly[0];
|
||||
auto b = poly[2] - poly[0];
|
||||
auto n = cross(a, b);
|
||||
return std::abs( total * n.normalized() ) / 2;
|
||||
}
|
||||
|
||||
void draw_sphere(const float3& pos, float r, int lats, int longs)
|
||||
{
|
||||
for(int i = 0; i <= lats; i++)
|
||||
{
|
||||
float lat0 = float(M_PI) * (-0.5f + (float) (i - 1) / lats);
|
||||
float z0 = sin(lat0);
|
||||
float zr0 = cos(lat0);
|
||||
|
||||
float lat1 = float(M_PI) * (-0.5f + (float) i / lats);
|
||||
float z1 = sin(lat1);
|
||||
float zr1 = cos(lat1);
|
||||
|
||||
glBegin(GL_QUAD_STRIP);
|
||||
for(int j = 0; j <= longs; j++)
|
||||
{
|
||||
float lng = 2.f * float(M_PI) * (float) (j - 1) / longs;
|
||||
float x = cos(lng);
|
||||
float y = sin(lng);
|
||||
|
||||
glNormal3f(pos.x + x * zr0, pos.y + y * zr0, pos.z + z0);
|
||||
glVertex3f(pos.x + r * x * zr0, pos.y + r * y * zr0, pos.z + r * z0);
|
||||
glNormal3f(pos.x + x * zr1, pos.y + y * zr1, pos.z + z1);
|
||||
glVertex3f(pos.x + r * x * zr1, pos.y + r * y * zr1, pos.z + r * z1);
|
||||
}
|
||||
glEnd();
|
||||
}
|
||||
}
|
||||
|
||||
rs2::float2 measurement::project_to_2d(rs2::float3 pos)
|
||||
{
|
||||
int32_t vp[4];
|
||||
glGetIntegerv(GL_VIEWPORT, vp);
|
||||
check_gl_error();
|
||||
|
||||
GLfloat model[16];
|
||||
glGetFloatv(GL_MODELVIEW_MATRIX, model);
|
||||
GLfloat proj[16];
|
||||
glGetFloatv(GL_PROJECTION_MATRIX, proj);
|
||||
|
||||
rs2::matrix4 p(proj);
|
||||
rs2::matrix4 v(model);
|
||||
|
||||
return translate_3d_to_2d(pos, p, v, rs2::matrix4::identity(), vp);
|
||||
}
|
||||
|
||||
void measurement::draw_label(ux_window& win, float3 pos, float distance, int height, bool is_area)
|
||||
{
|
||||
auto w_pos = project_to_2d(pos);
|
||||
std::string label = is_area ? area_to_string(distance) : length_to_string(distance);
|
||||
if (is_area) ImGui::PushFont(win.get_large_font());
|
||||
auto size = ImGui::CalcTextSize(label.c_str());
|
||||
if (is_area) ImGui::PopFont();
|
||||
|
||||
std::string win_id = rsutils::string::from() << "measurement_" << id;
|
||||
id++;
|
||||
|
||||
auto flags = ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | ImGuiWindowFlags_NoTitleBar;
|
||||
|
||||
if (!is_area)
|
||||
{
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, regular_blue);
|
||||
ImGui::PushStyleColor(ImGuiCol_WindowBg, almost_white_bg);
|
||||
}
|
||||
else
|
||||
{
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, white);
|
||||
ImGui::PushStyleColor(ImGuiCol_WindowBg, transparent);
|
||||
}
|
||||
ImGui::PushStyleVar(ImGuiStyleVar_WindowRounding, 10);
|
||||
ImGui::SetNextWindowPos(ImVec2(w_pos.x - size.x / 2, height - w_pos.y - size.y / 2 - 5));
|
||||
ImGui::SetNextWindowSize(ImVec2(size.x + 20, size.y - 15));
|
||||
ImGui::Begin(win_id.c_str(), nullptr, flags);
|
||||
|
||||
if (is_area) ImGui::PushFont(win.get_large_font());
|
||||
ImGui::Text("%s", label.c_str());
|
||||
if (is_area) {
|
||||
ImGui::PopFont();
|
||||
ImGui::SameLine();
|
||||
ImGui::SetCursorPosX(ImGui::GetCursorPosX() - 7);
|
||||
ImGui::Text("%s", "2");
|
||||
}
|
||||
|
||||
ImGui::End();
|
||||
ImGui::PopStyleVar();
|
||||
ImGui::PopStyleColor(2);
|
||||
}
|
||||
|
||||
void measurement::draw_ruler(ux_window& win, float3 from, float3 to, float height, int selected)
|
||||
{
|
||||
std::vector<float3> parts;
|
||||
parts.push_back(from);
|
||||
auto dir = to - from;
|
||||
auto l = dir.length();
|
||||
auto unit = is_metric() ? 0.01f : 0.0254f;
|
||||
if (l > 0.5f) unit = is_metric() ? 0.1f : 0.03048f;
|
||||
auto parts_num = l / unit;
|
||||
for (int i = 0; i < parts_num; i++)
|
||||
{
|
||||
auto t = i / (float)parts_num;
|
||||
parts.push_back(from + dir * t);
|
||||
}
|
||||
parts.push_back(to);
|
||||
|
||||
glLineWidth(3.f);
|
||||
glBegin(GL_LINES);
|
||||
for (int i = 1; i < parts.size(); i++)
|
||||
{
|
||||
auto alpha = selected == 0 ? 0.4f : 0.9f;
|
||||
alpha = selected == 2 ? 1.f : alpha;
|
||||
if (i % 2 == 0) glColor4f(1.f, 1.f, 1.f, alpha);
|
||||
else glColor4f(light_blue.x, light_blue.y, light_blue.z, alpha);
|
||||
auto from = parts[i-1];
|
||||
auto to = parts[i]; // intentional shadowing
|
||||
glVertex3d(from.x, from.y, from.z);
|
||||
glVertex3d(to.x, to.y, to.z);
|
||||
}
|
||||
glEnd();
|
||||
|
||||
if (selected == 2)
|
||||
{
|
||||
// calculate center of the ruler line
|
||||
float3 ctr = from + (to - from) / 2;
|
||||
float distance = (to - from).length();
|
||||
draw_label(win, ctr, distance, int(height));
|
||||
}
|
||||
}
|
||||
|
||||
void measurement::mouse_pick(ux_window& win, float3 picked, float3 normal)
|
||||
{
|
||||
_picked = picked; _normal = normal;
|
||||
mouse_picked_event.add_value(!input_ctrl.mouse_down);
|
||||
|
||||
if (input_ctrl.click) {
|
||||
add_point({ _picked, _normal });
|
||||
}
|
||||
|
||||
if (is_enabled())
|
||||
{
|
||||
if (point_hovered(win) < 0 && hovered_edge_id < 0)
|
||||
win.cross_hovered();
|
||||
}
|
||||
}
|
||||
|
||||
void measurement::update_input(ux_window& win, const rs2::rect& viewer_rect)
|
||||
{
|
||||
id = 0;
|
||||
|
||||
if (ImGui::IsKeyPressed(ImGuiKey_Z))
|
||||
restore_state();
|
||||
|
||||
input_ctrl.prev_mouse_down = input_ctrl.mouse_down;
|
||||
|
||||
auto rect_copy = viewer_rect;
|
||||
rect_copy.y += 60;
|
||||
input_ctrl.click = false;
|
||||
if (win.get_mouse().mouse_down[0] && !input_ctrl.mouse_down)
|
||||
{
|
||||
input_ctrl.mouse_down = true;
|
||||
input_ctrl.down_pos = win.get_mouse().cursor;
|
||||
input_ctrl.selection_started = win.time();
|
||||
}
|
||||
if (input_ctrl.mouse_down && !win.get_mouse().mouse_down[0])
|
||||
{
|
||||
input_ctrl.mouse_down = false;
|
||||
if (win.time() - input_ctrl.selection_started < 0.5 &&
|
||||
(win.get_mouse().cursor - input_ctrl.down_pos).length() < 100)
|
||||
{
|
||||
if (rect_copy.contains(win.get_mouse().cursor))
|
||||
{
|
||||
input_ctrl.click = true;
|
||||
input_ctrl.click_time = float(glfwGetTime());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int measurement::point_hovered(ux_window& win)
|
||||
{
|
||||
for (int i = 0; i < state.points.size(); i++)
|
||||
{
|
||||
auto&& point = state.points[i];
|
||||
auto pos_2d = project_to_2d(point.pos);
|
||||
pos_2d.y = win.framebuf_height() - pos_2d.y;
|
||||
|
||||
if ((pos_2d - win.get_mouse().cursor).length() < 15)
|
||||
{
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
float distance_to_line(rs2::float2 a, rs2::float2 b, rs2::float2 p)
|
||||
{
|
||||
const float l2 = dot(b - a, b - a);
|
||||
if (l2 == 0.0) return (p - a).length();
|
||||
const float t = clamp(dot(p - a, b - a) / l2, 0.f, 1.f);
|
||||
return (lerp(a, b, t) - p).length();
|
||||
}
|
||||
|
||||
int measurement::edge_hovered(ux_window& win)
|
||||
{
|
||||
for (int i = 0; i < state.edges.size(); i++)
|
||||
{
|
||||
auto&& a = state.points[state.edges[i].first];
|
||||
auto&& b = state.points[state.edges[i].second];
|
||||
|
||||
auto a_2d = project_to_2d(a.pos);
|
||||
auto b_2d = project_to_2d(b.pos);
|
||||
|
||||
auto cursor = win.get_mouse().cursor;
|
||||
cursor.y = win.framebuf_height() - cursor.y;
|
||||
|
||||
if (distance_to_line(a_2d, b_2d, cursor) < 15)
|
||||
{
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
void measurement::commit_state()
|
||||
{
|
||||
state_history.push_back(state);
|
||||
if (state_history.size() > 100)
|
||||
{
|
||||
state_history.pop_front();
|
||||
}
|
||||
}
|
||||
|
||||
void measurement::restore_state()
|
||||
{
|
||||
auto new_state = state;
|
||||
while (state_history.size() && new_state == state)
|
||||
{
|
||||
new_state = state_history.back();
|
||||
state_history.pop_back();
|
||||
}
|
||||
state = new_state;
|
||||
}
|
||||
|
||||
void measurement::draw(ux_window& win)
|
||||
{
|
||||
ImGuiIO& io = ImGui::GetIO();
|
||||
auto shift = io.KeysDown[GLFW_KEY_LEFT_SHIFT] || io.KeysDown[GLFW_KEY_RIGHT_SHIFT];
|
||||
|
||||
auto p_idx = point_hovered(win);
|
||||
if (p_idx >= 0 && !win.get_mouse().mouse_down[0])
|
||||
{
|
||||
_picked = state.points[p_idx].pos;
|
||||
_normal = state.points[p_idx].normal;
|
||||
}
|
||||
if (mouse_picked_event.eval() && is_enabled())
|
||||
{
|
||||
glDisable(GL_DEPTH_TEST);
|
||||
glLineWidth(2.f);
|
||||
glEnable(GL_BLEND);
|
||||
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
|
||||
|
||||
float size = _picked.z * 0.03f;
|
||||
|
||||
glBegin(GL_LINES);
|
||||
glColor3f(1.f, 1.f, 1.f);
|
||||
glVertex3d(_picked.x, _picked.y, _picked.z);
|
||||
auto nend = _picked + _normal * size * 0.3f;
|
||||
glVertex3d(nend.x, nend.y, nend.z);
|
||||
glEnd();
|
||||
|
||||
glBegin(GL_TRIANGLES);
|
||||
|
||||
if (input_ctrl.mouse_down) size -= _picked.z * 0.01f;
|
||||
size += _picked.z * 0.01f * single_wave(input_ctrl.click_period());
|
||||
|
||||
auto axis1 = cross(vec3d{ _normal.x, _normal.y, _normal.z }, vec3d{ 0.f, 1.f, 0.f });
|
||||
auto faxis1 = float3 { axis1.x, axis1.y, axis1.z };
|
||||
faxis1.normalized();
|
||||
auto axis2 = cross(vec3d{ _normal.x, _normal.y, _normal.z }, axis1);
|
||||
auto faxis2 = float3 { axis2.x, axis2.y, axis2.z };
|
||||
faxis2.normalized();
|
||||
|
||||
matrix4 basis = matrix4::identity();
|
||||
basis(0, 0) = faxis1.x;
|
||||
basis(0, 1) = faxis1.y;
|
||||
basis(0, 2) = faxis1.z;
|
||||
|
||||
basis(1, 0) = faxis2.x;
|
||||
basis(1, 1) = faxis2.y;
|
||||
basis(1, 2) = faxis2.z;
|
||||
|
||||
basis(2, 0) = _normal.x;
|
||||
basis(2, 1) = _normal.y;
|
||||
basis(2, 2) = _normal.z;
|
||||
|
||||
const int segments = 50;
|
||||
for (int i = 0; i < segments; i++)
|
||||
{
|
||||
auto t1 = 2.f * float(M_PI) * ((float)i / segments);
|
||||
auto t2 = 2.f * float(M_PI) * ((float)(i+1) / segments);
|
||||
float4 xy1 { cosf(t1) * size, sinf(t1) * size, 0.f, 1.f };
|
||||
xy1 = basis * xy1;
|
||||
xy1 = float4 { _picked.x + xy1.x, _picked.y + xy1.y, _picked.z + xy1.z, 1.f };
|
||||
float4 xy2 { cosf(t1) * size * 0.5f, sinf(t1) * size * 0.5f, 0.f, 1.f };
|
||||
xy2 = basis * xy2;
|
||||
xy2 = float4 { _picked.x + xy2.x, _picked.y + xy2.y, _picked.z + xy2.z, 1.f };
|
||||
float4 xy3 { cosf(t2) * size * 0.5f, sinf(t2) * size * 0.5f, 0.f, 1.f };
|
||||
xy3 = basis * xy3;
|
||||
xy3 = float4 { _picked.x + xy3.x, _picked.y + xy3.y, _picked.z + xy3.z, 1.f };
|
||||
float4 xy4 { cosf(t2) * size, sinf(t2) * size, 0.f, 1.f };
|
||||
xy4 = basis * xy4;
|
||||
xy4 = float4 { _picked.x + xy4.x, _picked.y + xy4.y, _picked.z + xy4.z, 1.f };
|
||||
//glVertex3fv(&_picked.x);
|
||||
|
||||
glColor4f(white.x, white.y, white.z, 0.5f);
|
||||
glVertex3fv(&xy1.x);
|
||||
glColor4f(white.x, white.y, white.z, 0.8f);
|
||||
glVertex3fv(&xy2.x);
|
||||
glVertex3fv(&xy3.x);
|
||||
|
||||
glColor4f(white.x, white.y, white.z, 0.5f);
|
||||
glVertex3fv(&xy1.x);
|
||||
glVertex3fv(&xy4.x);
|
||||
glColor4f(white.x, white.y, white.z, 0.8f);
|
||||
glVertex3fv(&xy3.x);
|
||||
}
|
||||
//glVertex3fv(&_picked.x); glVertex3fv(&end.x);
|
||||
glEnd();
|
||||
|
||||
if (state.points.size() == 1 || (shift && state.points.size()))
|
||||
{
|
||||
auto p0 = (last_hovered_point >= 0 && last_hovered_point < state.points.size())
|
||||
? state.points[last_hovered_point] : state.points.back();
|
||||
draw_ruler(win, _picked, p0.pos, win.framebuf_height(), 2);
|
||||
}
|
||||
|
||||
glDisable(GL_BLEND);
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
||||
glEnable(GL_BLEND);
|
||||
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
|
||||
|
||||
hovered_edge_id = edge_hovered(win);
|
||||
|
||||
for (auto&& poly : state.polygons)
|
||||
{
|
||||
auto ancor = state.points[poly.front()];
|
||||
|
||||
std::vector<float3> points;
|
||||
points.push_back(ancor.pos);
|
||||
|
||||
auto mid = ancor.pos;
|
||||
|
||||
glDisable(GL_DEPTH_TEST);
|
||||
|
||||
glBegin(GL_TRIANGLES);
|
||||
glColor4f(light_blue.x, light_blue.y, light_blue.z, 0.3f);
|
||||
for (int i = 0; i < poly.size() - 1; i++)
|
||||
{
|
||||
auto b = state.points[poly[i]];
|
||||
auto c = state.points[poly[i+1]];
|
||||
glVertex3fv(&ancor.pos.x);
|
||||
glVertex3fv(&b.pos.x);
|
||||
glVertex3fv(&c.pos.x);
|
||||
mid = mid + c.pos;
|
||||
points.push_back(c.pos);
|
||||
}
|
||||
glEnd();
|
||||
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
|
||||
mid = mid * (1.f / poly.size());
|
||||
|
||||
auto area = calculate_area(points);
|
||||
|
||||
draw_label(win, mid, area, int(win.framebuf_height()), true);
|
||||
}
|
||||
|
||||
for (int i = 0; i < state.edges.size(); i++)
|
||||
{
|
||||
auto&& pair = state.edges[i];
|
||||
glDisable(GL_DEPTH_TEST);
|
||||
int selected = 1;
|
||||
if (hovered_edge_id >= 0)
|
||||
selected = hovered_edge_id == i ? 2 : 0;
|
||||
draw_ruler(win, state.points[pair.second].pos, state.points[pair.first].pos, win.framebuf_height(), selected);
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
||||
if (win.get_mouse().mouse_down[1]) {
|
||||
commit_state();
|
||||
state.points.clear();
|
||||
state.edges.clear();
|
||||
state.polygons.clear();
|
||||
}
|
||||
|
||||
for (auto&& points: state.points)
|
||||
{
|
||||
glColor4f(light_blue.x, light_blue.y, light_blue.z, 0.9f);
|
||||
draw_sphere(points.pos, 0.011f, 20, 20);
|
||||
}
|
||||
glDisable(GL_DEPTH_TEST);
|
||||
|
||||
current_hovered_point = -1;
|
||||
measurement_point_hovered = false;
|
||||
int hovered_point = point_hovered(win);
|
||||
if (hovered_point >= 0)
|
||||
{
|
||||
if (!shift) last_hovered_point = hovered_point;
|
||||
current_hovered_point = hovered_point;
|
||||
if (!input_ctrl.prev_mouse_down && win.get_mouse().mouse_down[0])
|
||||
{
|
||||
dragging_point_index = hovered_point;
|
||||
measurement_point_hovered = true;
|
||||
if (input_ctrl.click_period() > 0.5f)
|
||||
{
|
||||
dragging_measurement_point = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int i = 0;
|
||||
for (auto&& points: state.points)
|
||||
{
|
||||
if (measurement_point_hovered)
|
||||
glColor4f(white.x, white.y, white.z, dragging_point_index == i ? 0.8f : 0.1f);
|
||||
else
|
||||
glColor4f(white.x, white.y, white.z, 0.6f);
|
||||
|
||||
draw_sphere(points.pos, dragging_point_index == i ? 0.012f : 0.008f, 20, 20);
|
||||
i++;
|
||||
}
|
||||
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
glDisable(GL_BLEND);
|
||||
|
||||
if (!win.get_mouse().mouse_down[0] || input_ctrl.click_period() < 0.5f)
|
||||
{
|
||||
if (dragging_measurement_point && state.points.size() >= 2)
|
||||
{
|
||||
dragging_measurement_point = false;
|
||||
input_ctrl.click_time = 0;
|
||||
|
||||
for (auto&& e : state.edges)
|
||||
{
|
||||
if (e.first == dragging_point_index || e.second == dragging_point_index)
|
||||
{
|
||||
auto dist = state.points[e.first].pos - state.points[e.second].pos;
|
||||
log_function( rsutils::string::from() << "Adjusted measurement to " << length_to_string(dist.length()));
|
||||
}
|
||||
}
|
||||
|
||||
for (auto&& path : state.polygons)
|
||||
{
|
||||
if (std::find(path.begin(), path.end(), dragging_point_index) != path.end())
|
||||
{
|
||||
std::vector<float3> poly;
|
||||
for (auto&& idx : path) poly.push_back(state.points[idx].pos);
|
||||
|
||||
auto area = calculate_area(poly);
|
||||
log_function( rsutils::string::from() << "Adjusted area of " << area_to_string(area));
|
||||
}
|
||||
}
|
||||
|
||||
commit_state();
|
||||
}
|
||||
dragging_point_index = -1;
|
||||
}
|
||||
if (dragging_measurement_point && dragging_point_index >= 0)
|
||||
{
|
||||
state.points[dragging_point_index].pos = _picked;
|
||||
}
|
||||
|
||||
if (point_hovered(win) >= 0 || hovered_edge_id >= 0)
|
||||
win.link_hovered();
|
||||
}
|
||||
|
||||
void measurement::show_tooltip(ux_window& win)
|
||||
{
|
||||
if (mouse_picked_event.eval() && ImGui::IsWindowHovered())
|
||||
{
|
||||
if (display_mouse_picked_tooltip() && hovered_edge_id < 0)
|
||||
{
|
||||
std::string tt = rsutils::string::from() << std::fixed << std::setprecision(3)
|
||||
<< _picked.x << ", " << _picked.y << ", " << _picked.z << " meters";
|
||||
RsImGui::CustomTooltip("%s", tt.c_str());
|
||||
}
|
||||
}
|
||||
}
|
||||
104
librealsense-r-256/common/measurement.h
Normal file
104
librealsense-r-256/common/measurement.h
Normal file
@@ -0,0 +1,104 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
#include "device-model.h"
|
||||
|
||||
#include <vector>
|
||||
#include <functional>
|
||||
#include <string>
|
||||
#include <set>
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
struct interest_point
|
||||
{
|
||||
float3 pos;
|
||||
float3 normal;
|
||||
|
||||
bool operator==(const interest_point& other) const
|
||||
{
|
||||
return (pos - other.pos).length() < 0.001f;
|
||||
}
|
||||
};
|
||||
|
||||
struct measurement_state
|
||||
{
|
||||
std::vector<interest_point> points;
|
||||
std::vector<std::pair<int, int>> edges;
|
||||
std::vector<std::vector<int>> polygons;
|
||||
|
||||
bool operator==(const measurement_state& other) const
|
||||
{
|
||||
return points == other.points && edges == other.edges && polygons == other.polygons;
|
||||
}
|
||||
|
||||
std::vector<int> find_path(int from, int to);
|
||||
};
|
||||
|
||||
class measurement
|
||||
{
|
||||
public:
|
||||
void enable();
|
||||
void disable();
|
||||
bool is_enabled() const;
|
||||
|
||||
bool display_mouse_picked_tooltip() const;
|
||||
bool manipulating() const;
|
||||
|
||||
void add_point(interest_point p);
|
||||
|
||||
void commit_state();
|
||||
void restore_state();
|
||||
|
||||
float calculate_area(std::vector<float3> points);
|
||||
|
||||
std::string length_to_string(float distance);
|
||||
std::string area_to_string(float area);
|
||||
rs2::float2 project_to_2d(rs2::float3 pos);
|
||||
void draw_label(ux_window& win, float3 pos, float distance, int height, bool is_area = false);
|
||||
void draw_ruler(ux_window& win, float3 from, float3 to, float height, int selected);
|
||||
void draw(ux_window& win);
|
||||
|
||||
void show_tooltip(ux_window& win);
|
||||
void mouse_pick(ux_window& win, float3 picked, float3 normal);
|
||||
void update_input(ux_window& win, const rs2::rect& viewer_rect);
|
||||
|
||||
std::function<void(std::string)> log_function = [](std::string) {};
|
||||
std::function<bool()> is_metric = [](){ return true; };
|
||||
|
||||
private:
|
||||
int point_hovered(ux_window& win);
|
||||
int edge_hovered(ux_window& win);
|
||||
|
||||
interest_point selection_point;
|
||||
|
||||
measurement_state state;
|
||||
std::deque<measurement_state> state_history;
|
||||
|
||||
bool dragging_measurement_point = false;
|
||||
int dragging_point_index = -1;
|
||||
bool measurement_point_hovered = false;
|
||||
bool measurement_active = false;
|
||||
int hovered_edge_id = -1;
|
||||
int last_hovered_point = -1;
|
||||
int current_hovered_point = -1;
|
||||
|
||||
temporal_event mouse_picked_event { std::chrono::milliseconds(1000) };
|
||||
float3 _normal, _picked;
|
||||
|
||||
struct mouse_control
|
||||
{
|
||||
bool mouse_down = false;
|
||||
bool prev_mouse_down = false;
|
||||
bool click = false;
|
||||
double selection_started = 0.0;
|
||||
float2 down_pos { 0.f, 0.f };
|
||||
int mouse_wheel = 0;
|
||||
float click_time = 0.f;
|
||||
float click_period() { return clamp(float(glfwGetTime() - click_time) * 10, 0.f, 1.f); }
|
||||
};
|
||||
mouse_control input_ctrl;
|
||||
int id = 0;
|
||||
};
|
||||
}
|
||||
366
librealsense-r-256/common/metadata-helper.cpp
Normal file
366
librealsense-r-256/common/metadata-helper.cpp
Normal file
@@ -0,0 +1,366 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2023 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#include "metadata-helper.h"
|
||||
|
||||
#ifdef WIN32
|
||||
|
||||
#include <Windows.h>
|
||||
#include <memory>
|
||||
#include <vector>
|
||||
#include <algorithm>
|
||||
#include <iterator>
|
||||
|
||||
#include <regex>
|
||||
#include <iostream>
|
||||
#include <sstream>
|
||||
#include <functional>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
|
||||
#include <librealsense2/rs.hpp>
|
||||
#include <rsutils/string/windows.h>
|
||||
|
||||
#define MAX_KEY_LENGTH 255
|
||||
#define MAX_VALUE_NAME 16383
|
||||
|
||||
#ifdef _MSC_VER
|
||||
#define strncasecmp _strnicmp
|
||||
#define strcasecmp _stricmp
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
#ifdef WIN32
|
||||
struct device_id
|
||||
{
|
||||
std::string pid, mi, guid, sn;
|
||||
};
|
||||
|
||||
inline bool equal(const std::string& a, const std::string& b)
|
||||
{
|
||||
return strcasecmp(a.c_str(), b.c_str()) == 0;
|
||||
}
|
||||
|
||||
inline bool operator==(const device_id& a, const device_id& b)
|
||||
{
|
||||
return equal(a.pid, b.pid) &&
|
||||
equal(a.guid, b.guid) &&
|
||||
equal(a.mi, b.mi) &&
|
||||
equal(a.sn, b.sn);
|
||||
}
|
||||
|
||||
class windows_metadata_helper : public metadata_helper
|
||||
{
|
||||
using super = metadata_helper;
|
||||
|
||||
public:
|
||||
static bool parse_device_id(const std::string& id, device_id* res)
|
||||
{
|
||||
static const std::regex regex("pid_([0-9a-f]+)&mi_([0-9a-f]+)#[0-9a-f]&([0-9a-f]+)&[\\s\\S]*\\{([0-9a-f]{8}-[0-9a-f]{4}-[0-9a-f]{4}-[0-9a-f]{4}-[0-9a-f]{12})\\}", std::regex_constants::icase);
|
||||
|
||||
std::match_results<std::string::const_iterator> match;
|
||||
|
||||
if (std::regex_search(id, match, regex) && match.size() > 4)
|
||||
{
|
||||
res->pid = match[1];
|
||||
res->mi = match[2];
|
||||
res->sn = match[3];
|
||||
res->guid = match[4];
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static void foreach_device_path(const std::vector<device_id>& devices,
|
||||
std::function<void(const device_id&, /* matched device */
|
||||
std::wstring /* registry key of Device Parameters for that device */)> action)
|
||||
{
|
||||
std::map<std::string, std::vector<device_id>> guid_to_devices;
|
||||
for (auto&& d : devices)
|
||||
{
|
||||
guid_to_devices[d.guid].push_back(d);
|
||||
}
|
||||
|
||||
for (auto&& kvp : guid_to_devices)
|
||||
{
|
||||
auto guid = kvp.first;
|
||||
|
||||
std::stringstream ss;
|
||||
ss << "SYSTEM\\CurrentControlSet\\Control\\DeviceClasses\\{" << guid << "}";
|
||||
auto s = ss.str();
|
||||
std::wstring prefix(s.begin(), s.end());
|
||||
|
||||
HKEY key;
|
||||
if (RegOpenKeyEx(HKEY_LOCAL_MACHINE, prefix.c_str(), 0, KEY_READ | KEY_WOW64_64KEY, &key) == ERROR_SUCCESS)
|
||||
{
|
||||
// Don't forget to release in the end:
|
||||
std::shared_ptr<void> raii(key, RegCloseKey);
|
||||
|
||||
TCHAR achClass[MAX_PATH] = TEXT(""); // buffer for class name
|
||||
DWORD cchClassName = MAX_PATH; // size of class string
|
||||
DWORD cSubKeys = 0; // number of subkeys
|
||||
DWORD cbMaxSubKey; // longest subkey size
|
||||
DWORD cchMaxClass; // longest class string
|
||||
DWORD cValues; // number of values for key
|
||||
DWORD cchMaxValue; // longest value name
|
||||
DWORD cbMaxValueData; // longest value data
|
||||
DWORD cbSecurityDescriptor; // size of security descriptor
|
||||
FILETIME ftLastWriteTime; // last write time
|
||||
|
||||
DWORD retCode = RegQueryInfoKey(
|
||||
key, // key handle
|
||||
achClass, // buffer for class name
|
||||
&cchClassName, // size of class string
|
||||
NULL, // reserved
|
||||
&cSubKeys, // number of subkeys
|
||||
&cbMaxSubKey, // longest subkey size
|
||||
&cchMaxClass, // longest class string
|
||||
&cValues, // number of values for this key
|
||||
&cchMaxValue, // longest value name
|
||||
&cbMaxValueData, // longest value data
|
||||
&cbSecurityDescriptor, // security descriptor
|
||||
&ftLastWriteTime); // last write time
|
||||
|
||||
for (auto i = 0ul; i < cSubKeys; i++)
|
||||
{
|
||||
TCHAR achKey[MAX_KEY_LENGTH];
|
||||
DWORD cbName = MAX_KEY_LENGTH;
|
||||
retCode = RegEnumKeyEx(key, i,
|
||||
achKey,
|
||||
&cbName,
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
&ftLastWriteTime);
|
||||
if (retCode == ERROR_SUCCESS)
|
||||
{
|
||||
std::wstring suffix = achKey;
|
||||
device_id rdid;
|
||||
|
||||
std::string a = rsutils::string::windows::win_to_utf( suffix.c_str() );
|
||||
|
||||
if (parse_device_id(a, &rdid))
|
||||
{
|
||||
for (auto&& did : kvp.second)
|
||||
{
|
||||
if (rdid == did)
|
||||
{
|
||||
std::wstringstream ss;
|
||||
ss << prefix << "\\" << suffix << "\\#GLOBAL\\Device Parameters";
|
||||
auto path = ss.str();
|
||||
action(rdid, path);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Heuristic that determines how many media-pins UVC device is expected to have
|
||||
static int number_of_mediapins(const std::string& pid, const std::string& mi)
|
||||
{
|
||||
if (mi == "00")
|
||||
{
|
||||
// D405 has 3 media-pins
|
||||
if (equal(pid, "0b5b")) return 3;
|
||||
else return 2; // D400 has two
|
||||
}
|
||||
return 1; // RGB has one
|
||||
}
|
||||
|
||||
bool is_running_as_admin()
|
||||
{
|
||||
BOOL result = FALSE;
|
||||
PSID admin_group = NULL;
|
||||
|
||||
SID_IDENTIFIER_AUTHORITY ntauthority = SECURITY_NT_AUTHORITY;
|
||||
if (!AllocateAndInitializeSid(
|
||||
&ntauthority,
|
||||
2,
|
||||
SECURITY_BUILTIN_DOMAIN_RID,
|
||||
DOMAIN_ALIAS_RID_ADMINS,
|
||||
0, 0, 0, 0, 0, 0,
|
||||
&admin_group))
|
||||
{
|
||||
rs2::log(RS2_LOG_SEVERITY_WARN, "Unable to query permissions - AllocateAndInitializeSid failed");
|
||||
return false;
|
||||
}
|
||||
std::shared_ptr<void> raii(admin_group, FreeSid);
|
||||
|
||||
if (!CheckTokenMembership(NULL, admin_group, &result))
|
||||
{
|
||||
rs2::log(RS2_LOG_SEVERITY_WARN, "Unable to query permissions - CheckTokenMembership failed");
|
||||
return false;
|
||||
}
|
||||
|
||||
return result == TRUE;
|
||||
}
|
||||
|
||||
void enable_metadata_with_new_admin_process()
|
||||
{
|
||||
wchar_t szPath[MAX_PATH];
|
||||
if (GetModuleFileName(NULL, szPath, ARRAYSIZE(szPath)))
|
||||
{
|
||||
SHELLEXECUTEINFO sei = { sizeof(sei) };
|
||||
|
||||
sei.lpVerb = L"runas";
|
||||
sei.fMask = SEE_MASK_NOCLOSEPROCESS;
|
||||
sei.lpFile = szPath;
|
||||
sei.hwnd = NULL;
|
||||
sei.nShow = SW_NORMAL;
|
||||
auto cmd_line = get_command_line_param();
|
||||
std::wstring wcmd(cmd_line.begin(), cmd_line.end());
|
||||
sei.lpParameters = wcmd.c_str();
|
||||
|
||||
if (!ShellExecuteEx(&sei))
|
||||
{
|
||||
auto errstr = std::system_category().message(GetLastError());
|
||||
std::string msg = "Unable to elevate to admin privilege to enable metadata! " + errstr;
|
||||
rs2::log(RS2_LOG_SEVERITY_WARN, msg.c_str());
|
||||
}
|
||||
else
|
||||
{
|
||||
WaitForSingleObject(sei.hProcess, INFINITE);
|
||||
DWORD exitCode = 0;
|
||||
GetExitCodeProcess(sei.hProcess, &exitCode);
|
||||
CloseHandle(sei.hProcess);
|
||||
if (exitCode)
|
||||
throw std::runtime_error("Failed to set metadata registry keys!");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
rs2::log(RS2_LOG_SEVERITY_WARN, "Unable to fetch module name!");
|
||||
}
|
||||
}
|
||||
|
||||
bool is_enabled(std::string id) const override
|
||||
{
|
||||
device_id did;
|
||||
if( ! parse_device_id( id, &did ) )
|
||||
// If it's not parsed, it's not a valid USB device; return the default
|
||||
return super::is_enabled( id );
|
||||
|
||||
bool res = false;
|
||||
foreach_device_path({ did }, [&res, did](const device_id&, std::wstring path) {
|
||||
|
||||
HKEY key;
|
||||
if (RegOpenKeyEx(HKEY_LOCAL_MACHINE, path.c_str(), 0, KEY_READ | KEY_WOW64_64KEY, &key) == ERROR_SUCCESS)
|
||||
{
|
||||
// Don't forget to release in the end:
|
||||
std::shared_ptr<void> raii(key, RegCloseKey);
|
||||
|
||||
bool found = true;
|
||||
DWORD len = sizeof(DWORD);//size of data
|
||||
|
||||
for (int i = 0; i < number_of_mediapins(did.pid, did.mi); i++)
|
||||
{
|
||||
std::wstringstream ss; ss << L"MetadataBufferSizeInKB" << i;
|
||||
std::wstring metadatakey = ss.str();
|
||||
|
||||
DWORD MetadataBufferSizeInKB = 0;
|
||||
if (RegQueryValueEx(
|
||||
key,
|
||||
metadatakey.c_str(),
|
||||
NULL,
|
||||
NULL,
|
||||
(LPBYTE)(&MetadataBufferSizeInKB),
|
||||
&len) != ERROR_SUCCESS)
|
||||
rs2::log(RS2_LOG_SEVERITY_DEBUG, "Unable to read metadata registry key!");
|
||||
|
||||
found = found && MetadataBufferSizeInKB;
|
||||
}
|
||||
|
||||
if (found) res = true;
|
||||
}
|
||||
});
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
void enable_metadata() override
|
||||
{
|
||||
if (!is_running_as_admin())
|
||||
{
|
||||
enable_metadata_with_new_admin_process();
|
||||
}
|
||||
else
|
||||
{
|
||||
std::vector<device_id> dids;
|
||||
|
||||
rs2::context ctx;
|
||||
auto list = ctx.query_devices();
|
||||
for (uint32_t i = 0; i < list.size(); i++)
|
||||
{
|
||||
try
|
||||
{
|
||||
rs2::device dev = list[i];
|
||||
|
||||
if (dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE))
|
||||
{
|
||||
std::string product = dev.get_info(RS2_CAMERA_INFO_PRODUCT_LINE);
|
||||
if (can_support_metadata(product))
|
||||
{
|
||||
for (auto sen : dev.query_sensors())
|
||||
{
|
||||
if (sen.supports(RS2_CAMERA_INFO_PHYSICAL_PORT))
|
||||
{
|
||||
std::string port = sen.get_info(RS2_CAMERA_INFO_PHYSICAL_PORT);
|
||||
device_id did;
|
||||
if (parse_device_id(port, &did))
|
||||
dids.push_back(did);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
catch (...) {}
|
||||
}
|
||||
|
||||
bool failure = false;
|
||||
foreach_device_path(dids, [&failure](const device_id& did, std::wstring path) {
|
||||
HKEY key;
|
||||
if (RegOpenKeyEx(HKEY_LOCAL_MACHINE, path.c_str(), 0, KEY_WRITE | KEY_WOW64_64KEY, &key) == ERROR_SUCCESS)
|
||||
{
|
||||
// Don't forget to release in the end:
|
||||
std::shared_ptr<void> raii(key, RegCloseKey);
|
||||
|
||||
bool found = true;
|
||||
DWORD len = sizeof(DWORD);//size of data
|
||||
|
||||
for (int i = 0; i < number_of_mediapins(did.pid, did.mi); i++)
|
||||
{
|
||||
std::wstringstream ss; ss << L"MetadataBufferSizeInKB" << i;
|
||||
std::wstring metadatakey = ss.str();
|
||||
|
||||
DWORD MetadataBufferSizeInKB = 5;
|
||||
if (RegSetValueEx(key, metadatakey.c_str(), 0, REG_DWORD,
|
||||
(const BYTE*)&MetadataBufferSizeInKB, sizeof(DWORD)) != ERROR_SUCCESS)
|
||||
{
|
||||
rs2::log(RS2_LOG_SEVERITY_DEBUG, "Unable to write metadata registry key!");
|
||||
failure = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
});
|
||||
if (failure) throw std::runtime_error("Unable to write to metadata registry key!");
|
||||
}
|
||||
}
|
||||
};
|
||||
#endif
|
||||
|
||||
metadata_helper& metadata_helper::instance()
|
||||
{
|
||||
#ifdef WIN32
|
||||
static windows_metadata_helper instance;
|
||||
#else
|
||||
static metadata_helper instance;
|
||||
#endif
|
||||
return instance;
|
||||
}
|
||||
}
|
||||
34
librealsense-r-256/common/metadata-helper.h
Normal file
34
librealsense-r-256/common/metadata-helper.h
Normal file
@@ -0,0 +1,34 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2023 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
// Helper class that is responsible for enabling per-frame metadata on different platforms
|
||||
// Currently implemented for Windows
|
||||
class metadata_helper
|
||||
{
|
||||
public:
|
||||
static metadata_helper& instance();
|
||||
|
||||
// Check if metadata is enabled using Physical Port ID
|
||||
// (can be retrieved with device::get_info(RS2_CAMERA_INFO_PHYSICAL_PORT))
|
||||
// throws runtime_error in case of errors
|
||||
virtual bool is_enabled(std::string id) const { return true; }
|
||||
|
||||
// Enable metadata for all connected devices
|
||||
// throws runtime_error in case of errors
|
||||
virtual void enable_metadata() { }
|
||||
|
||||
static bool can_support_metadata(const std::string& product)
|
||||
{
|
||||
return product == "D400" || product == "D500";
|
||||
}
|
||||
|
||||
// This is the command-line parameter that gets passed to another process (running as admin) in order to enable metadata -- see WinMain
|
||||
static std::string get_command_line_param() { return "--enable_metadata"; }
|
||||
};
|
||||
}
|
||||
413
librealsense-r-256/common/model-views.cpp
Normal file
413
librealsense-r-256/common/model-views.cpp
Normal file
@@ -0,0 +1,413 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#ifdef _MSC_VER
|
||||
#ifndef NOMINMAX
|
||||
#define NOMINMAX
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include <librealsense2/rs.hpp>
|
||||
|
||||
#include <realsense_imgui.h>
|
||||
#include "model-views.h"
|
||||
#include "subdevice-model.h"
|
||||
#include "stream-model.h"
|
||||
#include "updates-model.h"
|
||||
#include "notifications.h"
|
||||
#include "fw-update-helper.h"
|
||||
#include "on-chip-calib.h"
|
||||
#include "viewer.h"
|
||||
#include "post-processing-filters-list.h"
|
||||
#include "post-processing-block-model.h"
|
||||
#include <imgui_internal.h>
|
||||
#include <time.h>
|
||||
#include "ux-window.h"
|
||||
|
||||
#include "imgui-fonts-karla.hpp"
|
||||
#include "imgui-fonts-fontawesome.hpp"
|
||||
#include "imgui-fonts-monofont.hpp"
|
||||
|
||||
#include "os.h"
|
||||
|
||||
#include "metadata-helper.h"
|
||||
#include "calibration-model.h"
|
||||
#include "sw-update/http-downloader.h"
|
||||
|
||||
#include <thread>
|
||||
#include <algorithm>
|
||||
#include <regex>
|
||||
#include <cmath>
|
||||
|
||||
#include "opengl3.h"
|
||||
|
||||
ImVec4 flip(const ImVec4& c)
|
||||
{
|
||||
return{ c.y, c.x, c.z, c.w };
|
||||
}
|
||||
|
||||
ImVec4 from_rgba(uint8_t r, uint8_t g, uint8_t b, uint8_t a, bool consistent_color)
|
||||
{
|
||||
auto res = ImVec4(r / (float)255, g / (float)255, b / (float)255, a / (float)255);
|
||||
#ifdef FLIP_COLOR_SCHEME
|
||||
if (!consistent_color) return flip(res);
|
||||
#endif
|
||||
return res;
|
||||
}
|
||||
|
||||
ImVec4 operator+(const ImVec4& c, float v)
|
||||
{
|
||||
return ImVec4(
|
||||
std::max(0.f, std::min(1.f, c.x + v)),
|
||||
std::max(0.f, std::min(1.f, c.y + v)),
|
||||
std::max(0.f, std::min(1.f, c.z + v)),
|
||||
std::max(0.f, std::min(1.f, c.w))
|
||||
);
|
||||
}
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
std::vector<uint8_t> bytes_from_bin_file(const std::string& filename)
|
||||
{
|
||||
std::ifstream file(filename.c_str(), std::ios::binary);
|
||||
if (!file.good())
|
||||
throw std::runtime_error( rsutils::string::from() << "Invalid binary file specified " << filename
|
||||
<< " verify the source path and location permissions" );
|
||||
|
||||
// Determine the file length
|
||||
file.seekg(0, std::ios_base::end);
|
||||
std::size_t size = file.tellg();
|
||||
if (!size)
|
||||
throw std::runtime_error( rsutils::string::from()
|
||||
<< "Invalid binary file " << filename << " provided - zero-size " );
|
||||
file.seekg(0, std::ios_base::beg);
|
||||
|
||||
// Create a vector to store the data
|
||||
std::vector<uint8_t> v(size);
|
||||
|
||||
// Load the data
|
||||
file.read((char*)&v[0], size);
|
||||
|
||||
return v;
|
||||
}
|
||||
|
||||
// Flush binary stream to file, override previous if exists
|
||||
void bin_file_from_bytes(const std::string& filename, const std::vector<uint8_t> bytes)
|
||||
{
|
||||
std::ofstream file(filename, std::ios::binary | std::ios::trunc);
|
||||
if (!file.good())
|
||||
throw std::runtime_error( rsutils::string::from() << "Invalid binary file specified " << filename
|
||||
<< " verify the target path and location permissions" );
|
||||
file.write((char*)bytes.data(), bytes.size());
|
||||
}
|
||||
|
||||
void hyperlink(ux_window& window, const char* title, const char* link)
|
||||
{
|
||||
if (ImGui::Button(title))
|
||||
{
|
||||
open_url(link);
|
||||
}
|
||||
if (ImGui::IsItemHovered())
|
||||
{
|
||||
window.link_hovered();
|
||||
}
|
||||
}
|
||||
|
||||
std::tuple<uint8_t, uint8_t, uint8_t> get_texcolor(video_frame texture, texture_coordinate texcoords)
|
||||
{
|
||||
const int w = texture.get_width(), h = texture.get_height();
|
||||
int x = std::min(std::max(int(texcoords.u*w + .5f), 0), w - 1);
|
||||
int y = std::min(std::max(int(texcoords.v*h + .5f), 0), h - 1);
|
||||
int idx = x * texture.get_bytes_per_pixel() + y * texture.get_stride_in_bytes();
|
||||
const auto texture_data = reinterpret_cast<const uint8_t*>(texture.get_data());
|
||||
return std::tuple<uint8_t, uint8_t, uint8_t>(
|
||||
texture_data[idx], texture_data[idx + 1], texture_data[idx + 2]);
|
||||
}
|
||||
|
||||
void export_frame(const std::string& fname, std::unique_ptr<rs2::filter> exporter,
|
||||
notifications_model& ns, frame data, bool notify)
|
||||
{
|
||||
auto manager = std::make_shared<export_manager>(fname, std::move(exporter), data);
|
||||
|
||||
auto n = std::make_shared<export_notification_model>(manager);
|
||||
ns.add_notification(n);
|
||||
n->forced = true;
|
||||
|
||||
auto invoke = [n](std::function<void()> action) {
|
||||
n->invoke(action);
|
||||
};
|
||||
manager->start(invoke);
|
||||
}
|
||||
|
||||
bool save_frame_raw_data(const std::string& filename, rs2::frame frame)
|
||||
{
|
||||
bool ret = false;
|
||||
auto image = frame.as<video_frame>();
|
||||
if (image)
|
||||
{
|
||||
std::ofstream outfile(filename.data(), std::ofstream::binary);
|
||||
outfile.write(static_cast<const char*>(image.get_data()), image.get_height()*image.get_stride_in_bytes());
|
||||
|
||||
outfile.close();
|
||||
ret = true;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool frame_metadata_to_csv(const std::string& filename, rs2::frame frame)
|
||||
{
|
||||
bool ret = false;
|
||||
auto image = frame.as<video_frame>();
|
||||
if (image)
|
||||
{
|
||||
std::ofstream csv(filename);
|
||||
|
||||
auto profile = image.get_profile();
|
||||
csv << "Frame Info: " << std::endl << "Type," << profile.stream_name() << std::endl;
|
||||
csv << "Format," << rs2_format_to_string(profile.format()) << std::endl;
|
||||
csv << "Frame Number," << image.get_frame_number() << std::endl;
|
||||
csv << "Timestamp (ms)," << std::fixed << std::setprecision(2) << image.get_timestamp() << std::endl;
|
||||
csv << "Resolution x," << (int)image.get_width() << std::endl;
|
||||
csv << "Resolution y," << (int)image.get_height() << std::endl;
|
||||
csv << "Bytes per pixel," << (int)image.get_bytes_per_pixel() << std::endl;
|
||||
|
||||
if (auto vsp = profile.as<video_stream_profile>())
|
||||
{
|
||||
auto intrinsics = vsp.get_intrinsics();
|
||||
csv << std::endl << "Intrinsic:," << std::fixed << std::setprecision(6) << std::endl;
|
||||
csv << "Fx," << intrinsics.fx << std::endl;
|
||||
csv << "Fy," << intrinsics.fy << std::endl;
|
||||
csv << "PPx," << intrinsics.ppx << std::endl;
|
||||
csv << "PPy," << intrinsics.ppy << std::endl;
|
||||
csv << "Distorsion," << rs2_distortion_to_string(intrinsics.model) << std::endl;
|
||||
}
|
||||
|
||||
ret = true;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool motion_data_to_csv( const std::string & filename, rs2::frame frame )
|
||||
{
|
||||
bool ret = false;
|
||||
if( auto motion = frame.as< motion_frame >() )
|
||||
{
|
||||
std::string units;
|
||||
if( motion.get_profile().stream_type() == RS2_STREAM_GYRO )
|
||||
units = "( deg/sec )";
|
||||
else
|
||||
units = "( m/sec^2 )";
|
||||
auto axes = motion.get_motion_data();
|
||||
std::ofstream csv( filename );
|
||||
|
||||
auto profile = frame.get_profile();
|
||||
csv << "Frame Info: " << std::endl << "Type," << profile.stream_name() << std::endl;
|
||||
csv << "Format," << rs2_format_to_string( profile.format() ) << std::endl;
|
||||
csv << "Frame Number," << frame.get_frame_number() << std::endl;
|
||||
csv << "Timestamp (ms)," << std::fixed << std::setprecision( 2 )
|
||||
<< frame.get_timestamp() << std::endl;
|
||||
csv << std::setprecision( 7 ) << "Axes" << units << ", " << axes << std::endl;
|
||||
|
||||
ret = true;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool pose_data_to_csv( const std::string & filename, rs2::frame frame )
|
||||
{
|
||||
bool ret = false;
|
||||
if( auto pose = frame.as< pose_frame >() )
|
||||
{
|
||||
auto pose_data = pose.get_pose_data();
|
||||
std::ofstream csv( filename );
|
||||
|
||||
auto profile = frame.get_profile();
|
||||
csv << "Frame Info: " << std::endl << "Type," << profile.stream_name() << std::endl;
|
||||
csv << "Format," << rs2_format_to_string( profile.format() ) << std::endl;
|
||||
csv << "Frame Number," << frame.get_frame_number() << std::endl;
|
||||
csv << "Timestamp (ms)," << std::fixed << std::setprecision( 2 )
|
||||
<< frame.get_timestamp() << std::endl;
|
||||
csv << std::setprecision( 7 ) << "Acceleration( meters/sec^2 ), "
|
||||
<< pose_data.acceleration << std::endl;
|
||||
csv << std::setprecision( 7 ) << "Angular_acceleration( radians/sec^2 ), "
|
||||
<< pose_data.angular_acceleration << std::endl;
|
||||
csv << std::setprecision( 7 ) << "Angular_velocity( radians/sec ), "
|
||||
<< pose_data.angular_velocity << std::endl;
|
||||
csv << std::setprecision( 7 )
|
||||
<< "Mapper_confidence( 0x0 - Failed 0x1 - Low 0x2 - Medium 0x3 - High ), "
|
||||
<< pose_data.mapper_confidence << std::endl;
|
||||
csv << std::setprecision( 7 )
|
||||
<< "Rotation( quaternion rotation (relative to initial position) ), "
|
||||
<< pose_data.rotation << std::endl;
|
||||
csv << std::setprecision( 7 )
|
||||
<< "Tracker_confidence( 0x0 - Failed 0x1 - Low 0x2 - Medium 0x3 - High ), "
|
||||
<< pose_data.tracker_confidence << std::endl;
|
||||
csv << std::setprecision( 7 ) << "Translation( meters ), " << pose_data.translation
|
||||
<< std::endl;
|
||||
csv << std::setprecision( 7 ) << "Velocity( meters/sec ), " << pose_data.velocity
|
||||
<< std::endl;
|
||||
|
||||
ret = true;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
std::vector<std::string> get_device_info(const device& dev, bool include_location)
|
||||
{
|
||||
std::vector<std::string> res;
|
||||
for (auto i = 0; i < RS2_CAMERA_INFO_COUNT; i++)
|
||||
{
|
||||
auto info = static_cast<rs2_camera_info>(i);
|
||||
|
||||
// When camera is being reset, either because of "hardware reset"
|
||||
// or because of switch into advanced mode,
|
||||
// we don't want to capture the info that is about to change
|
||||
if ((info == RS2_CAMERA_INFO_PHYSICAL_PORT ||
|
||||
info == RS2_CAMERA_INFO_ADVANCED_MODE)
|
||||
&& !include_location) continue;
|
||||
|
||||
if (dev.supports(info))
|
||||
{
|
||||
auto value = dev.get_info(info);
|
||||
res.push_back(value);
|
||||
}
|
||||
}
|
||||
return res;
|
||||
}
|
||||
|
||||
bool yes_no_dialog(const std::string& title, const std::string& message_text, bool& approved, ux_window& window, const std::string& error_message, bool disabled, const std::string& disabled_reason)
|
||||
{
|
||||
RsImGui_ScopePushFont(window.get_font());
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_Button, button_color);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_ButtonHovered, sensor_header_light_blue); //TODO: Change color?
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_ButtonActive, regular_blue); //TODO: Change color?
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_TextSelectedBg, light_grey);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_TitleBg, header_color);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_PopupBg, sensor_bg);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_BorderShadow, dark_grey);
|
||||
RsImGui_ScopePushStyleVar(ImGuiStyleVar_WindowPadding, ImVec2(20, 10));
|
||||
auto clicked = false;
|
||||
|
||||
ImGui::OpenPopup(title.c_str());
|
||||
ImGui::SetNextWindowPos( {window.width() * 0.35f, window.height() * 0.35f });
|
||||
if (ImGui::BeginPopup(title.c_str()))
|
||||
{
|
||||
{
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_Text, almost_white_bg);
|
||||
|
||||
ImGui::SetWindowFontScale(1.3f);
|
||||
ImGui::Text("%s", title.c_str());
|
||||
}
|
||||
{
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_Text, light_grey);
|
||||
ImGui::Separator();
|
||||
ImGui::SetWindowFontScale(1.1f);
|
||||
ImGui::Text("\n%s\n", message_text.c_str());
|
||||
|
||||
if (!disabled)
|
||||
{
|
||||
ImGui::SameLine();
|
||||
auto width = ImGui::GetWindowWidth();
|
||||
ImGui::Dummy(ImVec2(0, 0));
|
||||
ImGui::Dummy(ImVec2(width / 3.f, 0));
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button("Yes", ImVec2(60, 30)))
|
||||
{
|
||||
ImGui::CloseCurrentPopup();
|
||||
approved = true;
|
||||
clicked = true;
|
||||
}
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button("No", ImVec2(60, 30)))
|
||||
{
|
||||
ImGui::CloseCurrentPopup();
|
||||
approved = false;
|
||||
clicked = true;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ImGui::NewLine();
|
||||
{
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_Text, red);
|
||||
ImGui::Text("%s\n\n", disabled_reason.c_str());
|
||||
}
|
||||
auto window_width = ImGui::GetWindowWidth();
|
||||
ImGui::SetCursorPosX(ImGui::GetCursorPosX() + window_width / 2.f - 30.f - ImGui::GetStyle().WindowPadding.x);
|
||||
if (ImGui::Button("Close", ImVec2(60, 30)))
|
||||
{
|
||||
ImGui::CloseCurrentPopup();
|
||||
approved = false;
|
||||
clicked = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
ImGui::EndPopup();
|
||||
}
|
||||
return clicked;
|
||||
}
|
||||
|
||||
// Create a process windows with process details from the caller,
|
||||
// and close button activated by the caller
|
||||
bool status_dialog(const std::string& title, const std::string& process_topic_text, const std::string& process_status_text , bool enable_close, ux_window& window)
|
||||
{
|
||||
RsImGui_ScopePushFont(window.get_font());
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_Button, button_color);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_ButtonHovered, sensor_header_light_blue); //TODO: Change color?
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_ButtonActive, regular_blue); //TODO: Change color?
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_Text, light_grey);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_TextSelectedBg, light_grey);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_TitleBg, header_color);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_PopupBg, sensor_bg);
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_BorderShadow, dark_grey);
|
||||
RsImGui_ScopePushStyleVar(ImGuiStyleVar_WindowPadding, ImVec2(20, 10));
|
||||
auto close_clicked = false;
|
||||
|
||||
ImGui::OpenPopup(title.c_str());
|
||||
ImGui::SetNextWindowPos({ window.width() * 0.35f, window.height() * 0.35f });
|
||||
if (ImGui::BeginPopup(title.c_str()))
|
||||
{
|
||||
{
|
||||
RsImGui_ScopePushStyleColor(ImGuiCol_Text, almost_white_bg);
|
||||
|
||||
ImGui::SetWindowFontScale(1.3f);
|
||||
ImGui::Text("%s", title.c_str());
|
||||
}
|
||||
{
|
||||
|
||||
ImGui::Separator();
|
||||
ImGui::SetWindowFontScale(1.1f);
|
||||
|
||||
ImGui::NewLine();
|
||||
ImGui::Text("%s", process_topic_text.c_str());
|
||||
ImGui::NewLine();
|
||||
|
||||
auto window_width = ImGui::GetWindowWidth();
|
||||
auto process_status_text_size = ImGui::CalcTextSize(process_status_text.c_str()).x + ImGui::CalcTextSize("Status: ").x + ImGui::GetStyle().WindowPadding.x;
|
||||
auto future_window_width = std::max(process_status_text_size, window_width);
|
||||
ImGui::SetCursorPosX(ImGui::GetCursorPosX() + future_window_width / 2.f - process_status_text_size / 2.f);
|
||||
|
||||
ImGui::Text("Status: %s", process_status_text.c_str());
|
||||
ImGui::NewLine();
|
||||
window_width = ImGui::GetWindowWidth();
|
||||
|
||||
if (enable_close)
|
||||
{
|
||||
ImGui::SetCursorPosX(ImGui::GetCursorPosX() + window_width / 2.f - 50.f); // 50 = 30 (button size) + 20 (padding)
|
||||
if (ImGui::Button("Close", ImVec2(60, 30)))
|
||||
{
|
||||
ImGui::CloseCurrentPopup();
|
||||
close_clicked = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
ImGui::EndPopup();
|
||||
}
|
||||
return close_clicked;
|
||||
}
|
||||
|
||||
}
|
||||
127
librealsense-r-256/common/model-views.h
Normal file
127
librealsense-r-256/common/model-views.h
Normal file
@@ -0,0 +1,127 @@
|
||||
// License: Apache 2.0. See LICENSE file in root directory.
|
||||
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.
|
||||
|
||||
#pragma once
|
||||
#include <librealsense2/rs.hpp>
|
||||
|
||||
#include "rendering.h"
|
||||
#include "ux-window.h"
|
||||
#include "parser.hpp"
|
||||
#include "rs-config.h"
|
||||
|
||||
#define GLFW_INCLUDE_GLU
|
||||
#include <GLFW/glfw3.h>
|
||||
#include "opengl3.h"
|
||||
#include <imgui.h>
|
||||
#include <realsense_imgui.h>
|
||||
#include <imgui_impl_glfw.h>
|
||||
#include <map>
|
||||
#include <set>
|
||||
#include <array>
|
||||
#include <unordered_map>
|
||||
|
||||
#include "objects-in-frame.h"
|
||||
#include "processing-block-model.h"
|
||||
|
||||
#include "realsense-ui-advanced-mode.h"
|
||||
#include "fw-update-helper.h"
|
||||
#include "updates-model.h"
|
||||
#include "calibration-model.h"
|
||||
#include <rsutils/time/periodic-timer.h>
|
||||
#include "option-model.h"
|
||||
|
||||
|
||||
namespace rs2
|
||||
{
|
||||
void prepare_config_file();
|
||||
|
||||
bool frame_metadata_to_csv( const std::string & filename, rs2::frame frame );
|
||||
|
||||
bool motion_data_to_csv( const std::string & filename, rs2::frame frame );
|
||||
|
||||
bool pose_data_to_csv( const std::string & filename, rs2::frame frame );
|
||||
|
||||
void open_issue(std::string body);
|
||||
|
||||
class option_model;
|
||||
|
||||
void hyperlink(ux_window& window, const char* title, const char* link);
|
||||
|
||||
static const float FEET_TO_METER = 0.3048f;
|
||||
|
||||
template<class T>
|
||||
void sort_together(std::vector<T>& vec, std::vector<std::string>& names)
|
||||
{
|
||||
std::vector<std::pair<T, std::string>> pairs(vec.size());
|
||||
for (size_t i = 0; i < vec.size(); i++) pairs[i] = std::make_pair(vec[i], names[i]);
|
||||
|
||||
std::sort(begin(pairs), end(pairs),
|
||||
[](const std::pair<T, std::string>& lhs,
|
||||
const std::pair<T, std::string>& rhs) {
|
||||
return lhs.first < rhs.first;
|
||||
});
|
||||
|
||||
for (size_t i = 0; i < vec.size(); i++)
|
||||
{
|
||||
vec[i] = pairs[i].first;
|
||||
names[i] = pairs[i].second;
|
||||
}
|
||||
}
|
||||
|
||||
template<class T>
|
||||
void push_back_if_not_exists(std::vector<T>& vec, T value)
|
||||
{
|
||||
auto it = std::find(vec.begin(), vec.end(), value);
|
||||
if (it == vec.end()) vec.push_back(value);
|
||||
}
|
||||
|
||||
struct notification_model;
|
||||
typedef std::map<int, rect> streams_layout;
|
||||
|
||||
std::vector<std::string> get_device_info(const device& dev, bool include_location = true);
|
||||
|
||||
using color = std::array<float, 3>;
|
||||
using face = std::array<float3, 4>;
|
||||
using colored_cube = std::array<std::pair<face, color>, 6>;
|
||||
using tracked_point = std::pair<rs2_vector, unsigned int>; // translation and confidence
|
||||
|
||||
class press_button_model
|
||||
{
|
||||
public:
|
||||
press_button_model(const char* icon_default, const char* icon_pressed, std::string tooltip_default, std::string tooltip_pressed,
|
||||
bool init_pressed)
|
||||
{
|
||||
state_pressed = init_pressed;
|
||||
tooltip[unpressed] = tooltip_default;
|
||||
tooltip[pressed] = tooltip_pressed;
|
||||
icon[unpressed] = icon_default;
|
||||
icon[pressed] = icon_pressed;
|
||||
}
|
||||
|
||||
void toggle_button() { state_pressed = !state_pressed; }
|
||||
void set_button_pressed(bool p) { state_pressed = p; }
|
||||
bool is_pressed() { return state_pressed; }
|
||||
std::string get_tooltip() { return(state_pressed ? tooltip[pressed] : tooltip[unpressed]); }
|
||||
std::string get_icon() { return(state_pressed ? icon[pressed] : icon[unpressed]); }
|
||||
|
||||
private:
|
||||
enum button_state
|
||||
{
|
||||
unpressed, //default
|
||||
pressed
|
||||
};
|
||||
|
||||
bool state_pressed = false;
|
||||
std::string tooltip[2];
|
||||
std::string icon[2];
|
||||
};
|
||||
|
||||
bool yes_no_dialog(const std::string& title, const std::string& message_text, bool& approved, ux_window& window, const std::string& error_message, bool disabled = false, const std::string& disabled_reason = "");
|
||||
bool status_dialog(const std::string& title, const std::string& process_topic_text, const std::string& process_status_text, bool enable_close, ux_window& window);
|
||||
|
||||
struct notifications_model;
|
||||
void export_frame(const std::string& fname, std::unique_ptr<rs2::filter> exporter, notifications_model& ns, rs2::frame data, bool notify = true);
|
||||
|
||||
// Auxillary function to save stream data in its internal (raw) format
|
||||
bool save_frame_raw_data(const std::string& filename, rs2::frame frame);
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user