18 #ifndef MARKERPUBLISHER_H 19 #define MARKERPUBLISHER_H 20 #define NAMESPACE "calibrationObject" 21 #define NAMESPACEOBJECT "calibrationObject/Object" //The namespace to which the calibration Object is published 22 #define NAMESPACEMARKER "calibrationObject/Marker" //The namespace to which the marker positions are published 23 #define NAMESPACECAMERA "calibrationObject/Camera" //The namespace to which thecamera poses are published 29 #include <visualization_msgs/Marker.h> 30 #include <geometry_msgs/Point.h> 31 #include <Eigen/Dense> 34 #include <boost/shared_ptr.hpp> 39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 void publishTriangles(std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > *triangles);
51 void publishTetrahedon(
const Eigen::Vector2d &baseA,
const Eigen::Vector2d &baseB,
const Eigen::Vector2d &baseC,
const Eigen::Vector3d &top);
52 void publishARMarkers(
bool activeLeft,
bool activeRight,
const Eigen::Matrix4d topFrame);
53 void publishColouredCameraFrames(std::vector<
colouredCameraFrame, Eigen::aligned_allocator<colouredCameraFrame> > * camFrames);
54 void publishCameraFramePointer(
const Eigen::Vector3d &startPoint,
const Eigen::Vector3d &endPoint,
bool isValid);
79 #endif // MARKERPUBLISHER_H
std::vector< visualization_msgs::Marker > markerCameraFrames
ROSCONSOLE_DECL void initialize()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix4d pose
visualization_msgs::Marker markerTop
std_msgs::ColorRGBA color
visualization_msgs::Marker markerARMarker_Left
visualization_msgs::Marker markerBottom
boost::shared_ptr< Calibration_Object > calibrationObject
ros::Publisher pubObjectPosition
ros::Publisher pubMarkerPosition
visualization_msgs::Marker markerCameraFrame
visualization_msgs::Marker markerTriangles
visualization_msgs::Marker markerARMarker_Right
ros::Publisher pubCameraPosition