00001 /*************************************************************************** 00002 * Copyright (c) 2014 Markus Bader <markus.bader@tuwien.ac.at> 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 1. Redistributions of source code must retain the above copyright 00008 * notice, this list of conditions and the following disclaimer. 00009 * 2. Redistributions in binary form must reproduce the above copyright 00010 * notice, this list of conditions and the following disclaimer in the 00011 * documentation and/or other materials provided with the distribution. 00012 * 3. All advertising materials mentioning features or use of this software 00013 * must display the following acknowledgement: 00014 * This product includes software developed by the TU-Wien. 00015 * 4. Neither the name of the TU-Wien nor the 00016 * names of its contributors may be used to endorse or promote products 00017 * derived from this software without specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY Markus Bader ''AS IS'' AND ANY 00020 * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00021 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00022 * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY 00023 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00024 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00025 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00026 * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00027 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00028 * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00029 ***************************************************************************/ 00030 00031 00032 #ifndef V4R_ELLIPSES_NODE_H 00033 #define V4R_ELLIPSES_NODE_H 00034 00035 #include "ros/ros.h" 00036 #include <nodelet/nodelet.h> 00037 #include <visualization_msgs/Marker.h> 00038 #include "v4r_ellipses/v4r_ellipses.h" 00039 #include <cv_bridge/cv_bridge.h> 00040 #include <image_transport/image_transport.h> 00041 #include <dynamic_reconfigure/server.h> 00042 #include <v4r_ellipses/EllipsesDetectionConfig.h> 00043 #include <boost/date_time/posix_time/posix_time.hpp> 00044 #include <tf/transform_broadcaster.h> 00045 #include <v4r_ellipses/ellipses.h> 00046 #include <v4r_ellipses/markers.h> 00047 00048 namespace V4R { 00049 00051 class EllipsesDetectionNode : public EllipsesDetection , public nodelet::Nodelet { 00052 public: 00053 struct ParametersNode : public Parameters { 00054 ParametersNode(); 00055 void update(const unsigned long &counter); 00056 void callbackParameters (v4r_ellipses::EllipsesDetectionConfig &config, uint32_t level ); 00057 ros::NodeHandle node; 00058 dynamic_reconfigure::Server<v4r_ellipses::EllipsesDetectionConfig> reconfigureServer_; 00059 dynamic_reconfigure::Server<v4r_ellipses::EllipsesDetectionConfig>::CallbackType reconfigureFnc_; 00060 std::string node_name; 00061 bool debug_freeze; 00062 bool show_camera_image; 00063 int show_camera_image_waitkey; 00064 int image_skip; 00065 bool skip_second_tf; 00066 std::string tf_prefix; 00067 }; 00068 EllipsesDetectionNode ( ); 00069 ~EllipsesDetectionNode(); 00070 void init (); 00071 virtual void onInit(); 00072 void imageCallback(const sensor_msgs::ImageConstPtr& image_msg, 00073 const sensor_msgs::CameraInfoConstPtr& info_msg); 00074 private: //functions 00075 const ParametersNode *param(); 00076 void update (); 00077 void publishTf(); 00078 void publishMarker (const std_msgs::Header &header); 00079 void publishPerceptions (const std_msgs::Header &header); 00080 void createTransforms(const std_msgs::Header &header); 00081 private: // variables 00082 ros::NodeHandle n_; 00083 unsigned long callback_counter_; 00084 tf::TransformBroadcaster transformBroadcaster_; 00085 ros::Publisher pub_viz_marker_; 00086 ros::Publisher pub_ellipses_; 00087 ros::Publisher pub_perceptions_; 00088 visualization_msgs::Marker msg_line_list_; 00089 image_transport::ImageTransport imageTransport_; 00090 image_transport::CameraSubscriber sub_camera_; 00091 cv_bridge::CvImagePtr image_mono_; 00092 sensor_msgs::CameraInfoConstPtr camera_info_; 00093 boost::posix_time::ptime timeCallbackReceivedLast_; 00094 boost::posix_time::ptime timeCallbackReceived_; 00095 boost::posix_time::ptime timeDetectionStart_; 00096 boost::posix_time::ptime timeDetectionEnd_; 00097 std::list<tf::StampedTransform> markerTransforms_; 00098 }; 00099 } 00100 00101 #endif //V4R_ELLIPSES_NODE_H