diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/config/laserscan/s1030_laserscan.yaml b/wrappers/ros/src/mynt_eye_ros_wrapper/config/laserscan/s1030_laserscan.yaml new file mode 100644 index 0000000..7818e14 --- /dev/null +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/config/laserscan/s1030_laserscan.yaml @@ -0,0 +1,4 @@ +# is_laserscan +is_laserscan: true + + diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/laserscan/mynteye_s1030_laserscan.launch b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/laserscan/mynteye_s1030_laserscan.launch new file mode 100644 index 0000000..9883720 --- /dev/null +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/laserscan/mynteye_s1030_laserscan.launch @@ -0,0 +1,157 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + - 'image_transport/compressedDepth' + + + + + + + + + + + + + + + + + diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch index 79615a5..4420f1d 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch @@ -9,6 +9,9 @@ + + + @@ -52,6 +55,8 @@ + + diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index dd01f41..4f319ab 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -324,6 +324,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet { } } + int depth_type = 0; + private_nh_.getParamCached("depth_type", depth_type); if (model_ == Model::STANDARD2 || model_ == Model::STANDARD210A) { camera_encodings_ = {{Stream::LEFT, enc::BGR8}, {Stream::RIGHT, enc::BGR8}, @@ -334,13 +336,23 @@ class ROSWrapperNodelet : public nodelet::Nodelet { {Stream::DEPTH, enc::MONO16}}; } if (model_ == Model::STANDARD) { - camera_encodings_ = {{Stream::LEFT, enc::MONO8}, - {Stream::RIGHT, enc::MONO8}, - {Stream::LEFT_RECTIFIED, enc::MONO8}, - {Stream::RIGHT_RECTIFIED, enc::MONO8}, - {Stream::DISPARITY, enc::MONO8}, // float - {Stream::DISPARITY_NORMALIZED, enc::MONO8}, - {Stream::DEPTH, enc::MONO16}}; + if (depth_type == 0) { + camera_encodings_ = {{Stream::LEFT, enc::MONO8}, + {Stream::RIGHT, enc::MONO8}, + {Stream::LEFT_RECTIFIED, enc::MONO8}, + {Stream::RIGHT_RECTIFIED, enc::MONO8}, + {Stream::DISPARITY, enc::MONO8}, // float + {Stream::DISPARITY_NORMALIZED, enc::MONO8}, + {Stream::DEPTH, enc::MONO16}}; + } else if (depth_type == 1) { + camera_encodings_ = {{Stream::LEFT, enc::MONO8}, + {Stream::RIGHT, enc::MONO8}, + {Stream::LEFT_RECTIFIED, enc::MONO8}, + {Stream::RIGHT_RECTIFIED, enc::MONO8}, + {Stream::DISPARITY, enc::MONO8}, // float + {Stream::DISPARITY_NORMALIZED, enc::MONO8}, + {Stream::DEPTH, enc::TYPE_16UC1}}; + } } pub_imu_ = nh_.advertise(imu_topic, 100); NODELET_INFO_STREAM("Advertized on topic " << imu_topic); @@ -1312,10 +1324,21 @@ class ROSWrapperNodelet : public nodelet::Nodelet { } } else { if (info_pair->left.distortion_model == "KANNALA_BRANDT") { - camera_info->distortion_model = - sensor_msgs::distortion_models::EQUIDISTANT; - for (size_t i; i < 4; i++) { - camera_info->D.push_back(info_pair->left.D[i]); + // compatible laserscan + bool is_laserscan = false; + private_nh_.getParamCached("is_laserscan", is_laserscan); + if (!is_laserscan) { + camera_info->distortion_model = + sensor_msgs::distortion_models::EQUIDISTANT; + for (size_t i; i < 4; i++) { + camera_info->D.push_back(info_pair->left.D[i]); + } + } else { + camera_info->distortion_model = + sensor_msgs::distortion_models::PLUMB_BOB; + for (size_t i; i < 4; i++) { + camera_info->D.push_back(0.0); + } } } else if (info_pair->left.distortion_model == "PINHOLE") { camera_info->distortion_model =