Skip to content

Commit 32dc472

Browse files
author
henrykotze
committed
Airflow Sensor
Copied Airspeed Sensor and renamed to Airflow - Also already added airflow code where airspeed is found made corresponding changes to fit airflow new index number for airflow sensor Added AirPressure header back Testing for airflow sensor implemented Add noise testing for airflow sensor Python implementation for Airflow Sensor
1 parent 24b6153 commit 32dc472

File tree

16 files changed

+704
-2
lines changed

16 files changed

+704
-2
lines changed

include/sdf/AirFlow.hh

Lines changed: 93 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,93 @@
1+
/*
2+
* Copyright 2023 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
#ifndef SDF_AirFlow_HH_
18+
#define SDF_AirFlow_HH_
19+
20+
#include <gz/utils/ImplPtr.hh>
21+
22+
#include <sdf/Error.hh>
23+
#include <sdf/Element.hh>
24+
#include <sdf/Noise.hh>
25+
#include <sdf/sdf_config.h>
26+
27+
namespace sdf
28+
{
29+
// Inline bracke to help doxygen filtering.
30+
inline namespace SDF_VERSION_NAMESPACE {
31+
/// \brief AirFlow contains information about a general
32+
/// purpose air flow sensor.
33+
/// This sensor can be attached to a link.
34+
class SDFORMAT_VISIBLE AirFlow
35+
{
36+
/// \brief Default constructor
37+
public: AirFlow();
38+
39+
/// \brief Load the air flow based on an element pointer.
40+
/// This is *not* the usual entry point. Typical usage of the SDF DOM is
41+
/// through the Root object.
42+
/// \param[in] _sdf The SDF Element pointer
43+
/// \return Errors, which is a vector of Error objects. Each Error includes
44+
/// an error code and message. An empty vector indicates no error.
45+
public: Errors Load(ElementPtr _sdf);
46+
47+
/// \brief Get a pointer to the SDF element that was used during
48+
/// load.
49+
/// \return SDF element pointer. The value will be nullptr if Load has
50+
/// not been called.
51+
public: sdf::ElementPtr Element() const;
52+
53+
/// \brief Get the noise values.
54+
/// \return Noise values for differential pressure data.
55+
public: const Noise &SpeedNoise() const;
56+
57+
/// \brief Set the noise values related to the differential pressure data.
58+
/// \param[in] _noise Noise values for the pressure data.
59+
public: void SetSpeedNoise(const Noise &_noise);\
60+
61+
/// \brief Get the noise values.
62+
/// \return Noise values for differential pressure data.
63+
public: const Noise &DirectionNoise() const;
64+
65+
/// \brief Set the noise values related to the differential pressure data.
66+
/// \param[in] _noise Noise values for the pressure data.
67+
public: void SetDirectionNoise(const Noise &_noise);
68+
69+
/// \brief Return true if both AirFlow objects contain the
70+
/// same values.
71+
/// \param[_in] _air AirFlow value to compare.
72+
/// \returen True if 'this' == _air.
73+
public: bool operator==(const AirFlow &_air) const;
74+
75+
/// \brief Return true this AirFlow object does not contain
76+
/// the same values as the passed in parameter.
77+
/// \param[_in] _air AirFlow value to compare.
78+
/// \returen True if 'this' != _air.
79+
public: bool operator!=(const AirFlow &_air) const;
80+
81+
/// \brief Create and return an SDF element filled with data from this
82+
/// air pressure sensor.
83+
/// Note that parameter passing functionality is not captured with this
84+
/// function.
85+
/// \return SDF element pointer with updated sensor values.
86+
public: sdf::ElementPtr ToElement() const;
87+
88+
/// \brief Private data pointer.
89+
GZ_UTILS_IMPL_PTR(dataPtr)
90+
};
91+
}
92+
}
93+
#endif

include/sdf/Sensor.hh

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ namespace sdf
3535
//
3636

3737
// Forward declarations.
38+
class AirFlow;
3839
class AirPressure;
3940
class AirSpeed;
4041
class Altimeter;
@@ -134,6 +135,9 @@ namespace sdf
134135

135136
/// \brief An air speed sensor.
136137
AIR_SPEED = 26,
138+
139+
/// \brief An airflow sensor.
140+
AIR_FLOW = 27,
137141
};
138142

139143
/// \brief Information about an SDF sensor.
@@ -341,6 +345,24 @@ namespace sdf
341345
/// \param[in] _air The air pressure sensor.
342346
public: void SetAirSpeedSensor(const AirSpeed &_air);
343347

348+
/// \brief Get the air speed sensor, or nullptr if this sensor type
349+
/// is not an AirSpeed sensor.
350+
/// \return Pointer to the AirSpeed sensor, or nullptr if this
351+
/// Sensor is not a AirSpeed sensor.
352+
/// \sa SensorType Type() const
353+
public: const AirFlow *AirFlowSensor() const;
354+
355+
/// \brief Get a mutable air speed sensor, or nullptr if this sensor type
356+
/// is not an AirSpeed sensor.
357+
/// \return Pointer to the AirSpeed sensor, or nullptr if this
358+
/// Sensor is not a AirSpeed sensor.
359+
/// \sa SensorType Type() const
360+
public: AirFlow *AirFlowSensor();
361+
362+
/// \brief Set the air pressure sensor.
363+
/// \param[in] _air The air pressure sensor.
364+
public: void SetAirFlowSensor(const AirFlow &_air);
365+
344366
/// \brief Set the camera sensor.
345367
/// \param[in] _cam The camera sensor.
346368
public: void SetCameraSensor(const Camera &_cam);

python/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ endfunction()
4444
set(BINDINGS_MODULE_NAME "pysdformat${PROJECT_VERSION_MAJOR}")
4545
pybind11_add_module(${BINDINGS_MODULE_NAME} MODULE
4646
src/sdf/_gz_sdformat_pybind11.cc
47+
src/sdf/pyAirFlow.cc
4748
src/sdf/pyAirPressure.cc
4849
src/sdf/pyAirSpeed.cc
4950
src/sdf/pyAltimeter.cc

python/src/sdf/_gz_sdformat_pybind11.cc

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <pybind11/stl.h>
1919
#include <gz/math/config.hh>
2020

21+
#include "pyAirFlow.hh"
2122
#include "pyAirPressure.hh"
2223
#include "pyAirSpeed.hh"
2324
#include "pyAltimeter.hh"
@@ -74,6 +75,7 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) {
7475
std::string("gz.math") + std::to_string(GZ_MATH_MAJOR_VERSION);
7576
pybind11::module::import(gzMathModule.c_str());
7677

78+
sdf::python::defineAirFlow(m);
7779
sdf::python::defineAirPressure(m);
7880
sdf::python::defineAirSpeed(m);
7981
sdf::python::defineAltimeter(m);

python/src/sdf/pyAirFlow.cc

Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
/*
2+
* Copyright (C) 2023 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*/
16+
17+
#include "pyAirFlow.hh"
18+
19+
#include <pybind11/operators.h>
20+
#include <pybind11/pybind11.h>
21+
22+
#include "sdf/AirFlow.hh"
23+
24+
25+
using namespace pybind11::literals;
26+
27+
namespace sdf
28+
{
29+
// Inline bracket to help doxygen filtering.
30+
inline namespace SDF_VERSION_NAMESPACE {
31+
namespace python
32+
{
33+
/////////////////////////////////////////////////
34+
void defineAirFlow(pybind11::object module)
35+
{
36+
pybind11::class_<sdf::AirFlow> geometryModule(module, "AirFlow");
37+
geometryModule
38+
.def(pybind11::init<>())
39+
.def(pybind11::init<sdf::AirFlow>())
40+
.def(pybind11::self == pybind11::self)
41+
.def(pybind11::self != pybind11::self)
42+
.def("speed_noise", &sdf::AirFlow::SpeedNoise,
43+
"Get the speed noise values.")
44+
.def("set_speed_noise",
45+
&sdf::AirFlow::SetSpeedNoise,
46+
"Set the noise values related to the speed data.")
47+
.def("dir_noise", &sdf::AirFlow::DirectionNoise,
48+
"Get the direction noise values.")
49+
.def("set_direction_noise",
50+
&sdf::AirFlow::SetDirectionNoise,
51+
"Set the noise values related to the direction data.")
52+
.def("__copy__", [](const sdf::AirFlow &self) {
53+
return sdf::AirFlow(self);
54+
})
55+
.def("__deepcopy__", [](const sdf::AirFlow &self, pybind11::dict) {
56+
return sdf::AirFlow(self);
57+
}, "memo"_a);
58+
}
59+
} // namespace python
60+
} // namespace SDF_VERSION_NAMESPACE
61+
} // namespace sdf

python/src/sdf/pyAirFlow.hh

Lines changed: 41 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
/*
2+
* Copyright (C) 2023 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*/
16+
17+
#ifndef SDFORMAT_PYTHON_AIRFLOW_HH_
18+
#define SDFORMAT_PYTHON_AIRFLOW_HH_
19+
20+
#include <pybind11/pybind11.h>
21+
22+
#include "sdf/AirFlow.hh"
23+
24+
#include "sdf/config.hh"
25+
26+
namespace sdf
27+
{
28+
// Inline bracket to help doxygen filtering.
29+
inline namespace SDF_VERSION_NAMESPACE {
30+
namespace python
31+
{
32+
/// Define a pybind11 wrapper for an sdf::AirFlow
33+
/**
34+
* \param[in] module a pybind11 module to add the definition to
35+
*/
36+
void defineAirFlow(pybind11::object module);
37+
} // namespace python
38+
} // namespace SDF_VERSION_NAMESPACE
39+
} // namespace sdf
40+
41+
#endif // SDFORMAT_PYTHON_AirFlow_HH_

python/test/pyAirFlow_TEST.py

Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
1+
# Copyright (C) 2023 Open Source Robotics Foundation
2+
3+
# Licensed under the Apache License, Version 2.0 (the "License")
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from gz_test_deps.sdformat import AirFlow, Noise
16+
import gz_test_deps.sdformat as sdf
17+
import unittest
18+
19+
class AirFlowTEST(unittest.TestCase):
20+
21+
22+
def test_default_construction(self):
23+
airflow = AirFlow()
24+
defaultNoise = Noise()
25+
self.assertEqual(defaultNoise, airflow.direction_noise())
26+
self.assertEqual(defaultNoise, airflow.speed_noise())
27+
28+
def test_set(self):
29+
air = AirFlow()
30+
defaultNoise = Noise()
31+
dir_noise = Noise()
32+
speed_noise = Noise()
33+
self.assertEqual(defaultNoise, air.speed_noise())
34+
self.assertEqual(defaultNoise, air.direction_noise())
35+
36+
dir_noise.set_type(sdf.NoiseType.GAUSSIAN)
37+
dir_noise.set_mean(1.2)
38+
dir_noise.set_std_dev(2.3)
39+
dir_noise.set_bias_mean(4.5)
40+
dir_noise.set_bias_std_dev(6.7)
41+
dir_noise.set_precision(8.9)
42+
43+
speed_noise.set_type(sdf.NoiseType.GAUSSIAN)
44+
speed_noise.set_mean(1.2)
45+
speed_noise.set_std_dev(2.3)
46+
speed_noise.set_bias_mean(4.5)
47+
speed_noise.set_bias_std_dev(6.7)
48+
speed_noise.set_precision(8.9)
49+
50+
air.set_direction_noise(dir_noise)
51+
self.assertEqual(dir_noise, air.direction_noise())
52+
self.assertEqual(speed_noise, air.speed_noise())
53+
54+
# Copy Constructor
55+
air2 = AirFlow(air)
56+
self.assertEqual(air, air2)
57+
58+
# Copy operator
59+
air3 = air
60+
self.assertEqual(air, air3)
61+
62+
air4 = AirFlow()
63+
self.assertNotEqual(air3, air4);
64+
65+
66+
if __name__ == '__main__':
67+
unittest.main()

sdf/1.10/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
set (sdfs
22
actor.sdf
3+
air_flow.sdf
34
air_pressure.sdf
45
air_speed.sdf
56
altimeter.sdf

sdf/1.10/air_flow.sdf

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
<element name="air_flow" required="0">
2+
<description>These elements are specific to an air flow sensor. This sensor emulates an ultrasonic airflow sensor which determines the airspeed and direction based on the doppler effect.</description>
3+
4+
<element name="speed" required="0">
5+
<description>
6+
Noise parameters for the speed data.
7+
</description>
8+
<include filename="noise.sdf" required="0"/>
9+
</element>
10+
11+
<element name="direction" required="0">
12+
<description>
13+
Noise parameters for the direction data.
14+
</description>
15+
<include filename="noise.sdf" required="0"/>
16+
</element>
17+
18+
</element>

sdf/1.10/sensor.sdf

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88

99
<attribute name="type" type="string" default="__default__" required="1">
1010
<description>The type name of the sensor. By default, SDFormat supports types
11+
air_flow,
1112
air_pressure,
1213
air_speed,
1314
altimeter,
@@ -61,6 +62,7 @@
6162

6263
<include filename="pose.sdf" required="0"/>
6364
<include filename="plugin.sdf" required="*"/>
65+
<include filename="air_flow.sdf" required="0"/>
6466
<include filename="air_pressure.sdf" required="0"/>
6567
<include filename="air_speed.sdf" required="0"/>
6668
<include filename="altimeter.sdf" required="0"/>

0 commit comments

Comments
 (0)