diff --git a/aruco/cfg/ArucoThreshold.cfg b/aruco/cfg/ArucoThreshold.cfg deleted file mode 100755 index 5d467de..0000000 --- a/aruco/cfg/ArucoThreshold.cfg +++ /dev/null @@ -1,14 +0,0 @@ -#!/usr/bin/env python -PACKAGE = "aruco_ros" - -from dynamic_reconfigure.parameter_generator_catkin import * - -gen = ParameterGenerator() - -gen.add("param1", int_t, 0, "blockSize parameter of cv::adaptiveThreshold", 4, 1, 15) -gen.add("param2", int_t, 0, "C parameter of cv::adaptiveThreshold", 8, 1, 15) -gen.add("normalizeImage", bool_t, 0, "normalizeImage", True) -gen.add("dctComponentsToRemove", int_t, 0, "DCT components to remove", 2, 1, 4) -gen.add("degree", int_t, 0, "Degree to rotate", 0, 0, 360) - -exit(gen.generate(PACKAGE, "double", "ArucoThreshold")) diff --git a/aruco_ros/src/marker_publish.cpp b/aruco_ros/src/marker_publish.cpp index 4476d4d..6f32a21 100644 --- a/aruco_ros/src/marker_publish.cpp +++ b/aruco_ros/src/marker_publish.cpp @@ -85,8 +85,6 @@ class ArucoMarkerPublisher , it_(nh_) , useCamInfo_(true) { - image_sub_ = it_.subscribe("/image", 1, &ArucoMarkerPublisher::image_callback, this); - nh_.param("use_camera_info", useCamInfo_, true); if(useCamInfo_) { @@ -113,6 +111,8 @@ class ArucoMarkerPublisher marker_msg_ = aruco_msgs::MarkerArray::Ptr(new aruco_msgs::MarkerArray()); marker_msg_->header.frame_id = reference_frame_; marker_msg_->header.seq = 0; + + image_sub_ = it_.subscribe("/image", 1, &ArucoMarkerPublisher::image_callback, this); } bool getTransform(const std::string& refFrame, diff --git a/aruco_ros/src/simple_double.cpp b/aruco_ros/src/simple_double.cpp index bbfc358..ea5f855 100644 --- a/aruco_ros/src/simple_double.cpp +++ b/aruco_ros/src/simple_double.cpp @@ -251,9 +251,6 @@ int main(int argc,char **argv) nh.param("image_is_rectified", useRectifiedImages, true); ROS_INFO_STREAM("Image is rectified: " << useRectifiedImages); - image_transport::Subscriber image_sub = it.subscribe("/image", 1, &image_callback); - cam_info_sub = nh.subscribe("/camera_info", 1, &cam_info_callback); - cam_info_received = false; image_pub = it.advertise("result", 1); debug_pub = it.advertise("debug", 1); @@ -276,6 +273,9 @@ int main(int argc,char **argv) ROS_ERROR("parent_name and/or child_name was not set!"); return -1; } + + image_transport::Subscriber image_sub = it.subscribe("/image", 1, &image_callback); + cam_info_sub = nh.subscribe("/camera_info", 1, &cam_info_callback); ROS_INFO("Aruco node started with marker size of %f meters and marker ids to track: %d, %d", marker_size, marker_id1, marker_id2); diff --git a/aruco_ros/src/simple_single.cpp b/aruco_ros/src/simple_single.cpp index b1a131c..995d4b6 100644 --- a/aruco_ros/src/simple_single.cpp +++ b/aruco_ros/src/simple_single.cpp @@ -83,15 +83,6 @@ class ArucoSimple nh("~"), it(nh) { - image_sub = it.subscribe("/image", 1, &ArucoSimple::image_callback, this); - cam_info_sub = nh.subscribe("/camera_info", 1, &ArucoSimple::cam_info_callback, this); - - image_pub = it.advertise("result", 1); - debug_pub = it.advertise("debug", 1); - pose_pub = nh.advertise("pose", 100); - transform_pub = nh.advertise("transform", 100); - position_pub = nh.advertise("position", 100); - nh.param("marker_size", marker_size, 0.05); nh.param("marker_id", marker_id, 300); nh.param("reference_frame", reference_frame, ""); @@ -103,6 +94,15 @@ class ArucoSimple if ( reference_frame.empty() ) reference_frame = camera_frame; + + image_pub = it.advertise("result", 1); + debug_pub = it.advertise("debug", 1); + pose_pub = nh.advertise("pose", 100); + transform_pub = nh.advertise("transform", 100); + position_pub = nh.advertise("position", 100); + + image_sub = it.subscribe("/image", 1, &ArucoSimple::image_callback, this); + cam_info_sub = nh.subscribe("/camera_info", 1, &ArucoSimple::cam_info_callback, this); ROS_INFO("Aruco node started with marker size of %f m and marker id to track: %d", marker_size, marker_id);