StateSpace.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #ifndef OMPL_BASE_STATE_SPACE_
38 #define OMPL_BASE_STATE_SPACE_
39 
40 #include "ompl/base/State.h"
41 #include "ompl/base/StateSpaceTypes.h"
42 #include "ompl/base/StateSampler.h"
43 #include "ompl/base/ProjectionEvaluator.h"
44 #include "ompl/base/GenericParam.h"
45 #include "ompl/util/Console.h"
46 #include "ompl/util/ClassForward.h"
47 #include <boost/concept_check.hpp>
48 #include <boost/noncopyable.hpp>
49 #include <iostream>
50 #include <vector>
51 #include <string>
52 #include <map>
53 
54 namespace ompl
55 {
56  namespace base
57  {
58 
60 
61  OMPL_CLASS_FORWARD(StateSpace);
63 
73  class StateSpace : private boost::noncopyable
74  {
75  public:
76 
78  typedef State StateType;
79 
81  StateSpace();
82 
83  virtual ~StateSpace();
84 
86  template<class T>
87  T* as()
88  {
90  BOOST_CONCEPT_ASSERT((boost::Convertible<T*, StateSpace*>));
91 
92  return static_cast<T*>(this);
93  }
94 
96  template<class T>
97  const T* as() const
98  {
100  BOOST_CONCEPT_ASSERT((boost::Convertible<T*, StateSpace*>));
101 
102  return static_cast<const T*>(this);
103  }
104 
107  {
113  std::vector<std::size_t> chain;
114 
117  };
118 
121  {
124 
126  std::size_t index;
127  };
128 
132  {
133 
136 
139 
142 
145 
148 
151 
154 
157  };
158 
163  virtual bool isCompound() const;
164 
171  virtual bool isDiscrete() const;
172 
174  virtual bool isHybrid() const;
175 
178  virtual bool isMetricSpace() const
179  {
180  return true;
181  }
182 
184  virtual bool hasSymmetricDistance() const;
185 
187  virtual bool hasSymmetricInterpolate() const;
188 
190  const std::string& getName() const;
191 
193  void setName(const std::string &name);
194 
198  int getType() const
199  {
200  return type_;
201  }
202 
204  bool includes(const StateSpacePtr &other) const;
205 
207  bool includes(const StateSpace *other) const;
208 
211  bool covers(const StateSpacePtr &other) const;
212 
215  bool covers(const StateSpace *other) const;
216 
219  {
220  return params_;
221  }
222 
224  const ParamSet& params() const
225  {
226  return params_;
227  }
228 
234  virtual double getLongestValidSegmentFraction() const;
235 
246  virtual void setLongestValidSegmentFraction(double segmentFraction);
247 
249  virtual unsigned int validSegmentCount(const State *state1, const State *state2) const;
250 
257  void setValidSegmentCountFactor(unsigned int factor);
258 
260  unsigned int getValidSegmentCountFactor() const;
261 
263  double getLongestValidSegmentLength() const;
264 
267  void computeSignature(std::vector<int> &signature) const;
268 
275  virtual unsigned int getDimension() const = 0;
276 
283  virtual double getMaximumExtent() const = 0;
284 
286  virtual double getMeasure() const = 0;
287 
290  virtual void enforceBounds(State *state) const = 0;
291 
294  virtual bool satisfiesBounds(const State *state) const = 0;
295 
298  virtual void copyState(State *destination, const State *source) const = 0;
299 
302  virtual double distance(const State *state1, const State *state2) const = 0;
303 
305  virtual unsigned int getSerializationLength() const;
306 
308  virtual void serialize(void *serialization, const State *state) const;
309 
311  virtual void deserialize(State *state, const void *serialization) const;
312 
314  virtual bool equalStates(const State *state1, const State *state2) const = 0;
315 
319  virtual void interpolate(const State *from, const State *to, const double t, State *state) const = 0;
320 
322  virtual StateSamplerPtr allocDefaultStateSampler() const = 0;
323 
327  virtual StateSamplerPtr allocStateSampler() const;
328 
331 
334 
336  virtual State* allocState() const = 0;
337 
339  virtual void freeState(State *state) const = 0;
340 
358  virtual double* getValueAddressAtIndex(State *state, const unsigned int index) const;
359 
361  const double* getValueAddressAtIndex(const State *state, const unsigned int index) const;
362 
365  const std::vector<ValueLocation>& getValueLocations() const;
366 
369  const std::map<std::string, ValueLocation>& getValueLocationsByName() const;
370 
372  double* getValueAddressAtLocation(State *state, const ValueLocation &loc) const;
373 
375  const double* getValueAddressAtLocation(const State *state, const ValueLocation &loc) const;
376 
378  double* getValueAddressAtName(State *state, const std::string &name) const;
379 
381  const double* getValueAddressAtName(const State *state, const std::string &name) const;
382 
384  void copyToReals(std::vector<double> &reals, const State *source) const;
385 
387  void copyFromReals(State *destination, const std::vector<double> &reals) const;
388 
395  void registerProjection(const std::string &name, const ProjectionEvaluatorPtr &projection);
396 
398  void registerDefaultProjection(const ProjectionEvaluatorPtr &projection);
399 
402  virtual void registerProjections();
403 
405  ProjectionEvaluatorPtr getProjection(const std::string &name) const;
406 
409 
411  bool hasProjection(const std::string &name) const;
412 
414  bool hasDefaultProjection() const;
415 
417  const std::map<std::string, ProjectionEvaluatorPtr>& getRegisteredProjections() const;
418 
425  virtual void printState(const State *state, std::ostream &out) const;
426 
428  virtual void printSettings(std::ostream &out) const;
429 
431  virtual void printProjections(std::ostream &out) const;
432 
435  virtual void sanityChecks(double zero, double eps, unsigned int flags) const;
436 
439  virtual void sanityChecks() const;
440 
442  void diagram(std::ostream &out) const;
443 
445  void list(std::ostream &out) const;
446 
448  static void Diagram(std::ostream &out);
449 
451  static void List(std::ostream &out);
452 
460 
462  virtual StateSamplerPtr allocSubspaceStateSampler(const StateSpace *subspace) const;
463 
465  State* getSubstateAtLocation(State *state, const SubstateLocation &loc) const;
466 
468  const State* getSubstateAtLocation(const State *state, const SubstateLocation &loc) const;
469 
471  const std::map<std::string, SubstateLocation>& getSubstateLocationsByName() const;
472 
475  void getCommonSubspaces(const StateSpacePtr &other, std::vector<std::string> &subspaces) const;
476 
479  void getCommonSubspaces(const StateSpace *other, std::vector<std::string> &subspaces) const;
480 
483  virtual void computeLocations();
484 
495  virtual void setup();
496 
497  protected:
498 
500  static const std::string DEFAULT_PROJECTION_NAME;
501 
503  int type_;
504 
507 
509  double maxExtent_;
510 
513 
516 
519 
521  std::map<std::string, ProjectionEvaluatorPtr> projections_;
522 
525 
528  std::vector<ValueLocation> valueLocationsInOrder_;
529 
532  std::map<std::string, ValueLocation> valueLocationsByName_;
533 
535  std::map<std::string, SubstateLocation> substateLocationsByName_;
536 
537  private:
538 
540  std::string name_;
541  };
542 
545  {
546  public:
547 
550 
553 
555  CompoundStateSpace(const std::vector<StateSpacePtr> &components, const std::vector<double> &weights);
556 
557  virtual ~CompoundStateSpace()
558  {
559  }
560 
562  template<class T>
563  T* as(const unsigned int index) const
564  {
566  BOOST_CONCEPT_ASSERT((boost::Convertible<T*, StateSpace*>));
567 
568  return static_cast<T*>(getSubspace(index).get());
569  }
570 
572  template<class T>
573  T* as(const std::string &name) const
574  {
576  BOOST_CONCEPT_ASSERT((boost::Convertible<T*, StateSpace*>));
577 
578  return static_cast<T*>(getSubspace(name).get());
579  }
580 
581  virtual bool isCompound() const;
582 
583  virtual bool isHybrid() const;
584 
590  void addSubspace(const StateSpacePtr &component, double weight);
591 
593  unsigned int getSubspaceCount() const;
594 
596  const StateSpacePtr& getSubspace(const unsigned int index) const;
597 
599  const StateSpacePtr& getSubspace(const std::string& name) const;
600 
602  unsigned int getSubspaceIndex(const std::string& name) const;
603 
605  bool hasSubspace(const std::string &name) const;
606 
608  double getSubspaceWeight(const unsigned int index) const;
609 
611  double getSubspaceWeight(const std::string &name) const;
612 
614  void setSubspaceWeight(const unsigned int index, double weight);
615 
617  void setSubspaceWeight(const std::string &name, double weight);
618 
620  const std::vector<StateSpacePtr>& getSubspaces() const;
621 
623  const std::vector<double>& getSubspaceWeights() const;
624 
628  bool isLocked() const;
629 
635  void lock();
641  virtual StateSamplerPtr allocSubspaceStateSampler(const StateSpace *subspace) const;
642 
648  virtual unsigned int getDimension() const;
649 
650  virtual double getMaximumExtent() const;
651 
652  virtual double getMeasure() const;
653 
654  virtual void enforceBounds(State *state) const;
655 
656  virtual bool satisfiesBounds(const State *state) const;
657 
658  virtual void copyState(State *destination, const State *source) const;
659 
660  virtual unsigned int getSerializationLength() const;
661 
662  virtual void serialize(void *serialization, const State *state) const;
663 
664  virtual void deserialize(State *state, const void *serialization) const;
665 
666  virtual double distance(const State *state1, const State *state2) const;
667 
673  virtual void setLongestValidSegmentFraction(double segmentFraction);
674 
677  virtual unsigned int validSegmentCount(const State *state1, const State *state2) const;
678 
679  virtual bool equalStates(const State *state1, const State *state2) const;
680 
681  virtual void interpolate(const State *from, const State *to, const double t, State *state) const;
682 
684 
685  virtual State* allocState() const;
686 
687  virtual void freeState(State *state) const;
688 
689  virtual double* getValueAddressAtIndex(State *state, const unsigned int index) const;
690 
693  virtual void printState(const State *state, std::ostream &out) const;
694 
695  virtual void printSettings(std::ostream &out) const;
696 
697  virtual void computeLocations();
698 
699  virtual void setup();
700 
701  protected:
702 
704  void allocStateComponents(CompoundState *state) const;
705 
707  std::vector<StateSpacePtr> components_;
708 
710  unsigned int componentCount_;
711 
713  std::vector<double> weights_;
714 
716  double weightSum_;
717 
719  bool locked_;
720 
721  };
722 
736 
744 
747  StateSpacePtr operator-(const StateSpacePtr &a, const std::string &name);
748 
761  {
764 
767 
770  };
771 
779  AdvancedStateCopyOperation copyStateData(const StateSpacePtr &destS, State *dest,
780  const StateSpacePtr &sourceS, const State *source);
781 
789  AdvancedStateCopyOperation copyStateData(const StateSpace *destS, State *dest,
790  const StateSpace *sourceS, const State *source);
791 
797  AdvancedStateCopyOperation copyStateData(const StateSpacePtr &destS, State *dest,
798  const StateSpacePtr &sourceS, const State *source,
799  const std::vector<std::string> &subspaces);
800 
806  AdvancedStateCopyOperation copyStateData(const StateSpace *destS, State *dest,
807  const StateSpace *sourceS, const State *source,
808  const std::vector<std::string> &subspaces);
811  }
812 }
813 
814 #endif
State * getSubstateAtLocation(State *state, const SubstateLocation &loc) const
Get the substate of state that is pointed to by loc.
Definition: StateSpace.cpp:282
void setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:203
virtual void setup()
Perform final setup steps. This function is automatically called by the SpaceInformation. If any default projections are to be registered, this call will set them and call their setup() functions. It is safe to call this function multiple times. At a subsequent call, projections that have been previously user configured are not re-instantiated, but their setup() method is still called.
virtual StateSamplerPtr allocStateSampler() const
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sam...
Definition: StateSpace.cpp:785
boost::function< StateSamplerPtr(const StateSpace *)> StateSamplerAllocator
Definition of a function that can allocate a state sampler.
Definition: StateSampler.h:184
virtual void deserialize(State *state, const void *serialization) const
Read the binary representation of a state from serialization and write it to state.
int type_
A type assigned for this state space.
Definition: StateSpace.h:503
ParamSet params_
The set of parameters for this space.
Definition: StateSpace.h:524
bool hasDefaultProjection() const
Check if a default projection is available.
Definition: StateSpace.cpp:699
virtual unsigned int validSegmentCount(const State *state1, const State *state2) const
Count how many segments of the "longest valid length" fit on the motion from state1 to state2...
Definition: StateSpace.cpp:834
virtual bool hasSymmetricInterpolate() const
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from, to, t, state) = interpolate(to, from, 1-t, state). Default implementation returns true.
Definition: StateSpace.cpp:770
Definition of a compound state.
Definition: State.h:95
virtual void copyState(State *destination, const State *source) const
Copy a state to another. The memory of source and destination should NOT overlap. ...
virtual double * getValueAddressAtIndex(State *state, const unsigned int index) const
Many states contain a number of double values. This function provides a means to get the memory addre...
Definition: StateSpace.cpp:298
virtual bool isHybrid() const
Check if this is a hybrid state space (i.e., both discrete and continuous components exist) ...
Definition: StateSpace.cpp:760
static const std::string DEFAULT_PROJECTION_NAME
The name used for the default projection.
Definition: StateSpace.h:500
std::size_t index
The index of the value to be accessed, within the substate location above.
Definition: StateSpace.h:126
virtual double getLongestValidSegmentFraction() const
When performing discrete validation of motions, the length of the longest segment that does not requi...
Definition: StateSpace.cpp:824
unsigned int getSubspaceIndex(const std::string &name) const
Get the index of a specific subspace from the compound state space.
Definition: StateSpace.cpp:909
virtual bool isCompound() const
Check if the state space is compound.
Definition: StateSpace.cpp:867
virtual unsigned int getSerializationLength() const
Get the number of chars in the serialization of a state in this space.
virtual StateSamplerPtr allocDefaultStateSampler() const
Allocate an instance of the default uniform state sampler for this space.
bool includes(const StateSpacePtr &other) const
Return true if other is a space included (perhaps equal, perhaps a subspace) in this one...
Definition: StateSpace.cpp:466
static void Diagram(std::ostream &out)
Print a Graphviz digraph that represents the containment diagram for all the instantiated state space...
Definition: StateSpace.cpp:568
virtual void printProjections(std::ostream &out) const
Print the list of registered projections. This function is also called by printSettings() ...
Definition: StateSpace.cpp:385
A boost shared pointer wrapper for ompl::base::StateSpace.
const std::vector< ValueLocation > & getValueLocations() const
Get the locations of values of type double contained in a state from this space. The order of the val...
Definition: StateSpace.cpp:309
double getSubspaceWeight(const unsigned int index) const
Get the weight of a subspace from the compound state space (used in distance computation) ...
Definition: StateSpace.cpp:922
A boost shared pointer wrapper for ompl::base::StateSampler.
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
virtual unsigned int getDimension() const =0
Get the dimension of the space (not the dimension of the surrounding ambient space) ...
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:147
bool isLocked() const
Return true if the state space is locked. A value of true means that no further spaces can be added a...
std::vector< std::size_t > chain
In a complex state space there may be multiple compound state spaces that make up an even larger comp...
Definition: StateSpace.h:113
Check whether sampled states are always within bounds.
Definition: StateSpace.h:150
Representation of the address of a value in a state. This structure stores the indexing information n...
Definition: StateSpace.h:120
No data was copied.
Definition: StateSpace.h:763
StateSpace()
Constructor. Assigns a unique name to the space.
Definition: StateSpace.cpp:88
AdvancedStateCopyOperation copyStateData(const StateSpacePtr &destS, State *dest, const StateSpacePtr &sourceS, const State *source)
Copy data from source (state from space sourceS) to dest (state from space destS) on a component by c...
T * as(const unsigned int index) const
Cast a component of this instance to a desired type.
Definition: StateSpace.h:563
CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:549
virtual double getMeasure() const
Get a measure of the space (this can be thought of as a generalization of volume) ...
Definition: StateSpace.cpp:989
virtual bool isMetricSpace() const
Return true if the distance function associated with the space is a metric.
Definition: StateSpace.h:178
virtual StateSamplerPtr allocSubspaceStateSampler(const StateSpace *subspace) const
Allocate a sampler that actually samples only components that are part of subspace.
void diagram(std::ostream &out) const
Print a Graphviz digraph that represents the containment diagram for the state space.
Definition: StateSpace.cpp:541
void registerProjection(const std::string &name, const ProjectionEvaluatorPtr &projection)
Register a projection for this state space under a specified name.
Definition: StateSpace.cpp:742
virtual void computeLocations()
Compute the location information for various components of the state space. Either this function or s...
Definition: StateSpace.cpp:215
void copyFromReals(State *destination, const std::vector< double > &reals) const
Copy the values from reals to the state destination using getValueAddressAtLocation() ...
Definition: StateSpace.cpp:326
void computeSignature(std::vector< int > &signature) const
Compute an array of ints that uniquely identifies the structure of the state space. The first element of the signature is the number of integers that follow.
Definition: StateSpace.cpp:220
virtual void printSettings(std::ostream &out) const
Print the settings for this state space to a stream.
Definition: StateSpace.cpp:379
virtual void registerProjections()
Register the projections for this state space. Usually, this is at least the default projection...
Definition: StateSpace.cpp:227
virtual void setLongestValidSegmentFraction(double segmentFraction)
When performing discrete validation of motions, the length of the longest segment that does not requi...
ParamSet & params()
Get the parameters for this space.
Definition: StateSpace.h:218
void registerDefaultProjection(const ProjectionEvaluatorPtr &projection)
Register the default projection for this state space.
Definition: StateSpace.cpp:737
unsigned int longestValidSegmentCountFactor_
The factor to multiply the value returned by validSegmentCount(). Rarely used but useful for things l...
Definition: StateSpace.h:518
void allocStateComponents(CompoundState *state) const
Allocate the state components. Called by allocState(). Usually called by derived state spaces...
StateSamplerAllocator ssa_
An optional state sampler allocator.
Definition: StateSpace.h:506
virtual double * getValueAddressAtIndex(State *state, const unsigned int index) const
Many states contain a number of double values. This function provides a means to get the memory addre...
unsigned int componentCount_
The number of components.
Definition: StateSpace.h:710
Maintain a set of parameters.
Definition: GenericParam.h:234
const StateSpacePtr & getSubspace(const unsigned int index) const
Get a specific subspace from the compound state space.
Definition: StateSpace.cpp:893
State StateType
Define the type of state allocated by this space.
Definition: StateSpace.h:78
T * as()
Cast this instance to a desired type.
Definition: StateSpace.h:87
All data was copied.
Definition: StateSpace.h:769
virtual void setLongestValidSegmentFraction(double segmentFraction)
When performing discrete validation of motions, the length of the longest segment that does not requi...
Definition: StateSpace.cpp:812
Main namespace. Contains everything in this library.
Definition: Cost.h:42
Check whether the distances between non-equal states is strictly positive (StateSpace::distance()) ...
Definition: StateSpace.h:135
virtual State * allocState() const
Allocate a state that can store a point in the described space.
const std::vector< StateSpacePtr > & getSubspaces() const
Get the list of components.
Definition: StateSpace.cpp:962
virtual void computeLocations()
Compute the location information for various components of the state space. Either this function or s...
virtual void interpolate(const State *from, const State *to, const double t, State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
A space to allow the composition of state spaces.
Definition: StateSpace.h:544
Representation of the address of a substate in a state. This structure stores the indexing informatio...
Definition: StateSpace.h:106
std::vector< double > weights_
The weight assigned to each component of the state space when computing the compound distance...
Definition: StateSpace.h:713
virtual double getMaximumExtent() const
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...
Definition: StateSpace.cpp:980
const std::map< std::string, SubstateLocation > & getSubstateLocationsByName() const
Get the list of known substate locations (keys of the map corrspond to names of subspaces) ...
Definition: StateSpace.cpp:277
void setSubspaceWeight(const unsigned int index, double weight)
Set the weight of a subspace in the compound state space (used in distance computation) ...
Definition: StateSpace.cpp:938
virtual void printState(const State *state, std::ostream &out) const
Print a state to a stream.
A boost shared pointer wrapper for ompl::base::ProjectionEvaluator.
StateSpacePtr operator-(const StateSpacePtr &a, const StateSpacePtr &b)
Construct a compound state space that contains subspaces only from a. If a is compound, b (or the components from b, if b is compound) are removed and the remaining components are returned as a compound state space. If the compound space would end up containing solely one component, that component is returned instead.
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.
Definition: StateSpace.h:73
virtual void setup()
Perform final setup steps. This function is automatically called by the SpaceInformation. If any default projections are to be registered, this call will set them and call their setup() functions. It is safe to call this function multiple times. At a subsequent call, projections that have been previously user configured are not re-instantiated, but their setup() method is still called.
Definition: StateSpace.cpp:231
virtual StateSamplerPtr allocDefaultStateSampler() const =0
Allocate an instance of the default uniform state sampler for this space.
unsigned int getValidSegmentCountFactor() const
Get the value used to multiply the return value of validSegmentCount().
Definition: StateSpace.cpp:819
virtual void printSettings(std::ostream &out) const
Print the settings for this state space to a stream.
virtual void freeState(State *state) const
Free the memory of the allocated state.
Definition of an abstract state.
Definition: State.h:50
virtual bool equalStates(const State *state1, const State *state2) const
Checks whether two states are equal.
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition: StateSpace.h:144
virtual bool satisfiesBounds(const State *state) const =0
Check if a state is inside the bounding box. For unbounded spaces this function can always return tru...
void setValidSegmentCountFactor(unsigned int factor)
Set factor to be the value to multiply the return value of validSegmentCount(). By default...
Definition: StateSpace.cpp:805
virtual bool isDiscrete() const
Check if the set of states is discrete.
Definition: StateSpace.cpp:755
OptimizationObjectivePtr operator+(const OptimizationObjectivePtr &a, const OptimizationObjectivePtr &b)
Given two optimization objectives, returns a MultiOptimizationObjective that combines the two objecti...
virtual double distance(const State *state1, const State *state2) const
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
StateSamplerPtr allocSubspaceStateSampler(const StateSpacePtr &subspace) const
Allocate a sampler that actually samples only components that are part of subspace.
Definition: StateSpace.cpp:793
int getType() const
Get the type of the state space. The type can be used to verify whether two space instances are of th...
Definition: StateSpace.h:198
const ParamSet & params() const
Get the parameters for this space.
Definition: StateSpace.h:224
void setStateSamplerAllocator(const StateSamplerAllocator &ssa)
Set the sampler allocator to use.
Definition: StateSpace.cpp:775
bool covers(const StateSpacePtr &other) const
Return true if other is a space that is either included (perhaps equal, perhaps a subspace) in this o...
Definition: StateSpace.cpp:461
Some data was copied.
Definition: StateSpace.h:766
virtual double getMeasure() const =0
Get a measure of the space (this can be thought of as a generalization of volume) ...
virtual bool hasSymmetricDistance() const
Check if the distance function on this state space is symmetric, i.e. distance(s1,s2) = distance(s2,s1). Default implementation returns true.
Definition: StateSpace.cpp:765
void addSubspace(const StateSpacePtr &component, double weight)
Adds a new state space as part of the compound state space. For computing distances within the compou...
Definition: StateSpace.cpp:855
std::vector< ValueLocation > valueLocationsInOrder_
The value locations for all varliables of type double contained in a state; The locations point to va...
Definition: StateSpace.h:528
double maxExtent_
The extent of this space at the time setup() was called.
Definition: StateSpace.h:509
SanityChecks
Flags to use in a bit mask for state space sanity checks. Some basic checks do not have flags associa...
Definition: StateSpace.h:131
std::map< std::string, ProjectionEvaluatorPtr > projections_
List of available projections.
Definition: StateSpace.h:521
const T * as() const
Cast this instance to a desired type.
Definition: StateSpace.h:97
virtual void enforceBounds(State *state) const =0
Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-...
const std::vector< double > & getSubspaceWeights() const
Get the list of component weights.
Definition: StateSpace.cpp:967
virtual bool isHybrid() const
Check if this is a hybrid state space (i.e., both discrete and continuous components exist) ...
Definition: StateSpace.cpp:872
bool hasSubspace(const std::string &name) const
Check if a specific subspace is contained in this state space.
Definition: StateSpace.cpp:901
void getCommonSubspaces(const StateSpacePtr &other, std::vector< std::string > &subspaces) const
Get the set of subspaces that this space and other have in common. The computed list of subspaces doe...
Definition: StateSpace.cpp:481
double weightSum_
The sum of all the weights in weights_.
Definition: StateSpace.h:716
virtual void deserialize(State *state, const void *serialization) const
Read the binary representation of a state from serialization and write it to state.
Definition: StateSpace.cpp:370
SubstateLocation stateLocation
Location of the substate that contains the pointed to value.
Definition: StateSpace.h:123
virtual unsigned int validSegmentCount(const State *state1, const State *state2) const
Count how many segments of the "longest valid length" fit on the motion from state1 to state2...
Check whether the distance function is symmetric (StateSpace::distance())
Definition: StateSpace.h:138
double longestValidSegmentFraction_
The fraction of the longest valid segment.
Definition: StateSpace.h:512
virtual bool equalStates(const State *state1, const State *state2) const =0
Checks whether two states are equal.
virtual double distance(const State *state1, const State *state2) const =0
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
const std::map< std::string, ProjectionEvaluatorPtr > & getRegisteredProjections() const
Get all the registered projections.
Definition: StateSpace.cpp:732
bool locked_
Flag indicating whether adding further components is allowed or not.
Definition: StateSpace.h:719
bool hasProjection(const std::string &name) const
Check if a projection with a specified name is available.
Definition: StateSpace.cpp:704
static void List(std::ostream &out)
Print the list of available state space instances.
Definition: StateSpace.cpp:515
virtual void serialize(void *serialization, const State *state) const
Write the binary representation of state to serialization.
Definition: StateSpace.cpp:366
std::map< std::string, SubstateLocation > substateLocationsByName_
All the known substat locations, by name.
Definition: StateSpace.h:535
virtual bool isCompound() const
Check if the state space is compound.
Definition: StateSpace.cpp:750
unsigned int getSubspaceCount() const
Get the number of state spaces that make up the compound state space.
Definition: StateSpace.cpp:888
Check whether the StateSpace::serialize() and StateSpace::deserialize() work as expected.
Definition: StateSpace.h:156
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:141
Check that enforceBounds() does not modify the contents of states that are within bounds...
Definition: StateSpace.h:153
double longestValidSegment_
The longest valid segment at the time setup() was called.
Definition: StateSpace.h:515
double getLongestValidSegmentLength() const
Get the longest valid segment at the time setup() was called.
Definition: StateSpace.cpp:829
const std::string & getName() const
Get the name of the state space.
Definition: StateSpace.cpp:198
CompoundStateSpace()
Construct an empty compound state space.
Definition: StateSpace.cpp:839
virtual void interpolate(const State *from, const State *to, const double t, State *state) const =0
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
ProjectionEvaluatorPtr getDefaultProjection() const
Get the default projection.
Definition: StateSpace.cpp:709
virtual void freeState(State *state) const =0
Free the memory of the allocated state.
virtual void enforceBounds(State *state) const
Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-...
Definition: StateSpace.cpp:998
double * getValueAddressAtLocation(State *state, const ValueLocation &loc) const
Get a pointer to the double value in state that loc points to.
Definition: StateSpace.cpp:333
const std::map< std::string, ValueLocation > & getValueLocationsByName() const
Get the named locations of values of type double contained in a state from this space. The setup() function must have been previously called.
Definition: StateSpace.cpp:314
double * getValueAddressAtName(State *state, const std::string &name) const
Get a pointer to the double value in state that name points to.
Definition: StateSpace.cpp:349
virtual void copyState(State *destination, const State *source) const =0
Copy a state to another. The memory of source and destination should NOT overlap. ...
const StateSpace * space
The space that is reached if the chain above is followed on the state space.
Definition: StateSpace.h:116
AdvancedStateCopyOperation
The possible outputs for an advanced copy operation.
Definition: StateSpace.h:760
virtual void serialize(void *serialization, const State *state) const
Write the binary representation of state to serialization.
void copyToReals(std::vector< double > &reals, const State *source) const
Copy all the real values from a state source to the array reals using getValueAddressAtLocation() ...
Definition: StateSpace.cpp:319
virtual State * allocState() const =0
Allocate a state that can store a point in the described space.
ProjectionEvaluatorPtr getProjection(const std::string &name) const
Get the projection registered under a specific name.
Definition: StateSpace.cpp:720
virtual void printState(const State *state, std::ostream &out) const
Print a state to a stream.
Definition: StateSpace.cpp:374
void clearStateSamplerAllocator()
Clear the state sampler allocator (reset to default)
Definition: StateSpace.cpp:780
virtual unsigned int getDimension() const
Get the dimension of the space (not the dimension of the surrounding ambient space) ...
Definition: StateSpace.cpp:972
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: StateSpace.cpp:591
std::map< std::string, ValueLocation > valueLocationsByName_
All the known value locations, by name. The names of state spaces access the first element of a state...
Definition: StateSpace.h:532
std::vector< StateSpacePtr > components_
The state spaces that make up the compound state space.
Definition: StateSpace.h:707
virtual unsigned int getSerializationLength() const
Get the number of chars in the serialization of a state in this space.
Definition: StateSpace.cpp:361
T * as(const std::string &name) const
Cast a component of this instance to a desired type.
Definition: StateSpace.h:573
OptimizationObjectivePtr operator*(double w, const OptimizationObjectivePtr &a)
Given a weighing factor and an optimization objective, returns a MultiOptimizationObjective containin...
virtual bool satisfiesBounds(const State *state) const
Check if a state is inside the bounding box. For unbounded spaces this function can always return tru...
void list(std::ostream &out) const
Print the list of all contained state space instances.
Definition: StateSpace.cpp:523
virtual double getMaximumExtent() const =0
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...