update img_dev
This commit is contained in:
@@ -10,7 +10,8 @@ def generate_launch_description():
|
||||
#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=['ros2','launch', 'realsense2_camera','rs_launch.py'],output='screen'),
|
||||
ExecuteProcess(cmd=['ros2', 'launch', 'realsense2_camera', 'rs_multi_camera_launch.py', 'serial_no1:=\'405622072723\'', 'serial_no2:=\'247122074159\''], output='screen'),
|
||||
|
||||
ExecuteProcess(cmd=['sleep', '2'],output='screen'),
|
||||
|
||||
|
||||
@@ -18,8 +18,8 @@ static shared_ptr<ImageSubscriber> cur_node=nullptr;
|
||||
ImgCfg cfg0=ImgCfg("orbbec", "myType","top","/camera/color/image_raw","/camera/depth/image_raw");
|
||||
ImgCfg cfg1=ImgCfg("orbbec", "myType","null","/camera_02/color/image_raw","/camera_02/depth/image_raw");
|
||||
//
|
||||
ImgCfg cfg2=ImgCfg("realsense", "myType","right","/camera/camera/rgbd","/camera/camera/rgbd");
|
||||
ImgCfg cfg3=ImgCfg("realsense", "myType","left","/camera2/camera2/rgbd","/camera2/camera2/rgbd");
|
||||
ImgCfg cfg2=ImgCfg("realsense", "myType","left","/camera/camera/rgbd","/camera/camera/rgbd");
|
||||
ImgCfg cfg3=ImgCfg("realsense", "myType","right","/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);
|
||||
}
|
||||
@@ -80,7 +80,7 @@ int main(int argc, char* argv[]) {
|
||||
//////////////////奥比中光2 END///////////////////////
|
||||
#endif
|
||||
//////////////////realsense START///////////////////////
|
||||
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) {
|
||||
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) {
|
||||
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());
|
||||
@@ -90,7 +90,7 @@ int main(int argc, char* argv[]) {
|
||||
cur_node->pub_msg(msg.rgb,msg.depth,cfg2);
|
||||
});
|
||||
//////////////////realsense END///////////////////////
|
||||
#if 0
|
||||
#if 1
|
||||
//////////////////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){
|
||||
|
||||
Reference in New Issue
Block a user