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 #include "parameters.h"
00030 #include <set>
00031
00032 #include <ros/node_handle.h>
00033 #include <ros/console.h>
00034
00035 #include <hector_nav_msgs/GetDistanceToObstacle.h>
00036
00037 namespace hector_object_tracker {
00038
00039 std::map<std::string, bool> _project_objects;
00040 std::map<std::string, double> _default_distance;
00041 std::map<std::string, double> _distance_variance;
00042 std::map<std::string, double> _angle_variance;
00043 std::map<std::string, double> _min_height;
00044 std::map<std::string, double> _max_height;
00045 std::map<std::string, double> _pending_support;
00046 std::map<std::string, double> _pending_time;
00047 std::map<std::string, double> _active_support;
00048 std::map<std::string, double> _active_time;
00049 std::map<std::string, double> _inactive_support;
00050 std::map<std::string, double> _inactive_time;
00051 std::map<std::string, std_msgs::ColorRGBA> _marker_color;
00052 std::map<std::string, ros::ServiceClient> _distance_to_obstacle_service;
00053
00054 namespace Parameters {
00055
00056 void load(const std::string &class_id )
00057 {
00058 static std::set<std::string> _per_class_parameters_loaded;
00059
00060 if (_per_class_parameters_loaded.count(class_id)) return;
00061 ros::NodeHandle priv_nh("~");
00062
00063 std::string prefix = class_id + "/";
00064 if (prefix == "/") prefix.clear();
00065
00066 if (priv_nh.hasParam(prefix + "project_objects"))
00067 priv_nh.getParam(prefix + "project_objects", _project_objects[class_id]);
00068 if (priv_nh.hasParam(prefix + "default_distance"))
00069 priv_nh.getParam(prefix + "default_distance", _default_distance[class_id]);
00070 if (priv_nh.hasParam(prefix + "distance_variance"))
00071 priv_nh.getParam(prefix + "distance_variance", _distance_variance[class_id]);
00072 if (priv_nh.hasParam(prefix + "angle_variance"))
00073 priv_nh.getParam(prefix + "angle_variance", _angle_variance[class_id]);
00074 if (priv_nh.hasParam(prefix + "min_height"))
00075 priv_nh.getParam(prefix + "min_height", _min_height[class_id]);
00076 if (priv_nh.hasParam(prefix + "max_height"))
00077 priv_nh.getParam(prefix + "max_height", _max_height[class_id]);
00078 if (priv_nh.hasParam(prefix + "pending_support"))
00079 priv_nh.getParam(prefix + "pending_support", _pending_support[class_id]);
00080 if (priv_nh.hasParam(prefix + "pending_time"))
00081 priv_nh.getParam(prefix + "pending_time", _pending_time[class_id]);
00082 if (priv_nh.hasParam(prefix + "active_support"))
00083 priv_nh.getParam(prefix + "active_support", _active_support[class_id]);
00084 if (priv_nh.hasParam(prefix + "active_time"))
00085 priv_nh.getParam(prefix + "active_time", _active_time[class_id]);
00086 if (priv_nh.hasParam(prefix + "inactive_support"))
00087 priv_nh.getParam(prefix + "inactive_support", _inactive_support[class_id]);
00088 if (priv_nh.hasParam(prefix + "inactive_time"))
00089 priv_nh.getParam(prefix + "inactive_time", _inactive_time[class_id]);
00090
00091 if (priv_nh.hasParam(prefix + "marker_color")) {
00092 XmlRpc::XmlRpcValue color;
00093 priv_nh.getParam(prefix + "marker_color", color);
00094 if (color.getType() == XmlRpc::XmlRpcValue::TypeArray && color.size() >= 3) {
00095 _marker_color[class_id].r = (double) color[0];
00096 _marker_color[class_id].g = (double) color[1];
00097 _marker_color[class_id].b = (double) color[2];
00098 if (color.size() > 3)
00099 _marker_color[class_id].a = (double) color[3];
00100 else
00101 _marker_color[class_id].a = 1.0;
00102 } else {
00103 ROS_ERROR_STREAM("Illegal value for param marker_color: " << color << ". Must be an array of size 3 or 4.");
00104 }
00105 }
00106
00107 std::string distance_to_obstacle_service;
00108 if (priv_nh.hasParam(prefix + "distance_to_obstacle_service")) {
00109 priv_nh.getParam(prefix + "distance_to_obstacle_service", distance_to_obstacle_service);
00110 } else if (class_id.empty()) {
00111 distance_to_obstacle_service = "get_distance_to_obstacle";
00112 }
00113
00114 if (!distance_to_obstacle_service.empty()) {
00115 _distance_to_obstacle_service[class_id] = ros::NodeHandle().serviceClient<hector_nav_msgs::GetDistanceToObstacle>(distance_to_obstacle_service);
00116 bool project_objects = _project_objects.count(class_id) ? _project_objects.at(class_id) : _project_objects.at(std::string());
00117 if (project_objects && !_distance_to_obstacle_service[class_id].waitForExistence(ros::Duration(5.0))) {
00118 ROS_WARN_STREAM("project_objects is true, but GetDistanceToObstacle service is not (yet) available" << (!class_id.empty() ? "for class " + class_id : ""));
00119 }
00120 }
00121
00122 _per_class_parameters_loaded.insert(class_id);
00123 }
00124
00125 }
00126 }