00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _camera_object_detection_alg_node_h_ 00026 #define _camera_object_detection_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "camera_object_detection_alg.h" 00030 #include <image_transport/image_transport.h> 00031 #include <image_geometry/pinhole_camera_model.h> 00032 00033 // [publisher subscriber headers] 00034 #include <trajectory_msgs/JointTrajectoryPoint.h> 00035 #include <iri_perception_msgs/peopleTrackingArray.h> 00036 #include <sensor_msgs/CameraInfo.h> 00037 00038 // [service client headers] 00039 00040 // [action server client headers] 00041 #include <actionlib/client/simple_action_client.h> 00042 #include <actionlib/client/terminal_state.h> 00043 #include <iri_nav_msgs/followTargetAction.h> 00044 00045 #include <geometry_msgs/PointStamped.h> 00046 #include <tf/transform_listener.h> 00047 00052 class CameraObjectDetectionAlgNode : public algorithm_base::IriBaseAlgorithm<CameraObjectDetectionAlgorithm> 00053 { 00054 private: 00055 // [publisher attributes] 00056 ros::Publisher target_joints_publisher_; 00057 trajectory_msgs::JointTrajectoryPoint JointTrajectoryPoint_msg_; 00058 ros::Publisher people_out_publisher_; 00059 iri_perception_msgs::peopleTrackingArray peopleTrackingArray_msg_; 00060 00061 image_transport::Publisher image_publisher; 00062 sensor_msgs::ImagePtr output_image; 00063 00064 // [subscriber attributes] 00065 ros::Subscriber people_subscriber_; 00066 void people_callback(const iri_perception_msgs::peopleTrackingArray::ConstPtr& msg); 00067 00068 ros::Subscriber camera_info_subscriber_; 00069 void camera_info_callback(const sensor_msgs::CameraInfo::ConstPtr& msg); 00070 00071 image_transport::ImageTransport it; 00072 image_transport::Subscriber camera_subscriber; 00073 void image_callback(const sensor_msgs::ImageConstPtr& image_msg); 00074 sensor_msgs::ImageConstPtr input_image; 00075 00076 // [service attributes] 00077 00078 // [client attributes] 00079 00080 // [action server attributes] 00081 00082 // [action client attributes] 00083 actionlib::SimpleActionClient<iri_nav_msgs::followTargetAction> follow_target_client_; 00084 iri_nav_msgs::followTargetGoal follow_target_goal_; 00085 void follow_targetMakeActionRequest(); 00086 void follow_targetDone(const actionlib::SimpleClientGoalState& state, const iri_nav_msgs::followTargetResultConstPtr& result); 00087 void follow_targetActive(); 00088 void follow_targetFeedback(const iri_nav_msgs::followTargetFeedbackConstPtr& feedback); 00089 00090 00091 cv::Rect init_rect; 00092 cv::Rect output_rect; 00093 cv::Size image_size; 00094 image_geometry::PinholeCameraModel camera_model; 00095 geometry_msgs::PointStamped init_point; 00096 tf::TransformListener tf_listener; 00097 00098 bool pointReady; 00099 bool initialized; 00100 bool rectReady; 00101 bool newDetection; 00102 bool tracking; 00103 bool following_target; 00104 int id; 00105 double window_width; 00106 double window_height; 00107 double window_offset; 00108 00109 bool computeRectangle(); 00110 void follow_rectangle(cv::Rect rect); 00111 00112 public: 00119 CameraObjectDetectionAlgNode(void); 00120 00127 ~CameraObjectDetectionAlgNode(void); 00128 00129 protected: 00142 void mainNodeThread(void); 00143 00156 void node_config_update(Config &config, uint32_t level); 00157 00164 void addNodeDiagnostics(void); 00165 00166 // [diagnostic functions] 00167 00168 // [test functions] 00169 }; 00170 00171 #endif