#include <actionlib/client/simple_action_client.h>#include <actionlib/server/simple_action_server.h>#include <boost/thread/condition.hpp>#include <ros/ros.h>#include <boost/thread.hpp>#include <boost/shared_ptr.hpp>#include <actionlib_msgs/GoalID.h>#include <actionlib_msgs/GoalStatusArray.h>#include <actionlib_msgs/GoalStatus.h>#include <actionlib/enclosure_deleter.h>#include <actionlib/goal_id_generator.h>#include <actionlib/action_definition.h>#include <actionlib/server/status_tracker.h>#include <actionlib/destruction_guard.h>#include <list>#include <string>#include <vector>#include <ostream>#include "ros/serialization.h"#include "ros/builtin_message_traits.h"#include "ros/message_operations.h"#include "ros/message.h"#include "ros/time.h"#include "std_msgs/Header.h"#include "geometry_msgs/Point.h"#include "ros/service_traits.h"#include "sensor_msgs/Image.h"#include "sensor_msgs/RegionOfInterest.h"#include "sensor_msgs/CameraInfo.h"#include "geometry_msgs/PoseStamped.h"#include "tabletop_object_detector/Table.h"#include "sensor_msgs/PointCloud.h"#include "geometry_msgs/Quaternion.h"#include <iostream>#include <iomanip>#include <cmath>#include <sstream>#include <map>#include <stdexcept>#include <boost/thread/mutex.hpp>#include "geometry_msgs/Vector3.h"#include "geometry_msgs/TransformStamped.h"#include "btMatrix3x3.h"#include "ros/console.h"#include "tf/exceptions.h"#include "LinearMath/btTransform.h"#include <boost/signals.hpp>#include "ros/callback_queue.h"#include <geometry_msgs/Pose.h>#include <geometry_msgs/Twist.h>#include "src/Core/util/DisableMSVCWarnings.h"#include "src/Core/util/Macros.h"#include <cerrno>#include <cstdlib>#include <complex>#include <cassert>#include <functional>#include <iosfwd>#include <cstring>#include <limits>#include <climits>#include <algorithm>#include "src/Core/util/Constants.h"#include "src/Core/util/ForwardDeclarations.h"#include "src/Core/util/Meta.h"#include "src/Core/util/XprHelper.h"#include "src/Core/util/StaticAssert.h"#include "src/Core/util/Memory.h"#include "src/Core/NumTraits.h"#include "src/Core/MathFunctions.h"#include "src/Core/GenericPacketMath.h"#include "src/Core/arch/Default/Settings.h"#include "src/Core/Functors.h"#include "src/Core/DenseCoeffsBase.h"#include "src/Core/DenseBase.h"#include "src/Core/MatrixBase.h"#include "src/Core/EigenBase.h"#include "src/Core/Assign.h"#include "src/Core/util/BlasUtil.h"#include "src/Core/DenseStorage.h"#include "src/Core/NestByValue.h"#include "src/Core/ForceAlignedAccess.h"#include "src/Core/ReturnByValue.h"#include "src/Core/NoAlias.h"#include "src/Core/PlainObjectBase.h"#include "src/Core/Matrix.h"#include "src/Core/Array.h"#include "src/Core/CwiseBinaryOp.h"#include "src/Core/CwiseUnaryOp.h"#include "src/Core/CwiseNullaryOp.h"#include "src/Core/CwiseUnaryView.h"#include "src/Core/SelfCwiseBinaryOp.h"#include "src/Core/Dot.h"#include "src/Core/StableNorm.h"#include "src/Core/MapBase.h"#include "src/Core/Stride.h"#include "src/Core/Map.h"#include "src/Core/Block.h"#include "src/Core/VectorBlock.h"#include "src/Core/Transpose.h"#include "src/Core/DiagonalMatrix.h"#include "src/Core/Diagonal.h"#include "src/Core/DiagonalProduct.h"#include "src/Core/PermutationMatrix.h"#include "src/Core/Transpositions.h"#include "src/Core/Redux.h"#include "src/Core/Visitor.h"#include "src/Core/Fuzzy.h"#include "src/Core/IO.h"#include "src/Core/Swap.h"#include "src/Core/CommaInitializer.h"#include "src/Core/Flagged.h"#include "src/Core/ProductBase.h"#include "src/Core/Product.h"#include "src/Core/TriangularMatrix.h"#include "src/Core/SelfAdjointView.h"#include "src/Core/SolveTriangular.h"#include "src/Core/products/Parallelizer.h"#include "src/Core/products/CoeffBasedProduct.h"#include "src/Core/products/GeneralBlockPanelKernel.h"#include "src/Core/products/GeneralMatrixVector.h"#include "src/Core/products/GeneralMatrixMatrix.h"#include "src/Core/products/GeneralMatrixMatrixTriangular.h"#include "src/Core/products/SelfadjointMatrixVector.h"#include "src/Core/products/SelfadjointMatrixMatrix.h"#include "src/Core/products/SelfadjointProduct.h"#include "src/Core/products/SelfadjointRank2Update.h"#include "src/Core/products/TriangularMatrixVector.h"#include "src/Core/products/TriangularMatrixMatrix.h"#include "src/Core/products/TriangularSolverMatrix.h"#include "src/Core/products/TriangularSolverVector.h"#include "src/Core/BandMatrix.h"#include "src/Core/BooleanRedux.h"#include "src/Core/Select.h"#include "src/Core/VectorwiseOp.h"#include "src/Core/Random.h"#include "src/Core/Replicate.h"#include "src/Core/Reverse.h"#include "src/Core/ArrayBase.h"#include "src/Core/ArrayWrapper.h"#include "src/Core/GlobalFunctions.h"#include "src/Core/util/EnableMSVCWarnings.h"#include "Core"#include "SVD"#include "LU"#include "src/Geometry/OrthoMethods.h"#include "src/Geometry/EulerAngles.h"#include "src/Geometry/Homogeneous.h"#include "src/Geometry/RotationBase.h"#include "src/Geometry/Rotation2D.h"#include "src/Geometry/Quaternion.h"#include "src/Geometry/AngleAxis.h"#include "src/Geometry/Transform.h"#include "src/Geometry/Translation.h"#include "src/Geometry/Scaling.h"#include "src/Geometry/Hyperplane.h"#include "src/Geometry/ParametrizedLine.h"#include "src/Geometry/AlignedBox.h"#include "src/Geometry/Umeyama.h"#include <Eigen/Core>#include <Eigen/Geometry>#include "motion_planning_msgs/RobotState.h"#include "geometric_shapes_msgs/Shape.h"#include "geometry_msgs/PointStamped.h"#include "motion_planning_msgs/ArmNavigationErrorCodes.h"#include "motion_planning_msgs/Constraints.h"#include "motion_planning_msgs/AllowedContactSpecification.h"#include "motion_planning_msgs/OrderedCollisionOperations.h"#include "motion_planning_msgs/LinkPadding.h"#include "motion_planning_msgs/MotionPlanRequest.h"#include <tf/tf.h>#include <motion_planning_msgs/RobotTrajectory.h>#include <motion_planning_msgs/JointConstraint.h>#include <trajectory_msgs/JointTrajectory.h>#include <sensor_msgs/JointState.h>#include <motion_planning_msgs/OrientationConstraint.h>#include <motion_planning_msgs/PositionConstraint.h>#include <motion_planning_msgs/GetMotionPlan.h>#include "motion_planning_msgs/JointLimits.h"#include <planning_environment_msgs/ContactInformation.h>#include "household_objects_database_msgs/DatabaseModelPose.h"#include "sensor_msgs/PointCloud2.h"#include "object_manipulation_msgs/GraspableObject.h"#include "geometry_msgs/Vector3Stamped.h"#include "object_manipulation_msgs/ManipulationResult.h"#include "object_manipulation_msgs/ManipulationPhase.h"#include "object_manipulator/tools/exceptions.h"#include <pr2_interactive_object_detection/UserCommandAction.h>#include <pr2_interactive_object_detection/msg_saver.h>#include <stereo_msgs/DisparityImage.h>#include "std_msgs/ColorRGBA.h"
Go to the source code of this file.
Classes | |
| class | InteractiveObjDetBackend |
| Does all the work for the Interactive Object Recognition GUI. More... | |