bool VectorVisualization::readParameters() { std::string typePrefix; nodeHandle_.param("vector/type_prefix", typePrefix, std::string("")); if (typePrefix.empty()) return true; types_.push_back(typePrefix + "_x"); types_.push_back(typePrefix + "_y"); types_.push_back(typePrefix + "_z"); nodeHandle_.param("vector/position_type", positionType_, std::string("")); nodeHandle_.param("vector/scale", scale_, 0.02); nodeHandle_.param("vector/line_width", lineWidth_, 0.001); int colorValue; nodeHandle_.param("vector/color", colorValue, 65280); // green setColorFromColorValue(color_, colorValue, true); return true; }
bool VectorVisualization::readParameters(XmlRpc::XmlRpcValue& config) { VisualizationBase::readParameters(config); std::string typePrefix; if (!getParam("layer_prefix", typePrefix)) { ROS_ERROR("VectorVisualization with name '%s' did not find a 'layer_prefix' parameter.", name_.c_str()); return false; } types_.push_back(typePrefix + "x"); types_.push_back(typePrefix + "y"); types_.push_back(typePrefix + "z"); if (!getParam("position_layer", positionLayer_)) { ROS_ERROR("VectorVisualization with name '%s' did not find a 'position_layer' parameter.", name_.c_str()); return false; } scale_ = 1.0; if (!getParam("scale", scale_)) { ROS_INFO("VectorVisualization with name '%s' did not find a 'scale' parameter. Using default.", name_.c_str()); } lineWidth_ = 0.003; if (!getParam("line_width", lineWidth_)) { ROS_INFO("VectorVisualization with name '%s' did not find a 'line_width' parameter. Using default.", name_.c_str()); } int colorValue = 65280; // green if (!getParam("color", colorValue)) { ROS_INFO("VectorVisualization with name '%s' did not find a 'color' parameter. Using default.", name_.c_str()); } setColorFromColorValue(color_, colorValue, true); return true; }