Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Using image_transports #2

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions astra_camera/include/astra_camera/ob_camera_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -219,8 +219,7 @@ class OBCameraNode {
std::map<stream_index_pair, openni::VideoMode> stream_video_mode_;
std::map<stream_index_pair, std::vector<openni::VideoMode>> supported_video_modes_;
std::map<stream_index_pair, int> unit_step_size_;
std::map<stream_index_pair, rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr>
image_publishers_;
std::map<stream_index_pair, image_transport::Publisher> image_publishers_;
std::map<stream_index_pair, rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr>
camera_info_publishers_;

Expand Down
2 changes: 1 addition & 1 deletion astra_camera/include/astra_camera/uvc_camera_driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class UVCCameraDriver {
rclcpp::Service<SetBool>::SharedPtr set_uvc_mirror_srv_;
rclcpp::Service<SetBool>::SharedPtr toggle_uvc_camera_srv_;

rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr image_publisher_;
image_transport::Publisher image_publisher_;
rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr camera_info_publisher_;
sensor_msgs::msg::CameraInfo camera_info_;
std::unique_ptr<camera_info_manager::CameraInfoManager> camera_info_manager_ = nullptr;
Expand Down
6 changes: 2 additions & 4 deletions astra_camera/src/ob_camera_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,9 +383,7 @@ void OBCameraNode::setupPublishers() {
std::string topic = name + "/image_raw";
auto image_qos = image_qos_[stream_index];
auto image_qos_profile = getRMWQosProfileFromString(image_qos);
image_publishers_[stream_index] = node_->create_publisher<sensor_msgs::msg::Image>(
topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(image_qos_profile), image_qos_profile));
image_publishers_[stream_index] = image_transport::create_publisher(node_, topic, image_qos_profile);
topic = name + "/camera_info";
auto camera_info_qos = camera_info_qos_[stream_index];
auto camera_info_qos_profile = getRMWQosProfileFromString(camera_info_qos);
Expand Down Expand Up @@ -531,7 +529,7 @@ void OBCameraNode::onNewFrameCallback(const openni::VideoFrameRef& frame,
image_msg->height = stream_index == DEPTH ? height * depth_scale_ : height;
image_msg->step = image_msg->width * unit_step_size_[stream_index];
image_msg->is_bigendian = false;
image_publisher->publish(*image_msg);
image_publisher.publish(image_msg);
sensor_msgs::msg::CameraInfo camera_info;
if (stream_index == DEPTH) {
camera_info = getDepthCameraInfo();
Expand Down
6 changes: 2 additions & 4 deletions astra_camera/src/uvc_camera_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,9 +87,7 @@ UVCCameraDriver::UVCCameraDriver(rclcpp::Node* node, std::shared_ptr<Parameters>
camera_info_manager_ = std::make_unique<camera_info_manager::CameraInfoManager>(
node_, "rgb_camera", color_info_url_);
}
image_publisher_ = node_->create_publisher<sensor_msgs::msg::Image>(
"color/image_raw",
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(color_qos_profile_), color_qos_profile_));
image_publisher_ = image_transport::create_publisher(node_, "color/image_raw", color_qos_profile_);
camera_info_publisher_ = node_->create_publisher<sensor_msgs::msg::CameraInfo>(
"color/camera_info", rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(color_info_qos_profile_),
color_info_qos_profile_));
Expand Down Expand Up @@ -395,7 +393,7 @@ void UVCCameraDriver::frameCallback(uvc_frame_t* frame) {
cv_image_ptr->image = cv_img;
image = *(cv_image_ptr->toImageMsg());
}
image_publisher_->publish(image);
image_publisher_.publish(image);
auto camera_info = getCameraInfo();
camera_info.header.stamp = image.header.stamp;
camera_info.header.frame_id = image.header.frame_id;
Expand Down