generate_evidence.cpp
Go to the documentation of this file.
1 /*
2  * generate_evidence.cpp
3  *
4  * Created on: Nov 12, 2012
5  * Author: jelfring
6  */
7 
8 #include <ros/ros.h>
9 
10 #include "wire_msgs/WorldEvidence.h"
11 #include "wire_msgs/ObjectEvidence.h"
12 
13 #include "problib/conversions.h"
14 
15 // Publisher used to send evidence to world model
17 
18 
19 void addEvidence(wire_msgs::WorldEvidence& world_evidence, double x, double y, double z, const std::string& class_label, const std::string& color) {
20  wire_msgs::ObjectEvidence obj_evidence;
21 
22  // Set the continuous position property
23  wire_msgs::Property posProp;
24  posProp.attribute = "position";
25 
26  // Set position (x,y,z), set the covariance matrix as 0.005*identity_matrix
27  pbl::PDFtoMsg(pbl::Gaussian(pbl::Vector3(x, y, z), pbl::Matrix3(0.0005, 0.0005, 0.0005)), posProp.pdf);
28  obj_evidence.properties.push_back(posProp);
29 
30  // Set the discrete class label property
31  wire_msgs::Property classProp;
32  classProp.attribute = "class_label";
33  pbl::PMF classPMF;
34 
35  // Probability of the class label is 0.7
36  classPMF.setProbability(class_label, 0.7);
37  pbl::PDFtoMsg(classPMF, classProp.pdf);
38  obj_evidence.properties.push_back(classProp);
39 
40  // Set the discrete color property with a probability of 0.9
41  wire_msgs::Property colorProp;
42  colorProp.attribute = "color";
43  pbl::PMF colorPMF;
44 
45  // The probability of the detected color is 0.9
46  colorPMF.setProbability(color, 0.1);
47  pbl::PDFtoMsg(colorPMF, colorProp.pdf);
48  obj_evidence.properties.push_back(colorProp);
49 
50  // Add all properties to the array
51  world_evidence.object_evidence.push_back(obj_evidence);
52 }
53 
54 
56 
57  // Create world evidence message
58  wire_msgs::WorldEvidence world_evidence;
59 
60  // Set header
61  world_evidence.header.stamp = ros::Time::now();
62  world_evidence.header.frame_id = "/map";
63 
64  // Add evidence
65  addEvidence(world_evidence, 2, 2.2, 3, "mug", "red");
66 
67  // Publish results
68  world_evidence_publisher_.publish(world_evidence);
69  ROS_INFO("Published world evidence with size %d", world_evidence.object_evidence.size());
70 
71 }
72 
76 int main(int argc, char **argv) {
77 
78  // Initialize ros and create node handle
79  ros::init(argc,argv,"generate_evidence");
80  ros::NodeHandle nh;
81 
82  // Publisher
83  world_evidence_publisher_ = nh.advertise<wire_msgs::WorldEvidence>("/world_evidence", 100);
84 
85  // Publish with 3 Hz
86  ros::Rate r(3.0);
87 
88  while (ros::ok()) {
90  r.sleep();
91  }
92 
93  return 0;
94 }
void publish(const boost::shared_ptr< M > &message) const
void generateEvidence()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void addEvidence(wire_msgs::WorldEvidence &world_evidence, double x, double y, double z, const std::string &class_label, const std::string &color)
int main(int argc, char **argv)
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
ros::Publisher world_evidence_publisher_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setProbability(const std::string &value, double p)
static Time now()
void PDFtoMsg(const PDF &pdf, problib::PDF &msg)


wire_tutorials
Author(s): Sjoerd van den Dries, Jos Elfring
autogenerated on Fri Apr 16 2021 02:32:37