32 #ifndef TUW_MARKER_POSE_ESTIMATION_POSE_ESTIMATION_NODE_H 33 #define TUW_MARKER_POSE_ESTIMATION_POSE_ESTIMATION_NODE_H 37 #include <marker_msgs/MarkerDetection.h> 38 #include <marker_msgs/FiducialDetection.h> 40 #include <dynamic_reconfigure/server.h> 41 #include <tuw_marker_pose_estimation/MarkerPoseEstimationConfig.h> 59 dynamic_reconfigure::Server<tuw_marker_pose_estimation::MarkerPoseEstimationConfig>
configServer_;
60 dynamic_reconfigure::Server<tuw_marker_pose_estimation::MarkerPoseEstimationConfig>::CallbackType
configCallbackFnct_;
66 void publishMarkers(
const std_msgs::Header &header, std::vector<MarkerPose> &markerPoses);
68 void configCallback(tuw_marker_pose_estimation::MarkerPoseEstimationConfig &config, uint32_t level);
71 #endif //TUW_MARKER_POSE_ESTIMATION_POSE_ESTIMATION_NODE_H ros::Subscriber fiducialDetectionSubscriber_
dynamic_reconfigure::Server< tuw_marker_pose_estimation::MarkerPoseEstimationConfig >::CallbackType configCallbackFnct_
void fiducialDetectionCallback(const marker_msgs::FiducialDetection::ConstPtr &msg)
PoseEstimationMarkerMapNode(ros::NodeHandle &n, MarkerMapConfig markerMapConfig)
void publishMarkers(const std_msgs::Header &header, std::vector< MarkerPose > &markerPoses)
ros::Publisher pub_markers_
PoseEstimationMarkerMapBase base_
~PoseEstimationMarkerMapNode()
tf::TransformBroadcaster transformBroadcaster_
dynamic_reconfigure::Server< tuw_marker_pose_estimation::MarkerPoseEstimationConfig > configServer_
void configCallback(tuw_marker_pose_estimation::MarkerPoseEstimationConfig &config, uint32_t level)