Skip to content

Commit

Permalink
OrientedBox Python interface (#276)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>

* Rename [XYZ]Length methods to [xyz]_length

Signed-off-by: Steve Peters <[email protected]>
Co-authored-by: Steve Peters <[email protected]>
  • Loading branch information
ahcorde and scpeters authored Nov 9, 2021
1 parent f92b793 commit cbc2a1b
Show file tree
Hide file tree
Showing 4 changed files with 405 additions and 0 deletions.
1 change: 1 addition & 0 deletions src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,7 @@ if (PYTHONLIBS_FOUND)
Matrix3_TEST
Matrix4_TEST
MovingWindowFilter_TEST
OrientedBox_TEST
PID_TEST
Plane_TEST
Pose3_TEST
Expand Down
93 changes: 93 additions & 0 deletions src/python/OrientedBox.i
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
/*
* Copyright (C) 2021 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.
*
*/

%module orientedbox
%{
#include <iostream>
#include <ignition/math/OrientedBox.hh>
#include <ignition/math/Helpers.hh>
#include <ignition/math/MassMatrix3.hh>
#include <ignition/math/Material.hh>
#include <ignition/math/Matrix4.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/config.hh>
%}

namespace ignition
{
namespace math
{
template<typename T>
class ignition::math::OrientedBox
{
%rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) "";
public: OrientedBox();

public: OrientedBox(
const ignition::math::Vector3<T> &_size, const ignition::math::Pose3<T> &_pose);

public: OrientedBox(const ignition::math::Vector3<T> &_size, const ignition::math::Pose3<T> &_pose,
const ignition::math::Material &_mat);

public: explicit OrientedBox(const ignition::math::Vector3<T> &_size);

public: explicit OrientedBox(const ignition::math::Vector3<T> &_size,
const ignition::math::Material &_mat);

public: OrientedBox(const ignition::math::OrientedBox<T> &_b);

public: virtual ~OrientedBox();

%rename(x_length) XLength;
public: T XLength() const;

%rename(y_length) YLength;
public: T YLength() const;

%rename(z_length) ZLength;
public: T ZLength() const;

public: const ignition::math::Vector3<T> &Size() const;

public: const ignition::math::Pose3<T> &Pose() const;

public: void Size(ignition::math::Vector3<T> &_size);

public: void Pose(ignition::math::Pose3<T> &_pose);

public: bool operator==(const ignition::math::OrientedBox<T> &_b) const;

public: bool operator!=(const ignition::math::OrientedBox<T> &_b) const;

public: bool Contains(const ignition::math::Vector3<double> &_p) const;

public: const ignition::math::ignition::math::Material &ignition::math::Material() const;

public: void ignition::math::SetMaterial(const ignition::math::ignition::math::Material &_mat);

public: T Volume() const;

public: T DensityFromMass(const T _mass) const;

public: bool SetDensityFromMass(const T _mass);

public: bool MassMatrix(MassMatrix3<T> &_massMat) const;
};
%template(OrientedBoxd) OrientedBox<double>;
}
}
Loading

0 comments on commit cbc2a1b

Please sign in to comment.