Skip to content
Merged
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
2 changes: 1 addition & 1 deletion intra_process_demo/include/image_pipeline/camera_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class CameraNode final : public rclcpp::Node
/// \param height What video height to capture at
explicit CameraNode(
const std::string & output, const std::string & node_name = "camera_node",
bool watermark = true, int device = 0, int width = 320, int height = 240)
bool watermark = true, int device = 0, int width = 640, int height = 480)
: Node(node_name, rclcpp::NodeOptions().use_intra_process_comms(true)),
canceled_(false), watermark_(watermark)
{
Expand Down
2 changes: 1 addition & 1 deletion intra_process_demo/include/image_pipeline/common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ draw_on_image(cv::Mat & image, const std::string & text, int height)
text.c_str(),
cv::Point(10, height),
cv::FONT_HERSHEY_SIMPLEX,
0.3,
0.5,
cv::Scalar(0, 255, 0));
}

Expand Down
4 changes: 2 additions & 2 deletions intra_process_demo/include/image_pipeline/image_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,12 @@ class ImageViewNode final : public rclcpp::Node
sub_ = this->create_subscription<sensor_msgs::msg::Image>(
input,
rclcpp::SensorDataQoS(),
[node_name, watermark](sensor_msgs::msg::Image::ConstSharedPtr msg) {
[node_name, watermark](sensor_msgs::msg::Image::UniquePtr msg) {
// Create a cv::Mat from the image message (without copying).
cv::Mat cv_mat(
msg->height, msg->width,
encoding2mat_type(msg->encoding),
const_cast<unsigned char *>(msg->data.data()));
msg->data.data());
if (watermark) {
// Annotate with the pid and pointer address.
std::stringstream ss;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@ int main(int argc, char * argv[])
}
auto watermark_node =
std::make_shared<WatermarkNode>("image", "watermarked_image", "Hello world!");
auto image_view_node = std::make_shared<ImageViewNode>("watermarked_image");
auto image_view_node =
std::make_shared<ImageViewNode>("watermarked_image", "image_pipeline_all_in_one");

executor.add_node(camera_node);
executor.add_node(watermark_node);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,10 @@ int main(int argc, char * argv[])
}
auto watermark_node =
std::make_shared<WatermarkNode>("image", "watermarked_image", "Hello world!");
auto image_view_node = std::make_shared<ImageViewNode>("watermarked_image");
auto image_view_node2 = std::make_shared<ImageViewNode>("watermarked_image", "image_view_node2");
auto image_view_node =
std::make_shared<ImageViewNode>("watermarked_image", "image_pipeline_with_two_image_view");
auto image_view_node2 =
std::make_shared<ImageViewNode>("watermarked_image", "image_pipeline_with_two_image_view2");

executor.add_node(camera_node);
executor.add_node(watermark_node);
Expand Down