one orbbec and one realsense

This commit is contained in:
NuoDaJia02
2025-10-28 16:00:42 +08:00
parent a535062a65
commit 9acd27ee40
3 changed files with 14 additions and 31 deletions

View File

@@ -7,25 +7,14 @@ from launch.conditions import IfCondition
def generate_launch_description():
return LaunchDescription([
# 启动orbbec_camera
#ExecuteProcess(
# cmd=['ros2','launch', 'orbbec_camera', 'multi_camera.launch.py'],
# output='screen'),
ExecuteProcess(
cmd=[
'ros2',
'launch',
'realsense2_camera',
'rs_multi_camera_launch.py'
],
output='screen'
),
#ExecuteProcess(cmd=['ros2','launch', 'orbbec_camera', 'multi_camera.launch.py'],output='screen'),
ExecuteProcess(cmd=['ros2','launch', 'orbbec_camera', 'gemini_330_series.launch.py'],output='screen'),
ExecuteProcess(cmd=['sleep', '2'],output='screen'),
ExecuteProcess(cmd=['ros2','launch', 'realsense2_camera','rs_launch.py'],output='screen'),
ExecuteProcess(cmd=['sleep', '2'],output='screen'),
# 等待一段时间确保相机启动完成
ExecuteProcess(
cmd=['sleep', '3'],
output='screen'
),
# 启动img_dev_node
Node(

View File

@@ -1,7 +0,0 @@
sensor_msgs/Image image_depth
sensor_msgs/Image image_color
float64[] karr
float64[] darr
string source
string position
string type

View File

@@ -15,11 +15,11 @@ using namespace std;
using namespace img_dev;
using SyncPolicy=message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image,sensor_msgs::msg::Image>;
static shared_ptr<ImageSubscriber> cur_node=nullptr;
ImgCfg cfg0=ImgCfg("orbbec", "myType","left","/camera_01/color/image_raw","/camera_01/depth/image_raw");
ImgCfg cfg0=ImgCfg("orbbec", "myType","left","/camera/color/image_raw","/camera/depth/image_raw");
ImgCfg cfg1=ImgCfg("orbbec", "myType","right","/camera_02/color/image_raw","/camera_02/depth/image_raw");
//
ImgCfg cfg2=ImgCfg("realsense", "myType","left","/camera/camera/rgbd","/camera/camera/rgbd");
ImgCfg cfg3=ImgCfg("realsense", "myType","right","/camera2/camera2/rgbd","/camera2/camera2/rgbd");
ImgCfg cfg2=ImgCfg("realsense", "myType","hand_l","/camera/camera/rgbd","/camera/camera/rgbd");
ImgCfg cfg3=ImgCfg("realsense", "myType","hand_r","/camera2/camera2/rgbd","/camera2/camera2/rgbd");
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);
}
@@ -34,7 +34,7 @@ int main(int argc, char* argv[]) {
return -1;
}
//////////////////奥比中光1 START///////////////////////
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr camera01_info=cur_node->create_subscription<sensor_msgs::msg::CameraInfo>("/camera_01/color/camera_info", 10,
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr camera01_info=cur_node->create_subscription<sensor_msgs::msg::CameraInfo>("/camera/color/camera_info", 10,
[&](const sensor_msgs::msg::CameraInfo& info){
if(info.k.empty()||info.d.empty())
return;
@@ -54,6 +54,7 @@ int main(int argc, char* argv[]) {
sync0->registerCallback(&sync_cb0);
//////////////////奥比中光1 END///////////////////////
#if 0
//////////////////奥比中光2 START///////////////////////
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr camera02_info=cur_node->create_subscription<sensor_msgs::msg::CameraInfo>("/camera_02/color/camera_info", 10,
@@ -74,9 +75,9 @@ 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///////////////////////
#endif
//////////////////realsense START///////////////////////
rclcpp::Subscription<realsense2_camera_msgs::msg::RGBD>::SharedPtr rgbd1_sub_ = cur_node->create_subscription<realsense2_camera_msgs::msg::RGBD>("/camera1/camera1/rgbd", 10, [&](const realsense2_camera_msgs::msg::RGBD& msg) {
rclcpp::Subscription<realsense2_camera_msgs::msg::RGBD>::SharedPtr rgbd1_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());
@@ -86,7 +87,7 @@ int main(int argc, char* argv[]) {
cur_node->pub_msg(msg.rgb,msg.depth,cfg2);
});
//////////////////realsense END///////////////////////
#if 0
//////////////////realsense START///////////////////////
rclcpp::Subscription<realsense2_camera_msgs::msg::RGBD>::SharedPtr rgbd2_sub_ = cur_node->create_subscription<realsense2_camera_msgs::msg::RGBD>("/camera2/camera2/rgbd", 10, [&](const realsense2_camera_msgs::msg::RGBD& msg) {
if(cfg3.k_arr.size()==0||cfg3.d_arr.size()==0){
@@ -98,7 +99,7 @@ int main(int argc, char* argv[]) {
cur_node->pub_msg(msg.rgb,msg.depth,cfg3);
});
//////////////////realsense END///////////////////////
#endif