Program Listing for File GenericParam.h

Return to documentation for file (src/ompl/base/GenericParam.h)

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2011, Willow Garage
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of the Willow Garage nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 *********************************************************************/

/* Author: Ioan Sucan */

#ifndef OMPL_BASE_GENERIC_PARAM_
#define OMPL_BASE_GENERIC_PARAM_

#include "ompl/util/Console.h"
#include "ompl/util/String.h"
#include "ompl/util/ClassForward.h"
#include <functional>
#include <iostream>
#include <string>
#include <sstream>
#include <utility>
#include <vector>
#include <map>

namespace ompl
{
    namespace base
    {

        OMPL_CLASS_FORWARD(GenericParam);

        class GenericParam
        {
        public:
            GenericParam(std::string name) : name_(std::move(name))
            {
            }

            virtual ~GenericParam() = default;

            const std::string &getName() const
            {
                return name_;
            }

            void setName(const std::string &name)
            {
                name_ = name;
            }

            virtual bool setValue(const std::string &value) = 0;

            virtual std::string getValue() const = 0;

            template <typename T>
            GenericParam &operator=(const T &value)
            {
                setValue(std::to_string(value));
                return *this;
            }

            void setRangeSuggestion(const std::string &rangeSuggestion)
            {
                rangeSuggestion_ = rangeSuggestion;
            }

            const std::string &getRangeSuggestion() const
            {
                return rangeSuggestion_;
            }

        protected:
            std::string name_;

            std::string rangeSuggestion_;
        };

        template <typename T>
        class SpecificParam : public GenericParam
        {
        public:
            using SetterFn = std::function<void(T)>;

            using GetterFn = std::function<T()>;

            SpecificParam(const std::string &name, SetterFn setter, GetterFn getter = GetterFn())
              : GenericParam(name), setter_(std::move(setter)), getter_(std::move(getter))
            {
                if (!setter_ && !getter_)
                    OMPL_ERROR("At least one setter or getter function must be specified for parameter");
            }

            ~SpecificParam() override = default;

            bool setValue(const std::string &value) override
            {
                bool result = true;
                try
                {
                    if (setter_)
                        setter_(lexical_cast(value));
                }
                catch (std::invalid_argument &e)
                {
                    result = false;
                    OMPL_WARN("Invalid value format specified for parameter '%s': %s", name_.c_str(), e.what());
                }

                if (getter_)
                    OMPL_DEBUG("The value of parameter '%s' is now: '%s'", name_.c_str(), getValue().c_str());
                else
                    OMPL_DEBUG("The value of parameter '%s' was set to: '%s'", name_.c_str(), value.c_str());
                return result;
            }

            std::string getValue() const override
            {
                return getter_ ? std::to_string(getter_()) : "";
            }

        protected:
            T lexical_cast(const std::string &value) const;

            SetterFn setter_;

            GetterFn getter_;
        };

        template <>
        inline std::string ompl::base::SpecificParam<float>::getValue() const
        {
            return getter_ ? ompl::toString(getter_()) : "";
        }
        template <>
        inline std::string ompl::base::SpecificParam<double>::getValue() const
        {
            return getter_ ? ompl::toString(getter_()) : "";
        }
        template <>
        inline std::string ompl::base::SpecificParam<long double>::getValue() const
        {
            return getter_ ? ompl::toString(getter_()) : "";
        }
        template <>
        inline std::string ompl::base::SpecificParam<std::string>::getValue() const
        {
            return getter_ ? getter_() : "";
        }


        OMPL_CLASS_FORWARD(ParamSet);

        class ParamSet
        {
        public:
            template <typename T>
            void declareParam(const std::string &name, const typename SpecificParam<T>::SetterFn &setter,
                              const typename SpecificParam<T>::GetterFn &getter = [] { return T(); })
            {
                params_[name] = std::make_shared<SpecificParam<T>>(name, setter, getter);
            }

            void add(const GenericParamPtr &param);

            void remove(const std::string &name);

            void include(const ParamSet &other, const std::string &prefix = "");

            bool setParam(const std::string &key, const std::string &value);

            bool getParam(const std::string &key, std::string &value) const;

            bool setParams(const std::map<std::string, std::string> &kv, bool ignoreUnknown = false);

            void getParams(std::map<std::string, std::string> &params) const;

            void getParamNames(std::vector<std::string> &params) const;

            void getParamValues(std::vector<std::string> &vals) const;

            const std::map<std::string, GenericParamPtr> &getParams() const;

            const GenericParamPtr &getParam(const std::string &key) const;

            bool hasParam(const std::string &key) const;

            GenericParam &operator[](const std::string &key);

            std::size_t size() const
            {
                return params_.size();
            }

            void clear();

            void print(std::ostream &out) const;

        private:
            std::map<std::string, GenericParamPtr> params_;
        };
    }  // namespace base
}  // namespace ompl

#endif