File: Physics.hh

package info (click to toggle)
sdformat 12.3.0%2Bds-2
  • links: PTS, VCS
  • area: main
  • in suites: bookworm
  • size: 7,980 kB
  • sloc: cpp: 54,706; python: 3,729; javascript: 704; ruby: 366; sh: 97; ansic: 30; makefile: 16
file content (110 lines) | stat: -rw-r--r-- 4,052 bytes parent folder | download
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
/*
 * Copyright 2018 Open Source Robotics Foundation
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 *     http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 *
 */
#ifndef SDF_PHYSICS_HH_
#define SDF_PHYSICS_HH_

#include <string>
#include <ignition/utils/ImplPtr.hh>

#include "sdf/Element.hh"
#include "sdf/Types.hh"
#include "sdf/sdf_config.h"
#include "sdf/system_util.hh"

namespace sdf
{
  // Inline bracket to help doxygen filtering.
  inline namespace SDF_VERSION_NAMESPACE {
  //

  /// \brief The physics element specifies the type and properties of a
  /// dynamics engine.
  class SDFORMAT_VISIBLE Physics
  {
    /// \brief Default constructor
    public: Physics();

    /// \brief Load the physics based on an element pointer. This is *not* the
    /// usual entry point. Typical usage of the SDF DOM is through the Root
    /// object.
    /// \param[in] _sdf The SDF Element pointer
    /// \return Errors, which is a vector of Error objects. Each Error includes
    /// an error code and message. An empty vector indicates no error.
    public: Errors Load(ElementPtr _sdf);

    /// \brief Get the name of this set of physics parameters.
    /// \return Name of the physics profile.
    public: std::string Name() const;

    /// \brief Set the name of this set of physics parameters.
    /// \param[in] _name Name of the physics profile.
    public: void SetName(const std::string &_name);

    /// \brief Get a pointer to the SDF element that was used during
    /// load.
    /// \return SDF element pointer. The value will be nullptr if Load has
    /// not been called.
    public: sdf::ElementPtr Element() const;

    /// \brief Get whether this physics profile is marked as default.
    /// If true, this physics profile is set as the default physics profile
    /// for the World. If multiple default physics elements exist, the first
    /// physics profile marked as default is chosen. If no default physics
    /// element exists, the first physics element is chosen.
    /// \return True if this profile is the default.
    public: bool IsDefault() const;

    /// \brief Set whether this physics profile is the default.
    /// \param[in] _default True to make this profile default.
    public: void SetDefault(const bool _default);

    /// \brief Get the physics profile dynamics engine type.
    /// Current options are ode, bullet, simbody and dart. Defaults to ode if
    /// left unspecified.
    /// \return The type of dynamics engine.
    public: std::string EngineType() const;

    /// \brief Set the physics profile dynamics engine type.
    /// \param[in] _type The type of dynamics engine.
    public: void SetEngineType(const std::string &_type);

    /// \brief Get the max step size in seconds.
    /// The Maximum time step size at which every system in simulation can
    /// interact with the states of the world.
    /// \return The max step size in seconds.
    public: double MaxStepSize() const;

    /// \brief Set the max step size in seconds.
    /// \param[in] _step The max step size in seconds.
    public: void SetMaxStepSize(const double _step);

    /// \brief Get the target real time factor.
    /// Target simulation speedup factor, defined by ratio of simulation time
    /// to real-time.
    /// \return The target real time factor.
    public: double RealTimeFactor() const;

    /// \brief Set the target realtime factor.
    /// \param[in] _factor The target real time factor.
    public: void SetRealTimeFactor(const double _factor);

    /// \brief Private data pointer.
    IGN_UTILS_IMPL_PTR(dataPtr)
  };
  }
}
#endif