Skip to content

Commit a4c09f9

Browse files
wjwwoodmergify[bot]
authored andcommitted
fixup image_pipeline_demo (#755)
Signed-off-by: William Woodall <wjwwood@intrinsic.ai> (cherry picked from commit 91c63e5)
1 parent 465ca70 commit a4c09f9

File tree

5 files changed

+10
-7
lines changed

5 files changed

+10
-7
lines changed

intra_process_demo/include/image_pipeline/camera_node.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ class CameraNode final : public rclcpp::Node
4141
/// \param height What video height to capture at
4242
explicit CameraNode(
4343
const std::string & output, const std::string & node_name = "camera_node",
44-
bool watermark = true, int device = 0, int width = 320, int height = 240)
44+
bool watermark = true, int device = 0, int width = 640, int height = 480)
4545
: Node(node_name, rclcpp::NodeOptions().use_intra_process_comms(true)),
4646
canceled_(false), watermark_(watermark)
4747
{

intra_process_demo/include/image_pipeline/common.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ draw_on_image(cv::Mat & image, const std::string & text, int height)
8181
text.c_str(),
8282
cv::Point(10, height),
8383
cv::FONT_HERSHEY_SIMPLEX,
84-
0.3,
84+
0.5,
8585
cv::Scalar(0, 255, 0));
8686
}
8787

intra_process_demo/include/image_pipeline/image_view_node.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -41,12 +41,12 @@ class ImageViewNode final : public rclcpp::Node
4141
sub_ = this->create_subscription<sensor_msgs::msg::Image>(
4242
input,
4343
rclcpp::SensorDataQoS(),
44-
[node_name, watermark](sensor_msgs::msg::Image::ConstSharedPtr msg) {
44+
[node_name, watermark](sensor_msgs::msg::Image::UniquePtr msg) {
4545
// Create a cv::Mat from the image message (without copying).
4646
cv::Mat cv_mat(
4747
msg->height, msg->width,
4848
encoding2mat_type(msg->encoding),
49-
const_cast<unsigned char *>(msg->data.data()));
49+
msg->data.data());
5050
if (watermark) {
5151
// Annotate with the pid and pointer address.
5252
std::stringstream ss;

intra_process_demo/src/image_pipeline/image_pipeline_all_in_one.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,8 @@ int main(int argc, char * argv[])
3535
}
3636
auto watermark_node =
3737
std::make_shared<WatermarkNode>("image", "watermarked_image", "Hello world!");
38-
auto image_view_node = std::make_shared<ImageViewNode>("watermarked_image");
38+
auto image_view_node =
39+
std::make_shared<ImageViewNode>("watermarked_image", "image_pipeline_all_in_one");
3940

4041
executor.add_node(camera_node);
4142
executor.add_node(watermark_node);

intra_process_demo/src/image_pipeline/image_pipeline_with_two_image_view.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,10 @@ int main(int argc, char * argv[])
3636
}
3737
auto watermark_node =
3838
std::make_shared<WatermarkNode>("image", "watermarked_image", "Hello world!");
39-
auto image_view_node = std::make_shared<ImageViewNode>("watermarked_image");
40-
auto image_view_node2 = std::make_shared<ImageViewNode>("watermarked_image", "image_view_node2");
39+
auto image_view_node =
40+
std::make_shared<ImageViewNode>("watermarked_image", "image_pipeline_with_two_image_view");
41+
auto image_view_node2 =
42+
std::make_shared<ImageViewNode>("watermarked_image", "image_pipeline_with_two_image_view2");
4143

4244
executor.add_node(camera_node);
4345
executor.add_node(watermark_node);

0 commit comments

Comments
 (0)