Skip to content

Commit

Permalink
Added Atmosphere Python interface (#968)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored May 12, 2022
1 parent 7182fad commit 324a755
Show file tree
Hide file tree
Showing 7 changed files with 180 additions and 2 deletions.
2 changes: 1 addition & 1 deletion include/sdf/Atmosphere.hh
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ namespace sdf
/// instance equals the given atmosphere instance.
/// \param[in] _atmosphere Atmosphere instance to compare.
/// \return True if this instance equals the given atmosphere.
public: bool operator==(const Atmosphere &_atmosphere);
public: bool operator==(const Atmosphere &_atmosphere) const;

/// \brief Create and return an SDF element filled with data from this
/// atmosphere.
Expand Down
2 changes: 2 additions & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ endfunction()
pybind11_add_module(sdformat SHARED
src/sdf/_ignition_sdformat_pybind11.cc
src/sdf/pyAltimeter.cc
src/sdf/pyAtmosphere.cc
src/sdf/pyBox.cc
src/sdf/pyCapsule.cc
src/sdf/pyCollision.cc
Expand Down Expand Up @@ -84,6 +85,7 @@ if (BUILD_TESTING)

set(python_tests
pyAltimeter_TEST
pyAtmosphere_TEST
pyBox_TEST
pyCapsule_TEST
pyCollision_TEST
Expand Down
2 changes: 2 additions & 0 deletions python/src/sdf/_ignition_sdformat_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <pybind11/pybind11.h>

#include "pyAltimeter.hh"
#include "pyAtmosphere.hh"
#include "pyBox.hh"
#include "pyCapsule.hh"
#include "pyCollision.hh"
Expand Down Expand Up @@ -47,6 +48,7 @@ PYBIND11_MODULE(sdformat, m) {
m.doc() = "sdformat Python Library.";

sdf::python::defineAltimeter(m);
sdf::python::defineAtmosphere(m);
sdf::python::defineBox(m);
sdf::python::defineCapsule(m);
sdf::python::defineCollision(m);
Expand Down
72 changes: 72 additions & 0 deletions python/src/sdf/pyAtmosphere.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
/*
* Copyright (C) 2022 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.
*/

#include "pyAtmosphere.hh"

#include <pybind11/operators.h>
#include <pybind11/pybind11.h>

#include <ignition/math/Temperature.hh>

#include "sdf/Atmosphere.hh"

using namespace pybind11::literals;

namespace sdf
{
// Inline bracket to help doxygen filtering.
inline namespace SDF_VERSION_NAMESPACE {
namespace python
{
/////////////////////////////////////////////////
void defineAtmosphere(pybind11::object module)
{
pybind11::class_<sdf::Atmosphere> atmosphereModule(module, "Atmosphere");
atmosphereModule
.def(pybind11::init<>())
.def(pybind11::init<sdf::Atmosphere>())
.def(pybind11::self == pybind11::self)
.def("type", &sdf::Atmosphere::Type,
"Get the type of the atmospheric model.")
.def("set_type", &sdf::Atmosphere::SetType,
"Set the type of the atmospheric model.")
.def("temperature", &sdf::Atmosphere::Temperature,
"Get the temperature at sea level.")
.def("set_temperature", &sdf::Atmosphere::SetTemperature,
"Set the temperature at sea level")
.def("temperature_gradient", &sdf::Atmosphere::TemperatureGradient,
"Get the temperature gradient with respect to increasing "
"altitude in units of K/m.")
.def("set_temperature_gradient", &sdf::Atmosphere::SetTemperatureGradient,
"Set the temperature gradient with respect to increasing "
"altitude in units of K/m.")
.def("pressure", &sdf::Atmosphere::Pressure,
"Get the pressure at sea level in pascals.")
.def("set_pressure", &sdf::Atmosphere::SetPressure,
"Set the pressure at sea level in pascals.")
.def("__copy__", [](const sdf::Atmosphere &self) {
return sdf::Atmosphere(self);
})
.def("__deepcopy__", [](const sdf::Atmosphere &self, pybind11::dict) {
return sdf::Atmosphere(self);
}, "memo"_a);

pybind11::enum_<sdf::AtmosphereType>(atmosphereModule, "AtmosphereType")
.value("ADIABATIC", sdf::AtmosphereType::ADIABATIC);
}
} // namespace python
} // namespace SDF_VERSION_NAMESPACE
} // namespace sdf
41 changes: 41 additions & 0 deletions python/src/sdf/pyAtmosphere.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* Copyright (C) 2022 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 SDFORMAT_PYTHON_ATMOSPHERE_HH_
#define SDFORMAT_PYTHON_ATMOSPHERE_HH_

#include <pybind11/pybind11.h>

#include "sdf/Atmosphere.hh"

#include "sdf/config.hh"

namespace sdf
{
// Inline bracket to help doxygen filtering.
inline namespace SDF_VERSION_NAMESPACE {
namespace python
{
/// Define a pybind11 wrapper for an sdf::Atmosphere
/**
* \param[in] module a pybind11 module to add the definition to
*/
void defineAtmosphere(pybind11::object module);
} // namespace python
} // namespace SDF_VERSION_NAMESPACE
} // namespace sdf

#endif // SDFORMAT_PYTHON_ATMOSPHERE_HH_
61 changes: 61 additions & 0 deletions python/test/pyAtmosphere_TEST.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
# Copyright (C) 2022 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.

from ignition.math import Pose3d, Temperature
from sdformat import Atmosphere
import unittest

class AtmosphereTEST(unittest.TestCase):


def test_default_construction(self):
atmosphere = Atmosphere()
self.assertEqual(Atmosphere.AtmosphereType.ADIABATIC, atmosphere.type())
self.assertAlmostEqual(288.15, atmosphere.temperature().kelvin())
self.assertAlmostEqual(-0.0065, atmosphere.temperature_gradient())
self.assertAlmostEqual(101325, atmosphere.pressure())


def test_set(self):
atmosphere = Atmosphere()
atmosphere.set_type(Atmosphere.AtmosphereType.ADIABATIC)
self.assertEqual(Atmosphere.AtmosphereType.ADIABATIC, atmosphere.type())

atmosphere.set_temperature(Temperature(123.23))
self.assertAlmostEqual(123.23, atmosphere.temperature().kelvin())

atmosphere.set_temperature_gradient(-1.65)
self.assertAlmostEqual(-1.65, atmosphere.temperature_gradient())

atmosphere.set_pressure(76531.3)
self.assertAlmostEqual(76531.3, atmosphere.pressure())


def test_copy_assignment(self):
atmosphere = Atmosphere()
atmosphere.set_temperature(Temperature(123.23))
atmosphere.set_temperature_gradient(-1.65)
atmosphere.set_pressure(76531.3)

atmosphere2 = atmosphere
self.assertEqual(Atmosphere.AtmosphereType.ADIABATIC, atmosphere2.type())
self.assertAlmostEqual(123.23, atmosphere2.temperature().kelvin())
self.assertAlmostEqual(-1.65, atmosphere2.temperature_gradient())
self.assertAlmostEqual(76531.3, atmosphere2.pressure())

self.assertEqual(atmosphere, atmosphere2)


if __name__ == '__main__':
unittest.main()
2 changes: 1 addition & 1 deletion src/Atmosphere.cc
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ void Atmosphere::SetPressure(const double _pressure)
}

//////////////////////////////////////////////////
bool Atmosphere::operator==(const Atmosphere &_atmosphere)
bool Atmosphere::operator==(const Atmosphere &_atmosphere) const
{
return this->dataPtr->type == _atmosphere.dataPtr->type &&
this->dataPtr->temperature == _atmosphere.dataPtr->temperature &&
Expand Down

0 comments on commit 324a755

Please sign in to comment.