32 #ifndef TUW_MARKER_POSE_ESTIMATION_POSE_ESTIMATION_COMBOMARKER_NODE_H 33 #define TUW_MARKER_POSE_ESTIMATION_POSE_ESTIMATION_COMBOMARKER_NODE_H 39 #include <marker_msgs/MarkerDetection.h> 40 #include <marker_msgs/FiducialDetection.h> 43 #include <dynamic_reconfigure/server.h> 64 const marker_msgs::FiducialDetection::ConstPtr &msgEllipseFiducialDetection);
66 void publishMarkers(
const std_msgs::Header &header, std::vector<MarkerPose> &markerPoses);
70 #endif //TUW_MARKER_POSE_ESTIMATION_POSE_ESTIMATION_COMBOMARKER_NODE_H
void publishMarkers(const std_msgs::Header &header, std::vector< MarkerPose > &markerPoses)
message_filters::TimeSynchronizer< marker_msgs::FiducialDetection, marker_msgs::FiducialDetection > sync_
void synchronizedFiducialsCallback(const marker_msgs::FiducialDetection::ConstPtr &msgIdFiducialDetection, const marker_msgs::FiducialDetection::ConstPtr &msgEllipseFiducialDetection)
message_filters::Subscriber< marker_msgs::FiducialDetection > ellipseFiducialDetectionSubscriber_
PoseEstimationComboMarkerNode(ros::NodeHandle &n)
message_filters::Subscriber< marker_msgs::FiducialDetection > idFiducialDetectionSubscriber_
tf::TransformBroadcaster transformBroadcaster_
ros::Publisher pub_markers_
~PoseEstimationComboMarkerNode()