Visualizer.cpp
Go to the documentation of this file.
00001 /*
00002  * Visualizer.cpp
00003  *
00004  *  Created on: May 8, 2012
00005  *      Author: sdries
00006  */
00007 
00008 #include "Visualizer.h"
00009 #include "default_values.h"
00010 
00011 using namespace std;
00012 
00013 Visualizer::Visualizer() : tf_listener_(0) {
00014 
00015         color_mapping_["red"] = Color(1,0,0);
00016         color_mapping_["green"] = Color(0,1,0);
00017         color_mapping_["blue"] = Color(0,0,1);
00018         color_mapping_["white"] = Color(1,1,1);
00019         color_mapping_["black"] = Color(0,0,0);
00020         color_mapping_["orange"] = Color(1,0.65,0);
00021         color_mapping_["pink"] = Color(1,0.08,0.58);
00022         color_mapping_["gold"] = Color(1,0.84,0);
00023         color_mapping_["grey"] = Color(0.41,0.41,0.41);
00024         color_mapping_["gray"] = Color(0.41,0.41,0.41);
00025         color_mapping_["cyan"] = Color(0,1,1);
00026         color_mapping_["yellow"] = Color(1,1,0);
00027         color_mapping_["magenta"] = Color(1,0,1);
00028 
00029 }
00030 
00031 Visualizer::~Visualizer() {
00032 
00033 }
00034 
00035 /*
00036  * Function that creates markers
00037  */
00038 bool Visualizer::createMarkers(const std_msgs::Header& header, long ID,
00039                 const vector<wire_msgs::Property>& props,
00040                 vector<visualization_msgs::Marker>& markers_out,
00041                 const std::string& frame_id = "" ) {
00042 
00043         // Pose according to evidence
00044         tf::Stamped<tf::Pose> ev_pose;
00045         ev_pose.setRotation(tf::Quaternion(0, 0, 0, 1));
00046         ev_pose.frame_id_ = header.frame_id;
00047         ev_pose.stamp_ = ros::Time();
00048 
00049         // Store class label and marker text
00050         string marker_text = "", class_label = "", color = "";
00051 
00052         // Variances
00053         double cov_xx = 0;
00054         double cov_yy = 0;
00055         double cov_zz = 0;
00056 
00057         // Iterate over all the propoerties
00058         bool pos_found = false;
00059         for (vector<wire_msgs::Property>::const_iterator it_prop = props.begin(); it_prop != props.end(); ++it_prop) {
00060 
00061                 pbl::PDF* pdf = pbl::msgToPDF(it_prop->pdf);
00062 
00063                 // Position
00064                 if (it_prop->attribute == "position") {
00065                         const pbl::Gaussian* gauss = getBestGaussian(*pdf);
00066                         if (gauss) {
00067                                 const pbl::Vector& mean = gauss->getMean();
00068 
00069                                 cov_xx = gauss->getCovariance()(0, 0);
00070                                 cov_yy = gauss->getCovariance()(1, 1);
00071                                 cov_zz = gauss->getCovariance()(2, 2);
00072 
00073                                 if (gauss->dimensions() == 2) {
00074                                         ev_pose.setOrigin(tf::Point(mean(0), mean(1), 0));
00075                                         pos_found = true;
00076                                 } else if (gauss->dimensions() == 3) {
00077                                         pos_found = true;
00078                                         ev_pose.setOrigin(tf::Point(mean(0), mean(1), mean(2)));
00079                                 } else {
00080                                         ROS_WARN("World evidence: position attribute has %d dimensions, Visualizer cannot deal with this.",
00081                                                         gauss->dimensions());
00082                                 }
00083                         }
00084                 }
00085                 // Orientation
00086                 else if (it_prop->attribute == "orientation") {
00087                         if (pdf->dimensions() == 4) {
00088                                 const pbl::Gaussian* gauss = getBestGaussian(*pdf);
00089                                 if (gauss) {
00090                                         const pbl::Vector& mean = gauss->getMean();
00091                                         ev_pose.setRotation(tf::Quaternion(mean(0), mean(1), mean(2), mean(3)));
00092                                 }
00093                         } else {
00094                                 ROS_WARN("Orientation attribute has %d dimensions, must be 4 (X Y Z W).", pdf->dimensions());
00095                         }
00096                 }
00097                 // Class label
00098                 else if (it_prop->attribute == "class_label") {
00099                         pdf->getExpectedValue(class_label);
00100                 }
00101                 // Color
00102                 else if (it_prop->attribute == "color") {
00103                         pdf->getExpectedValue(color);
00104                 }
00105 
00106                 // Check if the current property represents an attribute that has to be added to the text label
00107                 for (map<string,bool>::const_iterator it = attribute_map_.begin(); it != attribute_map_.end(); ++it) {
00108                         if (it_prop->attribute == it->first && it->second) {
00109                                 string txt = "";
00110                                 // Only consider pmfs otherwise the getExpectedValue function fails
00111                                 if (pdf->type() == pbl::PDF::DISCRETE) {
00112                                         pdf->getExpectedValue(txt);
00113                                         // If marker text not empty add ',' for ease of reading
00114                                         if (marker_text != "") {
00115                                                 txt = ", " + txt;
00116                                         }
00117                                         marker_text += txt;
00118                                 }
00119                         }
00120                 }
00121 
00122 
00123                 delete pdf;
00124 
00125         } // End iterate over properties
00126 
00127         // A position is always needed
00128         if (!pos_found) {
00129                 return false;
00130         }
00131 
00132         // Default marker must be defined
00133         ROS_ASSERT(object_class_to_marker_map_.find("default") != object_class_to_marker_map_.end());
00134 
00135         // Create markers belonging to the objects class
00136         string map_key = "default";
00137         visualization_msgs::Marker marker;
00138         visualization_msgs::Marker text_marker;
00139         if (object_class_to_marker_map_.find(class_label) != object_class_to_marker_map_.end()) {
00140                 map_key = class_label;
00141         }
00142         marker = object_class_to_marker_map_[map_key].shape_marker;
00143         text_marker = object_class_to_marker_map_[map_key].text_marker;
00144 
00145         // If the object has a color, use color of the object as marker color
00146         if (color != "" && color_mapping_.find(color) != color_mapping_.end()) {
00147                 marker.color.r = color_mapping_[color].r;
00148                 marker.color.g = color_mapping_[color].g;
00149                 marker.color.b = color_mapping_[color].b;
00150         }
00151 
00152 
00153         // Transform to frame
00154         tf::Stamped<tf::Pose> ev_pose_TRANSFORMED;
00155         if (frame_id != "" && tf_listener_ != 0) {
00156                 try{
00157                         tf_listener_->transformPose(frame_id, ev_pose, ev_pose_TRANSFORMED);
00158                         marker.header.frame_id = frame_id;
00159                         text_marker.header.frame_id = frame_id;
00160                 } catch (tf::TransformException ex){
00161                         ROS_ERROR("[VISUALIZER] %s",ex.what());
00162                         ev_pose_TRANSFORMED = ev_pose;
00163                         marker.header.frame_id = header.frame_id;
00164                         text_marker.header.frame_id = header.frame_id;
00165                 }
00166         } else {
00167                 ev_pose_TRANSFORMED = ev_pose;
00168                 marker.header.frame_id = header.frame_id;
00169                 text_marker.header.frame_id = header.frame_id;
00170         }
00171 
00172         // Update shape marker position to transformed position and add marker to array
00173         marker.pose.position.x = ev_pose_TRANSFORMED.getOrigin().getX();
00174         marker.pose.position.y = ev_pose_TRANSFORMED.getOrigin().getY();
00175         marker.pose.position.z = ev_pose_TRANSFORMED.getOrigin().getZ();
00176         marker.header.stamp = header.stamp;
00177         marker.id = 3 * ID;
00178         markers_out.push_back(marker);
00179 
00180         // Only if text must be shown
00181         if (object_class_to_marker_map_[map_key].show_text) {
00182                 // Update text marker and add to array
00183                 text_marker.pose.position.x += ev_pose_TRANSFORMED.getOrigin().getX();
00184                 text_marker.pose.position.y += ev_pose_TRANSFORMED.getOrigin().getY();
00185                 text_marker.pose.position.z += ev_pose_TRANSFORMED.getOrigin().getZ();
00186                 text_marker.header.stamp = header.stamp;
00187                 text_marker.id = 3 * ID + 1;
00188 
00189                 // Add ID separately since this not necessarily is an attribute
00190                 if (attribute_map_.find("ID") != attribute_map_.end() && attribute_map_["ID"]) {
00191                         stringstream ss;
00192                         ss << ID;
00193                         string id_text = " (" + ss.str() + ")";
00194                         marker_text += id_text;
00195                 }
00196 
00197                 // Set the text label and add the marker
00198                 text_marker.text = marker_text;
00199                 markers_out.push_back(text_marker);
00200         }
00201 
00202         // Covariance marker
00203         if (object_class_to_marker_map_[map_key].show_cov) {
00204                 visualization_msgs::Marker cov_marker = marker;
00205                 cov_marker.color.a *= 0.5;
00206                 cov_marker.scale.x *= (1 + sqrt(cov_xx) * 3);
00207                 cov_marker.scale.y *= (1 + sqrt(cov_yy) * 3);
00208                 cov_marker.scale.z *= (1 + sqrt(cov_zz) * 3);
00209                 cov_marker.id = 3 * ID + 2;
00210                 markers_out.push_back(cov_marker);
00211         }
00212 
00213         return true;
00214 }
00215 
00216 
00217 /*
00218  * Set the tf listener
00219  */
00220 void Visualizer::setTFListener(tf::TransformListener* tf_listener) {
00221         tf_listener_ = tf_listener;
00222 }
00223 
00224 /*
00225  * Get the most probable Gaussian from a pdf
00226  */
00227 const pbl::Gaussian* Visualizer::getBestGaussian(const pbl::PDF& pdf, double min_weight) {
00228         if (pdf.type() == pbl::PDF::GAUSSIAN) {
00229                 return pbl::PDFtoGaussian(pdf);
00230         } else if (pdf.type() == pbl::PDF::MIXTURE) {
00231                 const pbl::Mixture* mix = pbl::PDFtoMixture(pdf);
00232 
00233                 if (mix){
00234                         const pbl::Gaussian* G_best = 0;
00235                         double w_best = min_weight;
00236                         for(int i = 0; i < mix->components(); ++i) {
00237                                 const pbl::PDF& pdf = mix->getComponent(i);
00238                                 const pbl::Gaussian* G = pbl::PDFtoGaussian(pdf);
00239                                 double w = mix->getWeight(i);
00240                                 if (G && w > w_best) {
00241                                         G_best = G;
00242                                         w_best = w;
00243                                 }
00244                         }
00245                         return G_best;
00246                 }
00247     }
00248 
00249         return 0;
00250 }
00251 
00252 
00253 /*
00254  * Get double
00255  */
00256 void Visualizer::getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, double& d, double default_value) {
00257         XmlRpc::XmlRpcValue& v = s[name];
00258 
00259         if (v.getType() == XmlRpc::XmlRpcValue::TypeDouble) {
00260                 d = (double)v;
00261                 return;
00262         }
00263 
00264         if (v.getType() == XmlRpc::XmlRpcValue::TypeInt) {
00265                 d = (int)v;
00266                 return;
00267         }
00268 
00269         d = default_value;
00270 }
00271 
00272 /*
00273  * Get float
00274  */
00275 void Visualizer::getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, float& f, float default_value) {
00276         double d;
00277         getStructValue(s, name, d, default_value);
00278         f = (float)d;
00279 }
00280 
00281 /*
00282  * Get bool
00283  */
00284 void Visualizer::getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, bool& b, bool default_value) {
00285         XmlRpc::XmlRpcValue& v = s[name];
00286 
00287         if (v.getType() == XmlRpc::XmlRpcValue::TypeBoolean) {
00288                 b = (bool)v;
00289                 return;
00290         }
00291 
00292         b = default_value;
00293 }
00294 
00295 /*
00296  * Get string
00297  */
00298 void Visualizer::getStructValue(XmlRpc::XmlRpcValue& s, const std::string& name, std::string& str, const string& default_value) {
00299         XmlRpc::XmlRpcValue& v = s[name];
00300 
00301         if (v.getType() == XmlRpc::XmlRpcValue::TypeString) {
00302                 str = (string)v;
00303                 return;
00304         }
00305 
00306         str = default_value;
00307 }
00308 
00309 
00310 bool Visualizer::setParameters(ros::NodeHandle& n, const string& ns) {
00311 
00312         bool param = false, att = false;
00313         param = getMarkerParameters(n, ns);
00314         att = getAttributeSettings(n, ns);
00315 
00316         return (param && att);
00317 }
00318 
00319 
00320 
00321 /*
00322  * Get marker parameters from parameter servers
00323  */
00324 bool Visualizer::getMarkerParameters(ros::NodeHandle& n, const string& ns) {
00325 
00326         // Get marker parameters from the parameter server
00327         XmlRpc::XmlRpcValue marker_params;
00328         if (!n.getParam(ns, marker_params)) {
00329                 ROS_ERROR("No global marker parameters given. (namespace: %s)", n.getNamespace().c_str());
00330                 return false;
00331         }
00332 
00333         // Check if the marker parameters are of type array
00334         if (marker_params.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00335                 ROS_ERROR("Malformed marker parameter specification.  (namespace: %s)", n.getNamespace().c_str());
00336                 return false;
00337         }
00338 
00339         // Iterate over the marker parameters in array
00340         for(int i = 0; i < marker_params.size(); ++i) {
00341 
00342                 // Get current value
00343                 XmlRpc::XmlRpcValue& v = marker_params[i];
00344 
00345                 // Check type
00346                 if (v.getType() == XmlRpc::XmlRpcValue::TypeStruct) {
00347 
00348                         // Get class
00349                         string class_name = "";
00350                         getStructValue(v, "class", class_name, "");
00351 
00352                         // If no class defined, no marker can be added
00353                         if (class_name == "") {
00354                                 ROS_WARN("No class defined, skipping parameters");
00355                         }
00356                         // The first class must be default, since the default marker defines values that are not defined
00357                         else if (i==0 && class_name != "default") {
00358                                 ROS_ERROR("Make sure to first specify default in YAML file");
00359                                 return false;
00360                         }
00361                         // Add the default marker
00362                         else if (i==0 && class_name == "default") {
00363 
00364                                 // Get al properties
00365                                 MarkerInfo& m = object_class_to_marker_map_[class_name];
00366                                 m.shape_marker.action = visualization_msgs::Marker::ADD;
00367                                 m.shape_marker.ns = ns;
00368                                 getStructValue(v, "show_text", m.show_text, visualize::DEFAULT_SHOW_TEXT);
00369                                 getStructValue(v, "show_cov", m.show_cov, visualize::DEFAULT_SHOW_COV);
00370                                 getStructValue(v, "r", m.shape_marker.color.r, visualize::DEFAULT_COLOR_R);
00371                                 getStructValue(v, "g", m.shape_marker.color.g, visualize::DEFAULT_COLOR_G);
00372                                 getStructValue(v, "b", m.shape_marker.color.b, visualize::DEFAULT_COLOR_B);
00373                                 getStructValue(v, "alpha", m.shape_marker.color.a, visualize::DEFAULT_COLOR_ALPHA);
00374                                 getStructValue(v, "scale_x", m.shape_marker.scale.x, visualize::DEFAULT_SCALE_X);
00375                                 getStructValue(v, "scale_y", m.shape_marker.scale.y, visualize::DEFAULT_SCALE_Y);
00376                                 getStructValue(v, "scale_z", m.shape_marker.scale.z, visualize::DEFAULT_SCALE_Z);
00377                                 getStructValue(v, "offset_x_pos", m.shape_marker.pose.position.x, visualize::DEFAULT_OFFSET_X_POS);
00378                                 getStructValue(v, "offset_y_pos", m.shape_marker.pose.position.y, visualize::DEFAULT_OFFSET_Y_POS);
00379                                 getStructValue(v, "offset_z_pos", m.shape_marker.pose.position.z, visualize::DEFAULT_OFFSET_Z_POS);
00380                                 getStructValue(v, "offset_x_rot", m.shape_marker.pose.orientation.x, visualize::DEFAULT_OFFSET_X_ROT);
00381                                 getStructValue(v, "offset_y_rot", m.shape_marker.pose.orientation.y, visualize::DEFAULT_OFFSET_Y_ROT);
00382                                 getStructValue(v, "offset_z_rot", m.shape_marker.pose.orientation.z, visualize::DEFAULT_OFFSET_Z_ROT);
00383                                 getStructValue(v, "offset_w_rot", m.shape_marker.pose.orientation.w, visualize::DEFAULT_OFFSET_W_ROT);
00384                                 getStructValue(v, "mesh_resource", m.shape_marker.mesh_resource, "");
00385                                 double duration = 0;
00386                                 getStructValue(v, "duration", duration, visualize::DEFAULT_MARKER_LIFETIME);
00387                                 m.shape_marker.lifetime = ros::Duration(duration);
00388                                 m.text_marker.lifetime = ros::Duration(duration);
00389 
00390                                 // Set geomatric shape
00391                                 setMarkerType(v, m);
00392 
00393                                 ROS_DEBUG("Added marker with class default to %s", ns.c_str());
00394                         }
00395                         // Add marker of any class
00396                         else {
00397 
00398                                 // Add class to the map if not defined use default values
00399                                 MarkerInfo& m = object_class_to_marker_map_[class_name];
00400                                 m.shape_marker.action = visualization_msgs::Marker::ADD;
00401                                 m.shape_marker.ns = ns;
00402                                 getStructValue(v, "show_text", m.show_text, object_class_to_marker_map_["default"].show_text);
00403                                 getStructValue(v, "show_cov", m.show_cov, object_class_to_marker_map_["default"].show_cov);
00404                                 getStructValue(v, "r", m.shape_marker.color.r, object_class_to_marker_map_["default"].shape_marker.color.r);
00405                                 getStructValue(v, "g", m.shape_marker.color.g, object_class_to_marker_map_["default"].shape_marker.color.g);
00406                                 getStructValue(v, "b", m.shape_marker.color.b, object_class_to_marker_map_["default"].shape_marker.color.b);
00407                                 getStructValue(v, "alpha", m.shape_marker.color.a, object_class_to_marker_map_["default"].shape_marker.color.a);
00408                                 getStructValue(v, "scale_x", m.shape_marker.scale.x, object_class_to_marker_map_["default"].shape_marker.scale.x);
00409                                 getStructValue(v, "scale_y", m.shape_marker.scale.y, object_class_to_marker_map_["default"].shape_marker.scale.y);
00410                                 getStructValue(v, "scale_z", m.shape_marker.scale.z, object_class_to_marker_map_["default"].shape_marker.scale.z);
00411                                 getStructValue(v, "offset_x_pos", m.shape_marker.pose.position.x, object_class_to_marker_map_["default"].shape_marker.pose.position.x);
00412                                 getStructValue(v, "offset_y_pos", m.shape_marker.pose.position.y, object_class_to_marker_map_["default"].shape_marker.pose.position.y);
00413                                 getStructValue(v, "offset_z_pos", m.shape_marker.pose.position.z, object_class_to_marker_map_["default"].shape_marker.pose.position.z);
00414                                 getStructValue(v, "offset_x_rot", m.shape_marker.pose.orientation.x, object_class_to_marker_map_["default"].shape_marker.pose.orientation.x);
00415                                 getStructValue(v, "offset_y_rot", m.shape_marker.pose.orientation.y, object_class_to_marker_map_["default"].shape_marker.pose.orientation.y);
00416                                 getStructValue(v, "offset_z_rot", m.shape_marker.pose.orientation.z, object_class_to_marker_map_["default"].shape_marker.pose.orientation.z);
00417                                 getStructValue(v, "offset_w_rot", m.shape_marker.pose.orientation.w, object_class_to_marker_map_["default"].shape_marker.pose.orientation.w);
00418                                 double duration = object_class_to_marker_map_["default"].shape_marker.lifetime.toSec();
00419                                 getStructValue(v, "duration", duration, duration);
00420                                 m.shape_marker.lifetime = ros::Duration(duration);
00421                                 m.text_marker.lifetime = ros::Duration(duration);
00422 
00423                                 // Set appropriate marker geometry
00424                                 setMarkerType(v, m);
00425 
00426                                 ROS_DEBUG("Added marker with class %s to %s", class_name.c_str(), ns.c_str());
00427 
00428                         }
00429                 } else {
00430                         ROS_WARN("Parameter specification not a list (parameter ignored)!");
00431                 }
00432         }
00433 
00434         // Check if text marker is defined
00435         if (object_class_to_marker_map_.find("text") ==  object_class_to_marker_map_.end()) {
00436                 ROS_ERROR("Marker with class text must be defined!");
00437                 return false;
00438         }
00439 
00440         // Set text markers for all classes with text marker properties
00441         visualization_msgs::Marker default_text_marker = object_class_to_marker_map_["text"].shape_marker;
00442         for(map<string, MarkerInfo>::iterator it = object_class_to_marker_map_.begin(); it != object_class_to_marker_map_.end(); ++it) {
00443                 it->second.text_marker = default_text_marker;
00444                 it->second.text_marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00445         }
00446 
00447         return true;
00448 }
00449 
00450 
00451 /*
00452  * Set appropriate marker type
00453  */
00454 void Visualizer::setMarkerType(XmlRpc::XmlRpcValue& v, MarkerInfo& m) {
00455 
00456         // Check if a mesh is defined
00457         if (m.shape_marker.mesh_resource != "") {
00458                 m.shape_marker.type = visualization_msgs::Marker::MESH_RESOURCE;
00459                 ROS_INFO("mesh_resource = %s", m.shape_marker.mesh_resource.c_str());
00460         }
00461         // If no mesh defined, get geometry type or use default
00462         else {
00463 
00464                 // Get marker type from parameter server
00465                 string marker_type;
00466                 getStructValue(v, "type", marker_type, visualize::DEFAULT_TYPE);
00467 
00468                 // Convert type to lower case only
00469                 std::transform(marker_type.begin(), marker_type.end(), marker_type.begin(), ::tolower);
00470 
00471                 // Set appropriate type
00472                 if (marker_type == "cube") {
00473                         m.shape_marker.type = visualization_msgs::Marker::CUBE;
00474                 } else if (marker_type == "cylinder") {
00475                         m.shape_marker.type = visualization_msgs::Marker::CYLINDER;
00476                 } else if (marker_type == "arrow") {
00477                         m.shape_marker.type = visualization_msgs::Marker::ARROW;
00478                 } else if (marker_type == "sphere") {
00479                         m.shape_marker.type = visualization_msgs::Marker::SPHERE;
00480                 } else {
00481                         ROS_WARN("Defined marker type %s, which is unknown. Using sphere instead.", marker_type.c_str());
00482                         m.shape_marker.type = visualization_msgs::Marker::SPHERE;
00483                 }
00484         }
00485 
00486 }
00487 
00488 
00489 
00490 
00491 /*
00492  * Get attribute settings (which attributes should be present in the text labels)
00493  */
00494 bool Visualizer::getAttributeSettings(ros::NodeHandle& n, const string& ns) {
00495 
00496         string param_name = ns + "_attributes";
00497 
00498         // Get marker parameters from the parameter server
00499         XmlRpc::XmlRpcValue attribute_params;
00500         if (!n.getParam(param_name, attribute_params)) {
00501                 ROS_ERROR("No global \"%s\" parameters given. (namespace: %s)", param_name.c_str(), n.getNamespace().c_str());
00502                 return false;
00503         }
00504 
00505         // Check if the marker parameters are of type array
00506         if (attribute_params.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00507                 ROS_ERROR("Malformed \"attributes\" parameter specification.  (namespace: %s)", n.getNamespace().c_str());
00508                 return false;
00509         }
00510 
00511         // Iterate over the marker parameters in array
00512         for(int i = 0; i < attribute_params.size(); ++i) {
00513 
00514                 // Get the list
00515                 XmlRpc::XmlRpcValue& v = attribute_params[i];
00516 
00517                 // Iterate over the list
00518                 ROS_DEBUG("Attributes for %s:", ns.c_str());
00519                 for (XmlRpc::XmlRpcValue::iterator it = v.begin(); it != v.end(); ++it) {
00520                         string att_name = static_cast<string>(it->first);
00521                         bool att_bool = static_cast<int>(it->second);
00522                         attribute_map_[att_name] = att_bool;
00523                         ROS_DEBUG(" %s will %s shown", att_name.c_str(), att_bool?"be":"not be");
00524                 }
00525 
00526         }
00527 
00528         return true;
00529 }


wire_viz
Author(s): Jos Elfring, Sjoerd van den Dries
autogenerated on Tue Jan 7 2014 11:43:08