add realsense

This commit is contained in:
hehe
2025-09-22 13:47:15 +08:00
parent 2e76dd7059
commit 1f7251fb80
2 changed files with 16 additions and 3 deletions

View File

@@ -18,6 +18,7 @@ static shared_ptr<ImageSubscriber> cur_node=nullptr;
ImgCfg cfg0=ImgCfg("orbbec", "myType","left","/camera_01/color/image_raw","/camera_01/depth/image_raw");
ImgCfg cfg1=ImgCfg("orbbec", "myType","right","/camera_02/color/image_raw","/camera_02/depth/image_raw");
//
ImgCfg cfg2=ImgCfg("realsense", "myType","front","/camera/color/image_raw","/camera/depth/image_raw");
void sync_cb0(const sensor_msgs::msg::Image& c_img, const sensor_msgs::msg::Image& d_img) {
cur_node->pub_msg(c_img,d_img,cfg0);
}
@@ -72,6 +73,18 @@ int main(int argc, char* argv[]) {
auto sync1 = make_shared<message_filters::Synchronizer<SyncPolicy>>(SyncPolicy(10), c_sub1, d_sub1);
sync1->registerCallback(&sync_cb1);
//////////////////奥比中光2 END///////////////////////
//////////////////realsense START///////////////////////
rclcpp::Subscription<realsense2_camera_msgs::msg::RGBD>::SharedPtr rgbd_sub_ = cur_node->create_subscription<realsense2_camera_msgs::msg::RGBD>("/camera/camera/rgbd", 10, [&](const realsense2_camera_msgs::msg::RGBD& msg) {
if(cfg2.k_arr.size()==0||cfg2.d_arr.size()==0){
cfg2.k_arr.assign(msg.rgb_camera_info.k.begin(), msg.rgb_camera_info.k.end());
cfg2.d_arr.assign(msg.rgb_camera_info.d.begin(), msg.rgb_camera_info.d.end());
cfg2.arr_copy+=1;
cout<<"copy:"<<"k:"<<cfg2.k_arr[0]<<"d:"<<cfg2.d_arr[0]<<endl;
}
cur_node->pub_msg(msg.rgb,msg.depth,cfg2);
});
//////////////////realsense END///////////////////////
rclcpp::spin(cur_node);
rclcpp::shutdown();
return 0;

View File

@@ -57,9 +57,9 @@ configurable_parameters = [{'name': 'camera_name', 'default': '
{'name': 'depth_module.gain.1', 'default': '16', 'description': 'Depth module first gain value. Used for hdr_merge filter'},
{'name': 'depth_module.exposure.2', 'default': '1', 'description': 'Depth module second exposure value. Used for hdr_merge filter'},
{'name': 'depth_module.gain.2', 'default': '16', 'description': 'Depth module second gain value. Used for hdr_merge filter'},
{'name': 'enable_sync', 'default': 'false', 'description': "'enable sync mode'"},
{'name': 'enable_sync', 'default': 'true', 'description': "'enable sync mode'"},
{'name': 'depth_module.inter_cam_sync_mode', 'default': "0", 'description': '[0-Default, 1-Master, 2-Slave]'},
{'name': 'enable_rgbd', 'default': 'false', 'description': "'enable rgbd topic'"},
{'name': 'enable_rgbd', 'default': 'true', 'description': "'enable rgbd topic'"},
{'name': 'enable_gyro', 'default': 'false', 'description': "'enable gyro stream'"},
{'name': 'enable_accel', 'default': 'false', 'description': "'enable accel stream'"},
{'name': 'gyro_fps', 'default': '0', 'description': "''"},
@@ -77,7 +77,7 @@ configurable_parameters = [{'name': 'camera_name', 'default': '
{'name': 'pointcloud.stream_index_filter','default': '0', 'description': 'texture stream index for pointcloud'},
{'name': 'pointcloud.ordered_pc', 'default': 'false', 'description': ''},
{'name': 'pointcloud.allow_no_texture_points', 'default': 'false', 'description': "''"},
{'name': 'align_depth.enable', 'default': 'false', 'description': 'enable align depth filter'},
{'name': 'align_depth.enable', 'default': 'true', 'description': 'enable align depth filter'},
{'name': 'colorizer.enable', 'default': 'false', 'description': 'enable colorizer filter'},
{'name': 'decimation_filter.enable', 'default': 'false', 'description': 'enable_decimation_filter'},
{'name': 'rotation_filter.enable', 'default': 'false', 'description': 'enable rotation_filter'},