Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <cop_client_cpp/cop_client.h>
00031 #include <vision_srvs/cop_call.h>
00032 #include <vision_msgs/cop_feedback.h>
00033 #include <vision_srvs/srvjlo.h>
00034 using namespace vision_srvs;
00035 using namespace vision_msgs;
00036
00037 bool breaker = false;
00038 unsigned long vision_primitive = 0;
00039 bool found_trans_obj = false;
00040 unsigned long tobj_pos = 0;
00041
00042 CopClient::CopClient(ros::NodeHandle &nh, std::string stTopicName, std::string stCopName)
00043 {
00045 m_answerTopic = stTopicName;
00046 m_readAnswer = nh.subscribe<cop_answer>(stTopicName, 1000, &CopClient::callback, this);
00048 char srvname[512];
00049 sprintf(srvname, "/%s/in", stCopName.c_str());
00050 ros::service::waitForService(srvname);
00051 m_client = nh.serviceClient<cop_call>(srvname, true);
00052
00053 ros::service::waitForService("/located_object");
00054 m_jlo_client = nh.serviceClient<srvjlo>("/located_object", true);
00055
00056 m_pubFeedBack = nh.advertise<vision_msgs::cop_feedback>("/cop/feedback", 1000);
00057
00058
00059 ros::spinOnce();
00060
00061 }
00062
00063 unsigned long CopClient::LOFrameQuery(unsigned long child, unsigned long parent)
00064 {
00065 srvjlo msg;
00066 msg.request.command = "framequery";
00067 msg.request.query.id = child;
00068 msg.request.query.parent_id = parent;
00069 m_jlo_client.call(msg);
00070
00071 return msg.response.answer.id;
00072 }
00073
00074 void CopClient::LOFreeID(unsigned long id)
00075 {
00076 srvjlo msg;
00077 msg.request.command = "del";
00078 msg.request.query.id = id;
00079 m_jlo_client.call(msg);
00080 }
00081
00082 double CopClient::LODistanceQuery(unsigned long child, unsigned long parent)
00083 {
00084 srvjlo msg;
00085 if(child == parent)
00086 return 0.0;
00087 msg.request.command = "framequery";
00088 msg.request.query.id = child;
00089 msg.request.query.parent_id = parent;
00090 m_jlo_client.call(msg);
00091 LOFreeID(msg.response.answer.id);
00092 return sqrt(msg.response.answer.pose[3]*msg.response.answer.pose[3] + msg.response.answer.pose[7]*msg.response.answer.pose[7]+msg.response.answer.pose[11]*msg.response.answer.pose[11]);
00093 }
00094
00095
00096 void CopClient::LOPointQuery(unsigned long child, float *vector)
00097 {
00098 srvjlo msg;
00099 msg.request.command = "framequery";
00100 msg.request.query.id = child;
00101 msg.request.query.parent_id = 1;
00102 m_jlo_client.call(msg);
00103
00104 vector[0] = msg.response.answer.pose[3];
00105 vector[1] = msg.response.answer.pose[7];
00106 vector[2] = msg.response.answer.pose[11];
00107 LOFreeID(msg.response.answer.id);
00108
00109
00110 }
00111
00112
00113 tf::Stamped<tf::Pose> CopClient::LOPoseQuery(unsigned long child)
00114 {
00115 srvjlo msg;
00116 msg.request.command = "framequery";
00117 msg.request.query.id = child;
00118 msg.request.query.parent_id = 1;
00119 m_jlo_client.call(msg);
00120
00121 tf::Stamped<tf::Pose> ret;
00122 ret.frame_id_ = "/map";
00123 ret.setOrigin(btVector3(msg.response.answer.pose[3],msg.response.answer.pose[7],msg.response.answer.pose[11]));
00124 btMatrix3x3 mat(msg.response.answer.pose[0],msg.response.answer.pose[1],msg.response.answer.pose[2],
00125 msg.response.answer.pose[4],msg.response.answer.pose[5],msg.response.answer.pose[6],
00126 msg.response.answer.pose[8],msg.response.answer.pose[9],msg.response.answer.pose[10]);
00127 btQuaternion qat;
00128 mat.getRotation(qat);
00129 ret.setRotation(qat);
00130
00131 LOFreeID(msg.response.answer.id);
00132
00133
00134 return ret;
00135 }
00136
00137
00138 unsigned long CopClient::LOOffset(unsigned long id, unsigned long parent, float x, float y, float z)
00139 {
00140 srvjlo msg;
00141 msg.request.command = "update";
00142 msg.request.query.id = id;
00143 msg.request.query.parent_id = parent;
00144
00145 msg.request.query.pose[0] = 1.0;
00146 msg.request.query.pose[5] = 1.0;
00147 msg.request.query.pose[10] = 1.0;
00148 msg.request.query.pose[15] = 1.0;
00149 msg.request.query.pose[3] = x;
00150 msg.request.query.pose[7] = y;
00151 msg.request.query.pose[11] = z;
00152
00153 m_jlo_client.call(msg);
00154
00155 return msg.response.answer.id;
00156 }
00157
00158
00159
00160 unsigned long CopClient::LONameQuery(std::string name)
00161 {
00162 vision_srvs::srvjlo msg;
00163 msg.request.command = "namequery";
00164 msg.request.query.name = name;
00165 if (!m_jlo_client.call(msg))
00166 {
00167 printf("Error calling jlo!\n");
00168 }
00169 if (msg.response.error.length() > 0)
00170 {
00171 printf("Error from jlo: %s!\n", msg.response.error.c_str());
00172 return 0;
00173 }
00174 return msg.response.answer.id;
00175 }
00176
00177
00178 void CopClient::callback(const boost::shared_ptr<const cop_answer> &msg)
00179 {
00180 found_trans_obj = false;
00181 printf("got answer from cop! (Errors: %s)\n", msg->error.c_str());
00182 m_msg_cluster[msg->perception_primitive].push_back(*msg);
00183 for(size_t i = 0; i < msg->found_poses.size(); i++)
00184 {
00185 const aposteriori_position &pos = msg->found_poses[i];
00186 printf("Found Obj nr %d with prob %f at pos %d\n", (int)pos.objectId, pos.probability, (int)pos.position);
00187 for(size_t j = 0; j < pos.models.size(); j++)
00188 {
00189 printf(" %s", pos.models[j].sem_class.c_str());
00190 }
00191
00192 if(pos.models.size() > 0)
00193 printf("\n");
00194 }
00195 printf("End!\n");
00196 }
00197
00198
00199 long CopClient::CallCop(std::string object_class, unsigned long position_id, int num_of_objects, unsigned long alterantive_id, unsigned long action_type)
00200 {
00201 cop_call call;
00202 call.request.outputtopic = m_answerTopic;
00203
00204 if(alterantive_id == 0 && object_class.length() > 0)
00205 call.request.object_classes.push_back(object_class);
00206 else
00207 call.request.object_ids.push_back(alterantive_id);
00208
00209 call.request.action_type = action_type;
00210
00211 call.request.number_of_objects = num_of_objects;
00212
00213 apriori_position pos;
00214 pos.probability = 1.0;
00215 pos.positionId = position_id;
00216 call.request.list_of_poses.push_back(pos);
00217
00218
00219 if(!m_client.call(call))
00220 {
00221 printf("Error calling cop\n");
00222 return -1;
00223 }
00224 else
00225 printf("Called cop \n");
00226
00227 vision_primitive = call.response.perception_primitive;
00228 return (signed)vision_primitive;
00229 }
00230
00231
00232 long CopClient::CallCop(std::string object_class, std::vector<unsigned long> position_ids, int num_of_objects, unsigned long alterantive_id, unsigned long action_type)
00233 {
00234 cop_call call;
00235 call.request.outputtopic = m_answerTopic;
00236
00237 if(alterantive_id == 0 && object_class.length() > 0)
00238 call.request.object_classes.push_back(object_class);
00239 else
00240 call.request.object_ids.push_back(alterantive_id);
00241
00242 call.request.action_type = action_type;
00243
00244 call.request.number_of_objects = num_of_objects;
00245 for(size_t i = 0 ; i < position_ids.size(); i++)
00246 {
00247 apriori_position pos;
00248 pos.probability = 1.0;
00249 pos.positionId = position_ids[i];
00250 call.request.list_of_poses.push_back(pos);
00251 }
00252
00253
00254 if(!m_client.call(call))
00255 {
00256 printf("Error calling cop\n");
00257 return -1;
00258 }
00259 else
00260 printf("Called cop \n");
00261
00262 vision_primitive = call.response.perception_primitive;
00263 return (signed)vision_primitive;
00264 }
00265
00266
00267
00268 void CopClient::CopFeedBack(long primitive, double evaluation, unsigned long error_id)
00269 {
00270 vision_msgs::cop_feedback msg;
00271 msg.evaluation = evaluation;
00272 msg.perception_primitive = primitive;
00273 if(error_id > 0)
00274 {
00275 vision_msgs::system_error err;
00276 err.error_id = error_id;
00277 msg.error.push_back(err);
00278 }
00279 m_pubFeedBack.publish(msg);
00280
00281 }