Program Listing for File ProlateHyperspheroid.h

Return to documentation for file (src/ompl/util/ProlateHyperspheroid.h)

/*********************************************************************
* Software License Agreement (BSD License)
*
*  Copyright (c) 2014, University of Toronto
*  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 University of Toronto 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: Jonathan Gammell */

#ifndef OMPL_UTIL_PROLATE_HYPERSPHEROID_
#define OMPL_UTIL_PROLATE_HYPERSPHEROID_

#include <memory>

// For ease-of-use shared_ptr definition
#include <ompl/util/ClassForward.h>

namespace ompl
{
    // A forward declaration of the prolate hyperspheroid class
    OMPL_CLASS_FORWARD(ProlateHyperspheroid);

    class ProlateHyperspheroid
    {
    public:
        ProlateHyperspheroid(unsigned int n, const double focus1[], const double focus2[]);

        void setTransverseDiameter(double transverseDiameter);

        void transform(const double sphere[], double phs[]) const;

        bool isInPhs(const double point[]) const;

        bool isOnPhs(const double point[]) const;

        unsigned int getPhsDimension() const;

        double getPhsMeasure() const;

        double getPhsMeasure(double tranDiam) const;

        double getMinTransverseDiameter() const;

        double getPathLength(const double point[]) const;

        unsigned int getDimension() const;

    protected:
    private:
        struct PhsData;

        std::shared_ptr<PhsData> dataPtr_;

        // Functions
        void updateRotation();

        void updateTransformation();
    };
}

#endif