Skip to content
Open
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
14 changes: 0 additions & 14 deletions aruco/cfg/ArucoThreshold.cfg

This file was deleted.

4 changes: 2 additions & 2 deletions aruco_ros/src/marker_publish.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,6 @@ class ArucoMarkerPublisher
, it_(nh_)
, useCamInfo_(true)
{
image_sub_ = it_.subscribe("/image", 1, &ArucoMarkerPublisher::image_callback, this);

nh_.param<bool>("use_camera_info", useCamInfo_, true);
if(useCamInfo_)
{
Expand All @@ -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,
Expand Down
6 changes: 3 additions & 3 deletions aruco_ros/src/simple_double.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,9 +251,6 @@ int main(int argc,char **argv)
nh.param<bool>("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);
Expand All @@ -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);
Expand Down
18 changes: 9 additions & 9 deletions aruco_ros/src/simple_single.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<geometry_msgs::PoseStamped>("pose", 100);
transform_pub = nh.advertise<geometry_msgs::TransformStamped>("transform", 100);
position_pub = nh.advertise<geometry_msgs::Vector3Stamped>("position", 100);

nh.param<double>("marker_size", marker_size, 0.05);
nh.param<int>("marker_id", marker_id, 300);
nh.param<std::string>("reference_frame", reference_frame, "");
Expand All @@ -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<geometry_msgs::PoseStamped>("pose", 100);
transform_pub = nh.advertise<geometry_msgs::TransformStamped>("transform", 100);
position_pub = nh.advertise<geometry_msgs::Vector3Stamped>("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);
Expand Down