This file is indexed.

/usr/include/ompl/base/ScopedState.h is in libompl-dev 0.13.0+git20130920.01d0ca4-1.

This file is owned by root:root, with mode 0o644.

The actual contents of the file can be viewed below.

  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
/*********************************************************************
* 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_BASE_SCOPED_STATE_
#define OMPL_BASE_SCOPED_STATE_

#include "ompl/base/SpaceInformation.h"
#include <boost/concept_check.hpp>
#include <iostream>

namespace ompl
{
    namespace base
    {

        /** \brief Definition of a scoped state.

            This class allocates a state of a desired type using the
            allocation mechanism of the corresponding state space.
            The state is then freed when the instance goes out of
            scope using the corresponding free mechanism. */
        template<class T = StateSpace>
        class ScopedState
        {
            /** \brief Make sure the type we are allocating is indeed from a state space */
            BOOST_CONCEPT_ASSERT((boost::Convertible<T*, StateSpace*>));

            /** \brief Make sure the type we are allocating is indeed a state */
            BOOST_CONCEPT_ASSERT((boost::Convertible<typename T::StateType*, State*>));

        public:

            /** \brief The type of the contained state */
            typedef typename T::StateType StateType;

            /** \brief Given the space that we are working with,
                allocate a state from the corresponding
                state space.  */
            explicit
            ScopedState(const SpaceInformationPtr &si) : space_(si->getStateSpace())
            {
                State *s = space_->allocState();

                // ideally, this should be a dynamic_cast and we
                // should throw an exception in case of
                // failure. However, RTTI may not be available across
                // shared library boundaries, so we do not use it
                state_ = static_cast<StateType*>(s);
            }

            /** \brief Given the state space that we are working with,
                allocate a state. */
            explicit
            ScopedState(const StateSpacePtr &space) : space_(space)
            {
                State *s = space_->allocState();

                // ideally, this should be a dynamic_cast and we
                // should throw an exception in case of
                // failure. However, RTTI may not be available across
                // shared library boundaries, so we do not use it
                state_ = static_cast<StateType*>(s);
            }

            /** \brief Copy constructor */
            ScopedState(const ScopedState<T> &other) : space_(other.getSpace())
            {
                State *s = space_->allocState();
                state_ = static_cast<StateType*>(s);
                space_->copyState(s, static_cast<const State*>(other.get()));
            }

            /** \brief Copy constructor that allows instantiation from states of other type */
            template<class O>
            ScopedState(const ScopedState<O> &other) : space_(other.getSpace())
            {
                BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>));
                BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>));

                // ideally, we should use a dynamic_cast and throw an
                // exception in case other.get() does not cast to
                // const StateType*. However, RTTI may not be
                // available across shared library boundaries, so we
                // do not use it

                State *s = space_->allocState();
                state_ = static_cast<StateType*>(s);
                space_->copyState(s, static_cast<const State*>(other.get()));
            }

            /** \brief Given the state space that we are working with,
                allocate a state and fill that state with a given value. */
            ScopedState(const StateSpacePtr &space, const State *state) : space_(space)
            {
                State *s = space_->allocState();
                space_->copyState(s, state);

                // ideally, this should be a dynamic_cast and we
                // should throw an exception in case of
                // failure. However, RTTI may not be available across
                // shared library boundaries, so we do not use it
                state_ = static_cast<StateType*>(s);
            }

            /** \brief Free the memory of the internally allocated state */
            ~ScopedState(void)
            {
                space_->freeState(state_);
            }

            /** \brief Get the state space that the state corresponds to */
            const StateSpacePtr& getSpace(void) const
            {
                return space_;
            }

            /** \brief Assignment operator */
            ScopedState<T>& operator=(const ScopedState<T> &other)
            {
                if (&other != this)
                {
                    space_->freeState(state_);
                    space_ = other.getSpace();

                    State *s = space_->allocState();
                    state_ = static_cast<StateType*>(s);
                    space_->copyState(s, static_cast<const State*>(other.get()));
                }
                return *this;
            }

            /** \brief Assignment operator */
            ScopedState<T>& operator=(const State *other)
            {
                if (other != static_cast<State*>(state_))
                {
                    // ideally, we should use a dynamic_cast and throw an
                    // exception in case other does not cast to
                    // const StateType*. However, RTTI may not be
                    // available across shared library boundaries, so we
                    // do not use it

                    space_->copyState(static_cast<State*>(state_), other);
                }
                return *this;
            }

            /** \brief Assignment operator */
            ScopedState<T>& operator=(const State &other)
            {
                if (&other != static_cast<State*>(state_))
                {
                    // ideally, we should use a dynamic_cast and throw an
                    // exception in case &other does not cast to
                    // const StateType*. However, RTTI may not be
                    // available across shared library boundaries, so we
                    // do not use it

                    space_->copyState(static_cast<State*>(state_), &other);
                }
                return *this;
            }

            /** \brief Assignment operator that allows conversion of states */
            template<class O>
            ScopedState<T>& operator=(const ScopedState<O> &other)
            {
                BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>));
                BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>));

                // ideally, we should use a dynamic_cast and throw an
                // exception in case other.get() does not cast to
                // const StateType*. However, RTTI may not be
                // available across shared library boundaries, so we
                // do not use it

                if (reinterpret_cast<const void*>(&other) != reinterpret_cast<const void*>(this))
                {
                    space_->freeState(state_);
                    space_ = other.getSpace();

                    State *s = space_->allocState();
                    state_ = static_cast<StateType*>(s);
                    space_->copyState(s, static_cast<const State*>(other.get()));
                }
                return *this;
            }

            /** \brief Partial assignment operator. Only sets the double values of the state to specified real values */
            ScopedState<T>& operator=(const std::vector<double> &reals)
            {
                for (unsigned int i = 0 ; i < reals.size() ; ++i)
                    if (double *va = space_->getValueAddressAtIndex(state_, i))
                        *va = reals[i];
                    else
                        break;
                return *this;
            }

            /** \brief Partial assignment operator. Only sets the double values of the state to a fixed value */
            ScopedState<T>& operator=(const double value)
            {
                unsigned int index = 0;
                while (double *va = space_->getValueAddressAtIndex(state_, index++))
                    *va = value;
                return *this;
            }

            /** \brief Checks equality of two states */
            template<class O>
            bool operator==(const ScopedState<O> &other) const
            {
                BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>));
                BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>));

                // ideally, we should use a dynamic_cast and throw an
                // exception in case other.get() does not cast to
                // const StateType*. However, RTTI may not be
                // available across shared library boundaries, so we
                // do not use it

                return space_->equalStates(static_cast<const State*>(state_), static_cast<const State*>(other.get()));
            }

            /** \brief Checks equality of two states */
            template<class O>
            bool operator!=(const ScopedState<O> &other) const
            {
                return !(*this == other);
            }

            /** \brief Extract a state that corresponds to the
                components in state space \e s. Those components will
                have the same value as the current state (only the
                ones included in the current state; others will be
                uninitialised). Note: a new state is constructed and data is copied. */
            const ScopedState<> operator[](const StateSpacePtr &s) const;

            /** \brief Access the \e index<sup>th</sup> double value this state contains. */
            double& operator[](const unsigned int index)
            {
                double *val = space_->getValueAddressAtIndex(state_, index);
                if (!val)
                    throw Exception("Index out of bounds");
                return *val;
            }

            /** \brief Access the \e index<sup>th</sup> double value this state contains. */
            double operator[](const unsigned int index) const
            {
                const double *val = space_->getValueAddressAtIndex(state_, index);
                if (!val)
                    throw Exception("Index out of bounds");
                return *val;
            }

            /** \brief Access a double value from this state contains using its name. */
            double& operator[](const std::string &name)
            {
                const std::map<std::string, StateSpace::ValueLocation> &vm = space_->getValueLocationsByName();
                std::map<std::string, StateSpace::ValueLocation>::const_iterator it = vm.find(name);
                if (it != vm.end())
                {
                    double *val = space_->getValueAddressAtLocation(state_, it->second);
                    if (val)
                        return *val;
                }
                throw Exception("Name '" + name + "' not known");
            }

            /** \brief Access a double value from this state contains using its name. */
            double operator[](const std::string &name) const
            {
                const std::map<std::string, StateSpace::ValueLocation> &vm = space_->getValueLocationsByName();
                std::map<std::string, StateSpace::ValueLocation>::const_iterator it = vm.find(name);
                if (it != vm.end())
                {
                    const double *val = space_->getValueAddressAtLocation(state_, it->second);
                    if (val)
                        return *val;
                }
                throw Exception("Name '" + name + "' not known");
            }

            /** \brief Compute the distance to another state. */
            template<class O>
            double distance(const ScopedState<O> &other) const
            {
                BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>));
                BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>));
                return distance(other.get());
            }

            /** \brief Compute the distance to another state. */
            double distance(const State *state) const
            {
                return space_->distance(static_cast<const State*>(state_), state);
            }

            /** \brief Set this state to a random value (uniform) */
            void random(void)
            {
                if (!sampler_)
                    sampler_ = space_->allocStateSampler();
                sampler_->sampleUniform(state_);
            }

            /** \brief Enforce the bounds on the maintained state */
            void enforceBounds(void)
            {
                space_->enforceBounds(state_);
            }

            /** \brief Check if the maintained state satisfies bounds */
            bool satisfiesBounds(void) const
            {
                return space_->satisfiesBounds(state_);
            }

            /** \brief Return the real values corresponding to this
                state. If a conversion is not possible, an exception
                is thrown.*/
            std::vector<double> reals(void) const
            {
                std::vector<double> r;
                unsigned int index = 0;
                while (double *va = space_->getValueAddressAtIndex(state_, index++))
                    r.push_back(*va);
                return r;
            }

            /** \brief Print this state to a stream */
            void print(std::ostream &out = std::cout) const
            {
                space_->printState(state_, out);
            }

            /** \brief De-references to the contained state */
            StateType& operator*(void)
            {
                return *state_;
            }

            /** \brief De-references to the contained state */
            const StateType& operator*(void) const
            {
                return *state_;
            }

            /** \brief Returns a pointer to the contained state */
            StateType* operator->(void)
            {
                return state_;
            }

            /** \brief Returns a pointer to the contained state */
            const StateType* operator->(void) const
            {
                return state_;
            }

            /** \brief Returns a pointer to the contained state */
            StateType* get(void)
            {
                return state_;
            }

            /** \brief Returns a pointer to the contained state */
            const StateType* get(void) const
            {
                return state_;
            }

            /** \brief Returns a pointer to the contained state (used for Python bindings) */
            StateType* operator()(void) const
            {
                return state_;
            }

        private:

            StateSpacePtr                   space_;
            StateSamplerPtr                 sampler_;
            StateType                      *state_;
        };

        /** \addtogroup stateAndSpaceOperators Operators for States and State Spaces

           These operators are intended to simplify code that
           manipulates states and state spaces. They rely on the fact
           that state spaces have unique names. Here are some examples
           for using these operators:
          \code
           // Assume X, Y, Z, W are state space instances, none of
           // which inherits from ompl::base::CompoundStateSpace.
           // Denote a compound state space as C[...], where "..." is the
           // list of subspaces.

           ompl::base::StateSpacePtr X;
           ompl::base::StateSpacePtr Y;
           ompl::base::StateSpacePtr Z;
           ompl::base::StateSpacePtr W;

           // the following line will construct a state space C1 = C[X, Y]
           ompl::base::StateSpacePtr C1 = X + Y;

           // the following line will construct a state space C2 = C[X, Y, Z]
           ompl::base::StateSpacePtr C2 = C1 + Z;

           // the following line will leave C2 as C[X, Y, Z]
           ompl::base::StateSpacePtr C2 = C1 + C2;

           // the following line will construct a state space C2 = C[X, Y, Z, W]
           ompl::base::StateSpacePtr C2 = C2 + W;

           // the following line will construct a state space C3 = C[X, Z, Y]
           ompl::base::StateSpacePtr C3 = X + Z + Y;

           // the following line will construct a state space C4 = C[Z, W]
           ompl::base::StateSpacePtr C4 = C2 - C1;

           // the following line will construct a state space C5 = W
           ompl::base::StateSpacePtr C5 = C2 - C3;

           // the following line will construct an empty state space C6 = C[]
           ompl::base::StateSpacePtr C6 = X - X;

           // the following line will construct an empty state space C7 = Y
           ompl::base::StateSpacePtr C7 = Y + C6;
          \endcode
           These state spaces can be used when operating with states:
          \code
           ompl::base::ScopedState<> sX(X);
           ompl::base::ScopedState<> sXY(X + Y);
           ompl::base::ScopedState<> sY(Y);
           ompl::base::ScopedState<> sZX(Z + X);
           ompl::base::ScopedState<> sXZW(X + Z + W);

           // the following line will copy the content of the state sX to
           // the corresponding locations in sXZW. The components of the state
           // corresponding to the Z and W state spaces are not touched
           sX >> sXZW;

           // the following line will initialize the X component of sXY with
           // the X component of sXZW;
           sXY << sXZW;

           // the following line will initialize both components of sZX, using
           // the X and Z components of sXZW;
           sZX << sXZW;

           // the following line compares the concatenation of states sX and sY with sXY
           // the concatenation will automatically construct the state space X + Y and a state
           // from that state space containing the information from sX and sY. Since sXY is
           // constructed from the state space X + Y, the two are comparable.
           bool eq = (sX ^ sY) == sXY;
          \endcode
            @{
         */

        /** \brief Overload stream output operator. Calls ompl::base::StateSpace::printState() */
        template<class T>
        inline
        std::ostream& operator<<(std::ostream &out, const ScopedState<T> &state)
        {
            state.print(out);
            return out;
        }

        /** \brief This is a fancy version of the assignment
            operator. It is a partial assignment, in some sense. The
            difference is that if the states are part of compound
            state spaces, the data is copied from \e from to \e to on a
            component by component basis. State spaces are matched by
            name. If the state space for \e to contains any subspace
            whose name matches any subspace of the state space for \e
            from, the corresponding state components are copied. */
        template<class T, class Y>
        inline
        ScopedState<T>& operator<<(ScopedState<T> &to, const ScopedState<Y> &from)
        {
            copyStateData(to.getSpace(), to.get(), from.getSpace(), from.get());
            return to;
        }

        /** \brief This is a fancy version of the assignment
            operator. It is a partial assignment, in some sense. The
            difference is that if the states are part of compound
            state spaces, the data is copied from \e from to \e to on a
            component by component basis. State spaces are matched by
            name. If the state space for \e to contains any subspace
            whose name matches any subspace of the state space for \e
            from, the corresponding state components are copied. */
        template<class T, class Y>
        inline
        const ScopedState<T>& operator>>(const ScopedState<T> &from, ScopedState<Y> &to)
        {
            copyStateData(to.getSpace(), to.get(), from.getSpace(), from.get());
            return from;
        }

        /** \brief Given state \e a from state space A and state \e b
            from state space B, construct a state from state space A
            + B. The resulting state contains all the information from
            the input states (the states are concatenated). */
        template<class T, class Y>
        inline
        const ScopedState<> operator^(const ScopedState<T> &a, const ScopedState<Y> &b)
        {
            ScopedState<> r(a.getSpace() + b.getSpace());
            return r << a << b;
        }

        /** @} */

        template<class T>
        const ScopedState<> ScopedState<T>::operator[](const StateSpacePtr &s) const
        {
            ScopedState<> r(s);
            return r << *this;
        }

        /** \brief Shared pointer to a ScopedState<> */
        typedef boost::shared_ptr< ScopedState<> > ScopedStatePtr;
    }
}

#endif