|
| 1 | +/* |
| 2 | + * Copyright 2024 CogniPilot Foundation |
| 3 | + * Copyright 2024 Open Source Robotics Foundation |
| 4 | + * Copyright 2024 Rudis Laboratories |
| 5 | + * |
| 6 | + * Licensed under the Apache License, Version 2.0 (the "License"); |
| 7 | + * you may not use this file except in compliance with the License. |
| 8 | + * You may obtain a copy of the License at |
| 9 | + * |
| 10 | + * http://www.apache.org/licenses/LICENSE-2.0 |
| 11 | + * |
| 12 | + * Unless required by applicable law or agreed to in writing, software |
| 13 | + * distributed under the License is distributed on an "AS IS" BASIS, |
| 14 | + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 15 | + * See the License for the specific language governing permissions and |
| 16 | + * limitations under the License. |
| 17 | + * |
| 18 | +*/ |
| 19 | +#ifndef GZ_MATH_CONE_HH_ |
| 20 | +#define GZ_MATH_CONE_HH_ |
| 21 | + |
| 22 | +#include <optional> |
| 23 | +#include "gz/math/MassMatrix3.hh" |
| 24 | +#include "gz/math/Material.hh" |
| 25 | +#include "gz/math/Quaternion.hh" |
| 26 | + |
| 27 | +namespace gz |
| 28 | +{ |
| 29 | + namespace math |
| 30 | + { |
| 31 | + // Foward declarations |
| 32 | + class ConePrivate; |
| 33 | + |
| 34 | + // Inline bracket to help doxygen filtering. |
| 35 | + inline namespace GZ_MATH_VERSION_NAMESPACE { |
| 36 | + // |
| 37 | + /// \class Cone Cone.hh gz/math/Cone.hh |
| 38 | + /// \brief A representation of a cone. |
| 39 | + /// |
| 40 | + /// The cone class supports defining a cone with a radius, |
| 41 | + /// length, rotational offset, and material properties. Radius and |
| 42 | + /// length are in meters. See Material for more on material properties. |
| 43 | + /// By default, a cone's length is aligned with the Z axis where the base |
| 44 | + /// of the cone is proximal to the origin and vertex points in positive Z. |
| 45 | + /// The rotational offset encodes a rotation from the z axis. |
| 46 | + template<typename Precision> |
| 47 | + class Cone |
| 48 | + { |
| 49 | + /// \brief Default constructor. The default radius and length are both |
| 50 | + /// zero. The default rotational offset is |
| 51 | + /// Quaternion<Precision>::Identity. |
| 52 | + public: Cone() = default; |
| 53 | + |
| 54 | + /// \brief Construct a cone with a length, radius, and optionally |
| 55 | + /// a rotational offset. |
| 56 | + /// \param[in] _length Length of the cone. |
| 57 | + /// \param[in] _radius Radius of the cone. |
| 58 | + /// \param[in] _rotOffset Rotational offset of the cone. |
| 59 | + public: Cone(const Precision _length, const Precision _radius, |
| 60 | + const Quaternion<Precision> &_rotOffset = |
| 61 | + Quaternion<Precision>::Identity); |
| 62 | + |
| 63 | + /// \brief Construct a cone with a length, radius, material and |
| 64 | + /// optionally a rotational offset. |
| 65 | + /// \param[in] _length Length of the cone. |
| 66 | + /// \param[in] _radius Radius of the cone. |
| 67 | + /// \param[in] _mat Material property for the cone. |
| 68 | + /// \param[in] _rotOffset Rotational offset of the cone. |
| 69 | + public: Cone(const Precision _length, const Precision _radius, |
| 70 | + const Material &_mat, |
| 71 | + const Quaternion<Precision> &_rotOffset = |
| 72 | + Quaternion<Precision>::Identity); |
| 73 | + |
| 74 | + /// \brief Get the radius in meters. |
| 75 | + /// \return The radius of the cone in meters. |
| 76 | + public: Precision Radius() const; |
| 77 | + |
| 78 | + /// \brief Set the radius in meters. |
| 79 | + /// \param[in] _radius The radius of the cone in meters. |
| 80 | + public: void SetRadius(const Precision _radius); |
| 81 | + |
| 82 | + /// \brief Get the length in meters. |
| 83 | + /// \return The length of the cone in meters. |
| 84 | + public: Precision Length() const; |
| 85 | + |
| 86 | + /// \brief Set the length in meters. |
| 87 | + /// \param[in] _length The length of the cone in meters. |
| 88 | + public: void SetLength(const Precision _length); |
| 89 | + |
| 90 | + /// \brief Get the rotational offset. By default, a cone's length |
| 91 | + /// is aligned with the Z axis. The rotational offset encodes |
| 92 | + /// a rotation from the z axis. |
| 93 | + /// \return The cone's rotational offset. |
| 94 | + /// \sa void SetRotationalOffset(const Quaternion<Precision> &_rot) |
| 95 | + public: Quaternion<Precision> RotationalOffset() const; |
| 96 | + |
| 97 | + /// \brief Set the rotation offset. |
| 98 | + /// \param[in] _rotOffset |
| 99 | + /// See Quaternion<Precision> RotationalOffset() for details on the |
| 100 | + /// rotational offset. |
| 101 | + /// \sa Quaternion<Precision> RotationalOffset() const |
| 102 | + public: void SetRotationalOffset( |
| 103 | + const Quaternion<Precision> &_rotOffset); |
| 104 | + |
| 105 | + /// \brief Get the material associated with this cone. |
| 106 | + /// \return The material assigned to this cone |
| 107 | + public: const Material &Mat() const; |
| 108 | + |
| 109 | + /// \brief Set the material associated with this cone. |
| 110 | + /// \param[in] _mat The material assigned to this cone |
| 111 | + public: void SetMat(const Material &_mat); |
| 112 | + |
| 113 | + /// \brief Get the mass matrix for this cone. This function |
| 114 | + /// is only meaningful if the cone's radius, length, and material |
| 115 | + /// have been set. Optionally, set the rotational offset. |
| 116 | + /// \param[out] _massMat The computed mass matrix will be stored |
| 117 | + /// here. |
| 118 | + /// \return False if computation of the mass matrix failed, which |
| 119 | + /// could be due to an invalid radius (<=0), length (<=0), or density |
| 120 | + /// (<=0). |
| 121 | + public: bool MassMatrix(MassMatrix3d &_massMat) const; |
| 122 | + |
| 123 | + /// \brief Get the mass matrix for this cone. This function |
| 124 | + /// is only meaningful if the cone's radius, length, and material |
| 125 | + /// have been set. Optionally, set the rotational offset. |
| 126 | + /// \return The computed mass matrix if parameters are valid |
| 127 | + /// (radius > 0), (length > 0) and (density > 0). Otherwise |
| 128 | + /// std::nullopt is returned. |
| 129 | + public: std::optional< MassMatrix3<Precision> > MassMatrix() const; |
| 130 | + |
| 131 | + /// \brief Check if this cone is equal to the provided cone. |
| 132 | + /// Radius, length, and material properties will be checked. |
| 133 | + public: bool operator==(const Cone &_cone) const; |
| 134 | + |
| 135 | + /// \brief Get the volume of the cone in m^3. |
| 136 | + /// \return Volume of the cone in m^3. |
| 137 | + public: Precision Volume() const; |
| 138 | + |
| 139 | + /// \brief Compute the cone's density given a mass value. The |
| 140 | + /// cone is assumed to be solid with uniform density. This |
| 141 | + /// function requires the cone's radius and length to be set to |
| 142 | + /// values greater than zero. The Material of the cone is ignored. |
| 143 | + /// \param[in] _mass Mass of the cone, in kg. This value should be |
| 144 | + /// greater than zero. |
| 145 | + /// \return Density of the cone in kg/m^3. A negative value is |
| 146 | + /// returned if radius, length or _mass is <= 0. |
| 147 | + public: Precision DensityFromMass(const Precision _mass) const; |
| 148 | + |
| 149 | + /// \brief Set the density of this cone based on a mass value. |
| 150 | + /// Density is computed using |
| 151 | + /// Precision DensityFromMass(const Precision _mass) const. The |
| 152 | + /// cone is assumed to be solid with uniform density. This |
| 153 | + /// function requires the cone's radius and length to be set to |
| 154 | + /// values greater than zero. The existing Material density value is |
| 155 | + /// overwritten only if the return value from this true. |
| 156 | + /// \param[in] _mass Mass of the cone, in kg. This value should be |
| 157 | + /// greater than zero. |
| 158 | + /// \return True if the density was set. False is returned if the |
| 159 | + /// cone's radius, length, or the _mass value are <= 0. |
| 160 | + /// \sa Precision DensityFromMass(const Precision _mass) const |
| 161 | + public: bool SetDensityFromMass(const Precision _mass); |
| 162 | + |
| 163 | + /// \brief Radius of the cone. |
| 164 | + private: Precision radius = 0.0; |
| 165 | + |
| 166 | + /// \brief Length of the cone. |
| 167 | + private: Precision length = 0.0; |
| 168 | + |
| 169 | + /// \brief the cone's material. |
| 170 | + private: Material material; |
| 171 | + |
| 172 | + /// \brief Rotational offset. |
| 173 | + private: Quaternion<Precision> rotOffset = |
| 174 | + Quaternion<Precision>::Identity; |
| 175 | + }; |
| 176 | + |
| 177 | + /// \typedef Cone<int> Conei |
| 178 | + /// \brief Cone with integer precision. |
| 179 | + typedef Cone<int> Conei; |
| 180 | + |
| 181 | + /// \typedef Cone<double> Coned |
| 182 | + /// \brief Cone with double precision. |
| 183 | + typedef Cone<double> Coned; |
| 184 | + |
| 185 | + /// \typedef Cone<float> Conef |
| 186 | + /// \brief Cone with float precision. |
| 187 | + typedef Cone<float> Conef; |
| 188 | + } |
| 189 | + } |
| 190 | +} |
| 191 | +#include "gz/math/detail/Cone.hh" |
| 192 | + |
| 193 | +#endif |
0 commit comments