4 个版本
0.3.3 | 2023年2月11日 |
---|---|
0.3.2 | 2023年2月11日 |
0.2.0 |
|
0.1.1 |
|
#780 in 图像
87 每月下载量
31KB
424 行
cv-bridge-rs
Rust 实现的 cv_bridge,用于在 ROS 图像消息和 OpenCV 图像之间进行转换
警告:此包仍在积极开发中。使用风险自负。
入门
将 cv_bridge 添加到您的项目中
在 Cargo.toml 文件的依赖项下添加以下内容
[dependencies]
cv-bridge = "0.3.3"
或者您可以使用 cargo 添加依赖项
cargo add cv_bridge
在 ROS 图像消息和 OpenCV 图像之间进行转换
use opencv::highgui;
use cv_bridge::{
CvImage,
msgs::sensor_msgs::Image,
};
fn main() {
// Initialize ros node
rosrust::init("image_viewer");
// Create image subscriber
let _subscriber_raii = rosrust::subscribe(
"/camera/image_raw",
5,
move |image: Image| {
// Convert ros Image to opencv Mat
let mut cv_image = CvImage::from_imgmsg(image).expect("failed to construct CvImage from ros Image");
let mat = cv_image.as_cvmat().expect("failed to convert CvImage to Mat");
// Display image
let window = "view";
highgui::named_window(window, highgui::WINDOW_AUTOSIZE).unwrap();
highgui::imshow(window, &mat).unwrap();
highgui::wait_key(1).unwrap();
}
);
rosrust::spin();
}
特性
- 将 sensor_msgs/Image 转换为 opencv::core::Mat,反之亦然
- 支持由 sensor_msgs: image_encodings.h crate 定义的多种编码
- 支持 8 位和 16 位深度通道
- 支持 32 位和 64 位深度通道
- 文档和示例
- 将 sensor_msgs/CompressedImage 转换为 opencv::core::Mat,反之亦然
依赖项
~26–40MB
~822K SLoC