Main header file for ar_bounding box. More...
#include <string.h>#include <stdarg.h>#include <AR/ar.h>#include <AR/arMulti.h>#include <geometry_msgs/TransformStamped.h>#include <tf/transform_broadcaster.h>#include <tf/transform_listener.h>#include <image_transport/image_transport.h>#include <sensor_msgs/CameraInfo.h>#include <sensor_msgs/PointCloud2.h>#include <visualization_msgs/Marker.h>#include <pcl/ros/conversions.h>#include <pcl/point_types.h>#include <message_filters/subscriber.h>#include <opencv/cv.h>#include <cv_bridge/CvBridge.h>#include <ar_pose/ARMarkers.h>#include <ar_kinect/object.h>#include <boost/multi_array.hpp>

Go to the source code of this file.
Classes | |
| class | ARPublisher | 
Defines | |
| #define | AR_BOUNDING_BOX | 
| #define | DBG(str) | 
| #define | DEBUG_AR_KINECT | 
| #define | ORIGIN "/camera_rgb_optical_frame" | 
| Kinect camera origin tf frame.   | |
| #define | TARGET "/PATTERN_BASE" | 
| object center tf frame   | |
Typedefs | |
| typedef pcl::PointCloud < pcl::PointXYZRGB >  | PointCloud | 
Variables | |
| const double | AR_TO_ROS = 0.001 | 
| const std::string | cameraImageTopic_ = "/camera/depth_registered/image" | 
| const std::string | cameraInfoTopic_ = "/camera/depth_registered/camera_info" | 
| const std::string | cloudTopic_ = "/camera/depth_registered/points" | 
Main header file for ar_bounding box.
Based on Michael Ferguson's ar_kinect.
This file is part of the RoboEarth ROS ar_bounding_box package.
It file was originally created for RoboEarth. The research leading to these results has received funding from the European Union Seventh Framework Programme FP7/2007-2013 under grant agreement no248942 RoboEarth.
Copyright (C) 2011 by Andreas Koch, University of Stuttgart
This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>.
Definition in file ar_kinect.h.
| #define AR_BOUNDING_BOX | 
Definition at line 62 of file ar_kinect.h.
| #define DBG | ( | str | ) | 
Definition at line 70 of file ar_kinect.h.
| #define DEBUG_AR_KINECT | 
Definition at line 63 of file ar_kinect.h.
| #define ORIGIN "/camera_rgb_optical_frame" | 
Kinect camera origin tf frame.
Definition at line 66 of file ar_kinect.h.
| #define TARGET "/PATTERN_BASE" | 
object center tf frame
Definition at line 68 of file ar_kinect.h.
| typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud | 
Definition at line 80 of file ar_kinect.h.
| const double AR_TO_ROS = 0.001 | 
Definition at line 79 of file ar_kinect.h.
| const std::string cameraImageTopic_ = "/camera/depth_registered/image" | 
Definition at line 72 of file ar_kinect.h.
| const std::string cameraInfoTopic_ = "/camera/depth_registered/camera_info" | 
Definition at line 73 of file ar_kinect.h.
| const std::string cloudTopic_ = "/camera/depth_registered/points" | 
Definition at line 74 of file ar_kinect.h.