ellipses_nodelet.h
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (c) 2014 Markus Bader <markus.bader@tuwien.ac.at>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * 1. Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * 2. Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * 3. All advertising materials mentioning features or use of this software
13  * must display the following acknowledgement:
14  * This product includes software developed by the TU-Wien.
15  * 4. Neither the name of the TU-Wien nor the
16  * names of its contributors may be used to endorse or promote products
17  * derived from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY Markus Bader ''AS IS'' AND ANY
20  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY
23  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
24  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
26  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
28  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  ***************************************************************************/
30 
31 
32 #ifndef TUW_ELLIPSES_NODE_H
33 #define TUW_ELLIPSES_NODE_H
34 
35 #include "ros/ros.h"
36 #include <nodelet/nodelet.h>
37 #include <cv_bridge/cv_bridge.h>
39 #include <dynamic_reconfigure/server.h>
40 #include <tuw_ellipses/EllipsesDetectionConfig.h>
41 #include <boost/date_time/posix_time/posix_time.hpp>
44 #include <marker_msgs/FiducialDetection.h>
45 #include <marker_msgs/MarkerDetection.h>
46 
47 namespace tuw {
48 
51 public:
52  struct ParametersNode : public Parameters {
54  void update(const unsigned long &counter);
55  void callbackParameters (tuw_ellipses::EllipsesDetectionConfig &config, uint32_t level );
57  dynamic_reconfigure::Server<tuw_ellipses::EllipsesDetectionConfig> reconfigureServer_;
58  dynamic_reconfigure::Server<tuw_ellipses::EllipsesDetectionConfig>::CallbackType reconfigureFnc_;
59  std::string node_name;
62  bool publishTF;
68  std::string tf_prefix;
69  };
72  void init ();
73  virtual void onInit();
74  void imageCallback(const sensor_msgs::ImageConstPtr& image_msg,
75  const sensor_msgs::CameraInfoConstPtr& info_msg);
76 private: //functions
77  const ParametersNode *param();
78  void update ();
79  void publishTf();
80  void publishMarker (const std_msgs::Header &header);
81  void publishFiducials (const std_msgs::Header &header);
82  void createTransforms(const std_msgs::Header &header);
83 private: // variables
85  unsigned long callback_counter_;
93  sensor_msgs::CameraInfoConstPtr camera_info_;
94  boost::posix_time::ptime timeCallbackReceivedLast_;
95  boost::posix_time::ptime timeCallbackReceived_;
96  boost::posix_time::ptime timeDetectionStart_;
97  boost::posix_time::ptime timeDetectionEnd_;
98  std::list<tf::StampedTransform> markerTransforms_;
99 };
100 }
101 
102 #endif //TUW_ELLIPSES_NODE_H
dynamic_reconfigure::Server< tuw_ellipses::EllipsesDetectionConfig > reconfigureServer_
const ParametersNode * param()
dynamic_reconfigure::Server< tuw_ellipses::EllipsesDetectionConfig >::CallbackType reconfigureFnc_
tf::TransformBroadcaster transformBroadcaster_
boost::posix_time::ptime timeCallbackReceivedLast_
boost::posix_time::ptime timeDetectionStart_
std::list< tf::StampedTransform > markerTransforms_
boost::posix_time::ptime timeDetectionEnd_
void imageCallback(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
sensor_msgs::CameraInfoConstPtr camera_info_
boost::posix_time::ptime timeCallbackReceived_
cv_bridge::CvImagePtr image_mono_
image_transport::CameraSubscriber sub_camera_
void createTransforms(const std_msgs::Header &header)
image_transport::ImageTransport imageTransport_
void callbackParameters(tuw_ellipses::EllipsesDetectionConfig &config, uint32_t level)
void update(const unsigned long &counter)


tuw_ellipses
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:42:10