Program Listing for File ControlSpace.h
↰ Return to documentation for file (src/ompl/control/ControlSpace.h
)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, Rice University
* 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 Rice University 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_CONTROL_CONTROL_SPACE_
#define OMPL_CONTROL_CONTROL_SPACE_
#include "ompl/base/StateSpace.h"
#include "ompl/control/Control.h"
#include "ompl/control/ControlSampler.h"
#include "ompl/control/ControlSpaceTypes.h"
#include "ompl/util/Console.h"
#include "ompl/util/ClassForward.h"
#include <boost/concept_check.hpp>
#include <iostream>
#include <vector>
namespace ompl
{
namespace control
{
OMPL_CLASS_FORWARD(ControlSpace);
class ControlSpace
{
public:
using ControlType = ompl::control::Control;
// non-copyable
ControlSpace(const ControlSpace &) = delete;
ControlSpace &operator=(const ControlSpace &) = delete;
ControlSpace(base::StateSpacePtr stateSpace);
virtual ~ControlSpace();
template <class T>
T *as()
{
BOOST_CONCEPT_ASSERT((boost::Convertible<T *, ControlSpace *>));
return static_cast<T *>(this);
}
template <class T>
const T *as() const
{
BOOST_CONCEPT_ASSERT((boost::Convertible<T *, ControlSpace *>));
return static_cast<const T *>(this);
}
const std::string &getName() const;
void setName(const std::string &name);
int getType() const
{
return type_;
}
const base::StateSpacePtr &getStateSpace() const
{
return stateSpace_;
}
virtual unsigned int getDimension() const = 0;
virtual Control *allocControl() const = 0;
virtual void freeControl(Control *control) const = 0;
virtual void copyControl(Control *destination, const Control *source) const = 0;
virtual bool equalControls(const Control *control1, const Control *control2) const = 0;
virtual void nullControl(Control *control) const = 0;
virtual ControlSamplerPtr allocDefaultControlSampler() const = 0;
virtual ControlSamplerPtr allocControlSampler() const;
void setControlSamplerAllocator(const ControlSamplerAllocator &csa);
void clearControlSamplerAllocator();
virtual double *getValueAddressAtIndex(Control *control, unsigned int index) const;
virtual void printControl(const Control *control, std::ostream &out) const;
virtual void printSettings(std::ostream &out) const;
virtual void setup();
virtual unsigned int getSerializationLength() const;
virtual void serialize(void *serialization, const Control *ctrl) const;
virtual void deserialize(Control *ctrl, const void *serialization) const;
void computeSignature(std::vector<int> &signature) const;
virtual bool isCompound() const;
protected:
int type_;
base::StateSpacePtr stateSpace_;
ControlSamplerAllocator csa_;
private:
std::string name_;
};
class CompoundControlSpace : public ControlSpace
{
public:
using ControlType = ompl::control::CompoundControl;
CompoundControlSpace(const base::StateSpacePtr &stateSpace)
: ControlSpace(stateSpace), componentCount_(0), locked_(false)
{
}
~CompoundControlSpace() override = default;
template <class T>
T *as(const unsigned int index) const
{
BOOST_CONCEPT_ASSERT((boost::Convertible<T *, ControlSpace *>));
return static_cast<T *>(getSubspace(index).get());
}
virtual void addSubspace(const ControlSpacePtr &component);
unsigned int getSubspaceCount() const;
const ControlSpacePtr &getSubspace(unsigned int index) const;
const ControlSpacePtr &getSubspace(const std::string &name) const;
unsigned int getDimension() const override;
Control *allocControl() const override;
void freeControl(Control *control) const override;
void copyControl(Control *destination, const Control *source) const override;
bool equalControls(const Control *control1, const Control *control2) const override;
void nullControl(Control *control) const override;
ControlSamplerPtr allocDefaultControlSampler() const override;
double *getValueAddressAtIndex(Control *control, unsigned int index) const override;
void printControl(const Control *control, std::ostream &out = std::cout) const override;
void printSettings(std::ostream &out) const override;
void setup() override;
unsigned int getSerializationLength() const override;
void serialize(void *serialization, const Control *ctrl) const override;
void deserialize(Control *ctrl, const void *serialization) const override;
bool isCompound() const override;
void lock();
protected:
std::vector<ControlSpacePtr> components_;
unsigned int componentCount_;
bool locked_;
};
}
}
#endif