$search
00001 /* 00002 * Copyright (c) 2010, Dejan Pangercic <dejan.pangercic@cs.tum.edu> 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 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include <ros/ros.h> 00031 #include <ros/node_handle.h> 00032 //#include "cv_bridge/CvBridge.h" 00033 //#include <opencv/cv.h> 00034 //#include <opencv/highgui.h> 00035 #include <string.h> 00036 #include <vision_msgs/cop_answer.h> 00037 00038 using namespace std; 00039 00040 class SyntheticPercepts { 00041 00042 public: 00043 double rate_; 00044 int object_id_; 00045 std::vector<std::string> objects_; 00046 std::string missing_object_; 00047 SyntheticPercepts(ros::NodeHandle &n) : 00048 n_(n) 00049 { 00050 tabletop_pub_ = n_.advertise<vision_msgs::cop_answer>("tabletop_percepts",10); 00051 n_.param ("object_id", object_id_, 700000); 00052 n_.param("missing_object", missing_object_, string("")); 00053 objects_.push_back("BreakfastCereal"), objects_.push_back("CowsMilk-Product"), objects_.push_back("Bowl-Eating"); 00054 for (unsigned int i = 0; i < objects_.size(); i++) 00055 { 00056 if (objects_[i] == missing_object_) 00057 { 00058 objects_.erase (objects_.begin()+i); 00059 } 00060 } 00061 } 00062 00063 00064 ~SyntheticPercepts() 00065 { 00066 } 00067 00069 // Spin (!) 00070 bool spin () 00071 { 00072 ros::Rate loop_rate(1); 00073 vision_msgs::cop_answer msg; 00074 vision_msgs::cop_descriptor cop_descriptor; 00075 vision_msgs::aposteriori_position aposteriori_position; 00076 vision_msgs::cop_descriptor cop_descriptor2; 00077 vision_msgs::aposteriori_position aposteriori_position2; 00078 msg.found_poses.push_back(aposteriori_position); 00079 msg.found_poses.push_back(aposteriori_position2); 00080 00081 msg.found_poses[0].models.push_back(cop_descriptor); 00082 msg.found_poses[1].models.push_back(cop_descriptor2); 00083 00084 msg.found_poses[0].objectId = 0; 00085 msg.found_poses[1].objectId = 1; 00086 00087 while (n_.ok ()) 00088 { 00089 ROS_INFO ("Publishing data on topic %s.", n_.resolveName ("tabletop_percepts").c_str ()); 00090 msg.found_poses[0].models[0].type = "ODUFinder"; 00091 // msg.found_poses[0].models[0].sem_class = "CowsMilk-Product"; 00092 msg.found_poses[0].models[0].sem_class = objects_[0]; 00093 msg.found_poses[0].models[0].object_id = ++object_id_; 00094 msg.found_poses[0].position = 0; 00095 00096 msg.found_poses[1].models[0].type = "ODUFinder"; 00097 // msg.found_poses[1].models[0].sem_class = "BreakfastCereal"; 00098 msg.found_poses[1].models[0].sem_class = objects_[1]; 00099 msg.found_poses[1].models[0].object_id = ++object_id_; 00100 msg.found_poses[1].position = 0; 00101 00102 tabletop_pub_.publish(msg); 00103 loop_rate.sleep(); 00104 ros::spinOnce (); 00105 } 00106 return (true); 00107 } 00108 00109 protected: 00110 00111 ros::NodeHandle n_; 00112 ros::Publisher tabletop_pub_; 00113 00114 }; 00115 00116 int main(int argc, char** argv) 00117 { 00118 ros::init(argc, argv, "synthetic_percepts"); 00119 ros::NodeHandle n("~"); 00120 SyntheticPercepts sp(n); 00121 sp.spin(); 00122 return 0; 00123 }