tuw_checkerboard_node.h
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (c) 2017
3  * Florian Beck <florian.beck@tuwien.ac.at>
4  * Markus Bader <markus.bader@tuwien.ac.at>
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * 3. All advertising materials mentioning features or use of this software
15  * must display the following acknowledgement:
16  * This product includes software developed by the TU-Wien.
17  * 4. Neither the name of the TU-Wien nor the
18  * names of its contributors may be used to endorse or promote products
19  * derived from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY Markus Bader ''AS IS'' AND ANY
22  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
23  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY
25  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
26  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
28  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
29  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
30  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  ***************************************************************************/
32 
33 
34 #ifndef TUW_CHECKERBOARD_NODE_H
35 #define TUW_CHECKERBOARD_NODE_H
36 
37 #include <ros/ros.h>
38 
41 
42 #include <tf/transform_listener.h>
44 
46 #include <dynamic_reconfigure/server.h>
47 #include <marker_msgs/MarkerDetection.h>
48 #include <marker_msgs/FiducialDetection.h>
49 #include <geometry_msgs/PoseStamped.h>
50 #include <tuw_checkerboard/CheckerboardDetectionConfig.h>
51 
52 
54 {
55 public:
56  CheckerboardNode(); // Constructor
57 private:
58 
64  std::shared_ptr<tf::TransformBroadcaster> tf_broadcaster_;
67  cv::Mat image_grey_;
68  cv::Mat image_rgb_;
69  tuw_checkerboard::CheckerboardDetectionConfig config_;
71  marker_msgs::MarkerDetection marker_detection_;
72  marker_msgs::FiducialDetection fiducial_detection_;
73  std::vector<cv::Point2f> image_corners_;
74  std::vector<cv::Point3f> object_corners_;
75  cv::Mat_<double> intrinsic_matrix_;
76  cv::Mat_<double> extrinsic_matrix_;
77  cv::Mat_<double> projection_matrix_;
79 
80 
81  void callbackCamera(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& info_msg);
82  dynamic_reconfigure::Server<tuw_checkerboard::CheckerboardDetectionConfig>* reconfigureServer_;
83  dynamic_reconfigure::Server<tuw_checkerboard::CheckerboardDetectionConfig>::CallbackType reconfigureFnc_;
84  void callbackConfig ( tuw_checkerboard::CheckerboardDetectionConfig &_config, uint32_t _level );
85 };
86 
87 #endif //TUW_CHECKERBOARD_NODE_H
std::shared_ptr< tf::TransformBroadcaster > tf_broadcaster_
image_geometry::PinholeCameraModel cam_model_
ros::Publisher pub_fiducials_
dynamic_reconfigure::Server< tuw_checkerboard::CheckerboardDetectionConfig > * reconfigureServer_
parameter server stuff
ros::NodeHandle nh_private_
std::vector< cv::Point3f > object_corners_
std::string checkerboard_frame_id_
marker_msgs::MarkerDetection marker_detection_
image_transport::CameraSubscriber sub_cam_
marker_msgs::FiducialDetection fiducial_detection_
void callbackCamera(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
std::vector< cv::Point2f > image_corners_
cv::Mat_< double > projection_matrix_
cv::Mat_< double > extrinsic_matrix_
dynamic_reconfigure::Server< tuw_checkerboard::CheckerboardDetectionConfig >::CallbackType reconfigureFnc_
parameter server stuff
cv::Mat_< double > intrinsic_matrix_
void callbackConfig(tuw_checkerboard::CheckerboardDetectionConfig &_config, uint32_t _level)
callback function on incoming parameter changes
tf::Transform transform_
tuw_checkerboard::CheckerboardDetectionConfig config_
ros::Publisher pub_markers_
ros::Publisher pub_pose_


tuw_checkerboard
Author(s): Florian Beck , Markus Bader
autogenerated on Mon Jun 10 2019 15:42:06