Skip to content

Commit 49b12ed

Browse files
jacobperronDanielDanBmh
authored
Added more parameters for camera topic examples (#465)
* Added parameter for custom topic names, display window name and camera device id. Signed-off-by: Daniel <[email protected]> * Remove topic name parameters again. Signed-off-by: Daniel <[email protected]> * Update image_tools/src/cam2image.cpp Co-Authored-By: Jacob Perron <[email protected]> Signed-off-by: Daniel <[email protected]> * Update image_tools/src/cam2image.cpp Co-Authored-By: Jacob Perron <[email protected]> Signed-off-by: Daniel <[email protected]> * Use topic name as default window name. Signed-off-by: Daniel <[email protected]> * Add spaces. Signed-off-by: Daniel <[email protected]> * Explicit template type To fix warning on Windows. Signed-off-by: Jacob Perron <[email protected]> * Explicitly cast parameter to int This avoids a compiler warning on Windows. Signed-off-by: Jacob Perron <[email protected]> Co-authored-by: Daniel <[email protected]> Co-authored-by: DanBmh <[email protected]>
1 parent 59ce1ff commit 49b12ed

File tree

2 files changed

+16
-9
lines changed

2 files changed

+16
-9
lines changed

image_tools/src/cam2image.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -89,8 +89,7 @@ class Cam2Image : public rclcpp::Node
8989

9090
if (!burger_mode_) {
9191
// Initialize OpenCV video capture stream.
92-
// Always open device 0.
93-
cap.open(0);
92+
cap.open(device_id_);
9493

9594
// Set the width and height based on command line arguments.
9695
cap.set(cv::CAP_PROP_FRAME_WIDTH, static_cast<double>(width_));
@@ -181,6 +180,8 @@ class Cam2Image : public rclcpp::Node
181180
ss << std::endl;
182181
ss << " show_camera\tShow camera stream. Either 'true' or 'false' (default)";
183182
ss << std::endl;
183+
ss << " device_id\tDevice ID of the camera. 0 (default) selects the default camera device.";
184+
ss << std::endl;
184185
ss << " width\t\tWidth component of the camera stream resolution. Default value is 320";
185186
ss << std::endl;
186187
ss << " height\tHeight component of the camera stream resolution. Default value is 240";
@@ -236,6 +237,7 @@ class Cam2Image : public rclcpp::Node
236237
depth_ = this->declare_parameter("depth", 10);
237238
freq_ = this->declare_parameter("frequency", 30.0);
238239
show_camera_ = this->declare_parameter("show_camera", false);
240+
device_id_ = static_cast<int>(this->declare_parameter("device_id", 0));
239241
width_ = this->declare_parameter("width", 320);
240242
height_ = this->declare_parameter("height", 240);
241243
rcl_interfaces::msg::ParameterDescriptor burger_mode_desc;
@@ -304,6 +306,7 @@ class Cam2Image : public rclcpp::Node
304306
size_t height_;
305307
bool burger_mode_;
306308
std::string frame_id_;
309+
int device_id_;
307310

308311
/// If true, will cause the incoming camera image message to flip about the y-axis.
309312
bool is_flipped_;

image_tools/src/showimage.cpp

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -53,11 +53,6 @@ class ShowImage : public rclcpp::Node
5353
IMAGE_TOOLS_LOCAL
5454
void initialize()
5555
{
56-
if (show_image_) {
57-
// Initialize an OpenCV named window called "showimage".
58-
cv::namedWindow("showimage", cv::WINDOW_AUTOSIZE);
59-
cv::waitKey(1);
60-
}
6156
// Set quality of service profile based on command line options.
6257
auto qos = rclcpp::QoS(
6358
rclcpp::QoSInitialization(
@@ -82,6 +77,11 @@ class ShowImage : public rclcpp::Node
8277

8378
RCLCPP_INFO(this->get_logger(), "Subscribing to topic '%s'", topic_.c_str());
8479
sub_ = create_subscription<sensor_msgs::msg::Image>(topic_, qos, callback);
80+
81+
if (window_name_ == "") {
82+
// If no custom window name is given, use the topic name
83+
window_name_ = sub_->get_topic_name();
84+
}
8585
}
8686

8787
IMAGE_TOOLS_LOCAL
@@ -110,6 +110,8 @@ class ShowImage : public rclcpp::Node
110110
ss << std::endl;
111111
ss << " show_image\tShow the image. Either 'true' (default) or 'false'";
112112
ss << std::endl;
113+
ss << " window_name\tName of the display window. Default value is the topic name";
114+
ss << std::endl;
113115
std::cout << ss.str();
114116
return true;
115117
}
@@ -156,6 +158,7 @@ class ShowImage : public rclcpp::Node
156158
// Declare and get remaining parameters
157159
depth_ = this->declare_parameter("depth", 10);
158160
show_image_ = this->declare_parameter("show_image", true);
161+
window_name_ = this->declare_parameter("window_name", "");
159162
}
160163

161164
/// Convert a sensor_msgs::Image encoding type (stored as a string) to an OpenCV encoding type.
@@ -206,8 +209,8 @@ class ShowImage : public rclcpp::Node
206209

207210
cv::Mat cvframe = frame;
208211

209-
// Show the image in a window called "showimage".
210-
cv::imshow("showimage", cvframe);
212+
// Show the image in a window
213+
cv::imshow(window_name_, cvframe);
211214
// Draw the screen and wait for 1 millisecond.
212215
cv::waitKey(1);
213216
}
@@ -219,6 +222,7 @@ class ShowImage : public rclcpp::Node
219222
rmw_qos_history_policy_t history_policy_ = rmw_qos_profile_default.history;
220223
bool show_image_ = true;
221224
std::string topic_ = "image";
225+
std::string window_name_;
222226
};
223227

224228
} // namespace image_tools

0 commit comments

Comments
 (0)