everything seems to work together as expected
(if not perfectly)
This commit is contained in:
@@ -25,12 +25,16 @@ class ImageConverter {
|
||||
ImageConverter() :
|
||||
it_(nh_)
|
||||
{
|
||||
// Subscrive to input video feed
|
||||
ros::Rate loop_rate(0.1);
|
||||
loop_rate.sleep();
|
||||
|
||||
// Subscribe to input video feed
|
||||
image_sub_ = it_.subscribe("/usb_cam/image_raw", 1,
|
||||
&ImageConverter::imageCb, this);
|
||||
|
||||
// Create output windows
|
||||
cv::namedWindow(ARUCO_WINDOW);
|
||||
ROS_INFO("ARUCO: UP");
|
||||
}
|
||||
|
||||
~ImageConverter() {
|
||||
@@ -115,6 +119,7 @@ class ImageConverter {
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
ros::init(argc, argv, "aruco_detector");
|
||||
ROS_INFO("ARUCO: STARTING");
|
||||
ImageConverter ic;
|
||||
ros::spin();
|
||||
return 0;
|
||||
|
||||
Reference in New Issue
Block a user