IndividualMarkersNoKinect.cpp
Go to the documentation of this file.
1 /*
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2012, Scott Niekum
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without
8  modification, are permitted provided that the following conditions
9  are met:
10 
11  * Redistributions of source code must retain the above copyright
12  notice, this list of conditions and the following disclaimer.
13  * Redistributions in binary form must reproduce the above
14  copyright notice, this list of conditions and the following
15  disclaimer in the documentation and/or other materials provided
16  with the distribution.
17  * Neither the name of the Willow Garage nor the names of its
18  contributors may be used to endorse or promote products derived
19  from this software without specific prior written permission.
20 
21  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  POSSIBILITY OF SUCH DAMAGE.
33 
34  author: Scott Niekum
35 */
36 
37 
38 #include <std_msgs/Bool.h>
41 #include "ar_track_alvar/Shared.h"
42 #include <cv_bridge/cv_bridge.h>
43 #include <ar_track_alvar_msgs/AlvarMarker.h>
44 #include <ar_track_alvar_msgs/AlvarMarkers.h>
45 #include <tf/transform_listener.h>
48 #include <dynamic_reconfigure/server.h>
49 #include <ar_track_alvar/ParamsConfig.h>
50 
51 using namespace alvar;
52 using namespace std;
53 
54 bool init=true;
60 ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_;
61 visualization_msgs::Marker rvizMarker_;
65 
66 bool enableSwitched = false;
67 bool enabled = true;
69 double marker_size;
72 std::string cam_image_topic;
73 std::string cam_info_topic;
74 std::string output_frame;
75 int marker_resolution = 5; // default marker resolution
76 int marker_margin = 2; // default marker margin
77 
78 void getCapCallback (const sensor_msgs::ImageConstPtr & image_msg);
79 
80 
81 void getCapCallback (const sensor_msgs::ImageConstPtr & image_msg)
82 {
83  //If we've already gotten the cam info, then go ahead
84  if(cam->getCamInfo_){
85  try{
86  tf::StampedTransform CamToOutput;
87  try{
88  tf_listener->waitForTransform(output_frame, image_msg->header.frame_id, image_msg->header.stamp, ros::Duration(1.0));
89  tf_listener->lookupTransform(output_frame, image_msg->header.frame_id, image_msg->header.stamp, CamToOutput);
90  }
91  catch (tf::TransformException ex){
92  ROS_ERROR("%s",ex.what());
93  }
94 
95 
96  //Convert the image
98 
99  //Get the estimated pose of the main markers by using all the markers in each bundle
100 
101  // GetMultiMarkersPoses expects an IplImage*, but as of ros groovy, cv_bridge gives
102  // us a cv::Mat. I'm too lazy to change to cv::Mat throughout right now, so I
103  // do this conversion here -jbinney
104  IplImage ipl_image = cv_ptr_->image;
105 
106  marker_detector.Detect(&ipl_image, cam, true, false, max_new_marker_error, max_track_error, CVSEQ, true);
107  arPoseMarkers_.markers.clear ();
108  for (size_t i=0; i<marker_detector.markers->size(); i++)
109  {
110  //Get the pose relative to the camera
111  int id = (*(marker_detector.markers))[i].GetId();
112  Pose p = (*(marker_detector.markers))[i].pose;
113  double px = p.translation[0]/100.0;
114  double py = p.translation[1]/100.0;
115  double pz = p.translation[2]/100.0;
116  double qx = p.quaternion[1];
117  double qy = p.quaternion[2];
118  double qz = p.quaternion[3];
119  double qw = p.quaternion[0];
120 
121  tf::Quaternion rotation (qx,qy,qz,qw);
122  tf::Vector3 origin (px,py,pz);
123  tf::Transform t (rotation, origin);
124  tf::Vector3 markerOrigin (0, 0, 0);
125  tf::Transform m (tf::Quaternion::getIdentity (), markerOrigin);
126  tf::Transform markerPose = t * m; // marker pose in the camera frame
127 
128  tf::Vector3 z_axis_cam = tf::Transform(rotation, tf::Vector3(0,0,0)) * tf::Vector3(0, 0, 1);
129 // ROS_INFO("%02i Z in cam frame: %f %f %f",id, z_axis_cam.x(), z_axis_cam.y(), z_axis_cam.z());
131  if (z_axis_cam.z() > 0)
132  {
133  continue;
134  }
135 
136  //Publish the transform from the camera to the marker
137  std::string markerFrame = "ar_marker_";
138  std::stringstream out;
139  out << id;
140  std::string id_string = out.str();
141  markerFrame += id_string;
142  tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame.c_str());
143  tf_broadcaster->sendTransform(camToMarker);
144 
145  //Create the rviz visualization messages
146  tf::poseTFToMsg (markerPose, rvizMarker_.pose);
147  rvizMarker_.header.frame_id = image_msg->header.frame_id;
148  rvizMarker_.header.stamp = image_msg->header.stamp;
149  rvizMarker_.id = id;
150 
151  rvizMarker_.scale.x = 1.0 * marker_size/100.0;
152  rvizMarker_.scale.y = 1.0 * marker_size/100.0;
153  rvizMarker_.scale.z = 0.2 * marker_size/100.0;
154  rvizMarker_.ns = "basic_shapes";
155  rvizMarker_.type = visualization_msgs::Marker::CUBE;
156  rvizMarker_.action = visualization_msgs::Marker::ADD;
157  switch (id)
158  {
159  case 0:
160  rvizMarker_.color.r = 0.0f;
161  rvizMarker_.color.g = 0.0f;
162  rvizMarker_.color.b = 1.0f;
163  rvizMarker_.color.a = 1.0;
164  break;
165  case 1:
166  rvizMarker_.color.r = 1.0f;
167  rvizMarker_.color.g = 0.0f;
168  rvizMarker_.color.b = 0.0f;
169  rvizMarker_.color.a = 1.0;
170  break;
171  case 2:
172  rvizMarker_.color.r = 0.0f;
173  rvizMarker_.color.g = 1.0f;
174  rvizMarker_.color.b = 0.0f;
175  rvizMarker_.color.a = 1.0;
176  break;
177  case 3:
178  rvizMarker_.color.r = 0.0f;
179  rvizMarker_.color.g = 0.5f;
180  rvizMarker_.color.b = 0.5f;
181  rvizMarker_.color.a = 1.0;
182  break;
183  case 4:
184  rvizMarker_.color.r = 0.5f;
185  rvizMarker_.color.g = 0.5f;
186  rvizMarker_.color.b = 0.0;
187  rvizMarker_.color.a = 1.0;
188  break;
189  default:
190  rvizMarker_.color.r = 0.5f;
191  rvizMarker_.color.g = 0.0f;
192  rvizMarker_.color.b = 0.5f;
193  rvizMarker_.color.a = 1.0;
194  break;
195  }
196  rvizMarker_.lifetime = ros::Duration (1.0);
197  rvizMarkerPub_.publish (rvizMarker_);
198 
199  //Get the pose of the tag in the camera frame, then the output frame (usually torso)
200  tf::Transform tagPoseOutput = CamToOutput * markerPose;
201 
202  //Create the pose marker messages
203  ar_track_alvar_msgs::AlvarMarker ar_pose_marker;
204  tf::poseTFToMsg (tagPoseOutput, ar_pose_marker.pose.pose);
205  ar_pose_marker.header.frame_id = output_frame;
206  ar_pose_marker.header.stamp = image_msg->header.stamp;
207  ar_pose_marker.id = id;
208  arPoseMarkers_.markers.push_back (ar_pose_marker);
209  }
210  arMarkerPub_.publish (arPoseMarkers_);
211  }
212  catch (cv_bridge::Exception& e){
213  ROS_ERROR ("Could not convert from '%s' to 'rgb8'.", image_msg->encoding.c_str ());
214  }
215  }
216 }
217 
218 void configCallback(ar_track_alvar::ParamsConfig &config, uint32_t level)
219 {
220  ROS_INFO("AR tracker reconfigured: %s %.2f %.2f %.2f %.2f", config.enabled ? "ENABLED" : "DISABLED",
221  config.max_frequency, config.marker_size, config.max_new_marker_error, config.max_track_error);
222 
223  enableSwitched = enabled != config.enabled;
224 
225  enabled = config.enabled;
226  max_frequency = config.max_frequency;
227  marker_size = config.marker_size;
228  max_new_marker_error = config.max_new_marker_error;
229  max_track_error = config.max_track_error;
230 }
231 
232 void enableCallback(const std_msgs::BoolConstPtr& msg)
233 {
234  enableSwitched = enabled != msg->data;
235  enabled = msg->data;
236 }
237 
238 int main(int argc, char *argv[])
239 {
240  ros::init (argc, argv, "marker_detect");
241  ros::NodeHandle n, pn("~");
242 
243  if(argc > 1) {
244  ROS_WARN("Command line arguments are deprecated. Consider using ROS parameters and remappings.");
245 
246  if(argc < 7){
247  std::cout << std::endl;
248  cout << "Not enough arguments provided." << endl;
249  cout << "Usage: ./individualMarkersNoKinect <marker size in cm> <max new marker error> <max track error> "
250  << "<cam image topic> <cam info topic> <output frame> [ <max frequency> <marker_resolution> <marker_margin>]";
251  std::cout << std::endl;
252  return 0;
253  }
254 
255  // Get params from command line
256  marker_size = atof(argv[1]);
257  max_new_marker_error = atof(argv[2]);
258  max_track_error = atof(argv[3]);
259  cam_image_topic = argv[4];
260  cam_info_topic = argv[5];
261  output_frame = argv[6];
262 
263  if (argc > 7) {
264  max_frequency = atof(argv[7]);
265  pn.setParam("max_frequency", max_frequency);
266  }
267  if (argc > 8)
268  marker_resolution = atoi(argv[8]);
269  if (argc > 9)
270  marker_margin = atoi(argv[9]);
271 
272  } else {
273  // Get params from ros param server.
274  pn.param("marker_size", marker_size, 10.0);
275  pn.param("max_new_marker_error", max_new_marker_error, 0.08);
276  pn.param("max_track_error", max_track_error, 0.2);
277  pn.param("max_frequency", max_frequency, 8.0);
278  pn.setParam("max_frequency", max_frequency); // in case it was not set.
279  pn.param("marker_resolution", marker_resolution, 5);
280  pn.param("marker_margin", marker_margin, 2);
281  if (!pn.getParam("output_frame", output_frame)) {
282  ROS_ERROR("Param 'output_frame' has to be set.");
283  exit(EXIT_FAILURE);
284  }
285 
286  // Camera input topics. Use remapping to map to your camera topics.
287  cam_image_topic = "camera_image";
288  cam_info_topic = "camera_info";
289  }
290 
291  // Set dynamically configurable parameters so they don't get replaced by default values
292  pn.setParam("marker_size", marker_size);
293  pn.setParam("max_new_marker_error", max_new_marker_error);
294  pn.setParam("max_track_error", max_track_error);
295 
297 
298  cam = new Camera(n, cam_info_topic);
299  tf_listener = new tf::TransformListener(n);
300  tf_broadcaster = new tf::TransformBroadcaster();
301  arMarkerPub_ = n.advertise < ar_track_alvar_msgs::AlvarMarkers > ("ar_pose_marker", 0);
302  rvizMarkerPub_ = n.advertise < visualization_msgs::Marker > ("visualization_marker", 0);
303 
304  // Prepare dynamic reconfiguration
305  dynamic_reconfigure::Server < ar_track_alvar::ParamsConfig > server;
306  dynamic_reconfigure::Server<ar_track_alvar::ParamsConfig>::CallbackType f;
307 
308  f = boost::bind(&configCallback, _1, _2);
309  server.setCallback(f);
310 
311  //Give tf a chance to catch up before the camera callback starts asking for transforms
312  // It will also reconfigure parameters for the first time, setting the default values
313  ros::Duration(1.0).sleep();
314  ros::spinOnce();
315 
317 
318  // Run at the configured rate, discarding pointcloud msgs if necessary
319  ros::Rate rate(max_frequency);
320 
323  ros::Subscriber enable_sub_ = pn.subscribe("enable_detection", 1, &enableCallback);
324 
325  enableSwitched = true;
326  while (ros::ok())
327  {
328  ros::spinOnce();
329  rate.sleep();
330 
331  if (std::abs((rate.expectedCycleTime() - ros::Duration(1.0 / max_frequency)).toSec()) > 0.001)
332  {
333  // Change rate dynamically; if must be above 0, as 0 will provoke a segfault on next spinOnce
334  ROS_DEBUG("Changing frequency from %.2f to %.2f", 1.0 / rate.expectedCycleTime().toSec(), max_frequency);
335  rate = ros::Rate(max_frequency);
336  }
337 
338  if (enableSwitched)
339  {
340  // Enable/disable switch: subscribe/unsubscribe to make use of pointcloud processing nodelet
341  // lazy publishing policy; in CPU-scarce computer as TurtleBot's laptop this is a huge saving
342  if (enabled)
343  cam_sub_ = it_.subscribe(cam_image_topic, 1, &getCapCallback);
344  else
345  cam_sub_.shutdown();
346  enableSwitched = false;
347  }
348  }
349 
350  return 0;
351 }
Main ALVAR namespace.
Definition: Alvar.h:174
int main(int argc, char *argv[])
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
tf::TransformListener * tf_listener
void configCallback(ar_track_alvar::ParamsConfig &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
image_transport::Subscriber cam_sub_
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void SetMarkerSize(double _edge_length=1, int _res=5, double _margin=2)
ros::Publisher rvizMarkerPub_
bool sleep() const
This file implements a generic marker detector.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher arMarkerPub_
tf::TransformBroadcaster * tf_broadcaster
std::string output_frame
#define ROS_WARN(...)
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
Definition: Camera.h:82
double max_track_error
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
std::vector< M, Eigen::aligned_allocator< M > > * markers
std::string cam_image_topic
MarkerDetector for detecting markers of type M
double marker_size
TFSIMD_FORCE_INLINE const tfScalar & z() const
Camera * cam
Duration expectedCycleTime() const
static const Quaternion & getIdentity()
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
MarkerDetector< MarkerData > marker_detector
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
std::string cam_info_topic
Pose representation derived from the Rotation class
Definition: Pose.h:50
void enableCallback(const std_msgs::BoolConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
cv_bridge::CvImagePtr cv_ptr_
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
bool sleep()
visualization_msgs::Marker rvizMarker_
double quaternion[4]
Definition: Rotation.h:48
ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
double max_new_marker_error
bool enableSwitched
bool getParam(const std::string &key, std::string &s) const
int Detect(IplImage *image, Camera *cam, bool track=false, bool visualize=false, double max_new_marker_error=0.08, double max_track_error=0.2, LabelingMethod labeling_method=CVSEQ, bool update_pose=true)
Detect Marker &#39;s from image
double max_frequency
int marker_resolution
double translation[4]
Definition: Pose.h:54
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void getCapCallback(const sensor_msgs::ImageConstPtr &image_msg)
#define ROS_DEBUG(...)
bool getCamInfo_
Definition: Camera.h:92


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Mon Jun 10 2019 12:47:04