Skip to content
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
Empty file modified CMakeLists.txt
100644 → 100755
Empty file.
Empty file modified README.md
100644 → 100755
Empty file.
Empty file modified cfg/calibration_depth.yaml
100644 → 100755
Empty file.
Empty file modified cfg/calibration_rgb.yaml
100644 → 100755
Empty file.
Empty file modified include/kinect_ros2/kinect_ros2_component.hpp
100644 → 100755
Empty file.
Empty file modified launch/pointcloud.launch.py
100644 → 100755
Empty file.
Empty file modified launch/showimage.launch.py
100644 → 100755
Empty file.
Empty file modified package.xml
100644 → 100755
Empty file.
Empty file modified rviz/pointcloud.rviz
100644 → 100755
Empty file.
27 changes: 10 additions & 17 deletions src/kinect_ros2_component.cpp
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -134,35 +134,28 @@ void KinectRosComponent::rgb_cb(freenect_device * dev, void * rgb_ptr, uint32_t
_rgb_flag = true;
}


void KinectRosComponent::timer_callback()
{
freenect_process_events(fn_ctx_);
auto header = std_msgs::msg::Header();
header.frame_id = "kinect_depth";


auto stamp = now();
header.stamp = stamp;
depth_info_.header.stamp = stamp;

std_msgs::msg::Header rgb_header, depth_header;
rgb_header.frame_id = "kinect_rgb"; rgb_header.stamp = stamp;
depth_header.frame_id = "kinect_depth"; depth_header.stamp = stamp;
rgb_info_.header = rgb_header;
depth_info_.header = depth_header;

if (_depth_flag) {
//convert 16bit to 8bit mono
// cv::Mat depth_8UC1(_depth_image, CV_16UC1);
// depth_8UC1.convertTo(depth_8UC1, CV_8UC1);

auto msg = cv_bridge::CvImage(header, "16UC1", _depth_image).toImageMsg();
auto msg = cv_bridge::CvImage(depth_header, "16UC1", _depth_image).toImageMsg();
depth_pub_.publish(*msg, depth_info_);

// cv::imshow("Depth", _depth_image);
// cv::waitKey(1);
_depth_flag = false;
}

if (_rgb_flag) {
auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "rgb8", _rgb_image).toImageMsg();
auto msg = cv_bridge::CvImage(rgb_header, "rgb8", _rgb_image).toImageMsg();
rgb_pub_.publish(*msg, rgb_info_);

// cv::imshow("RGB", _rgb_image);
// cv::waitKey(1);
_rgb_flag = false;
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/kinect_ros2_node.cpp
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -62,4 +62,4 @@ int main(int argc, char * argv[])
rclcpp::shutdown();

return 0;
}
}