Skip to content

Commit

Permalink
rename satnav to navsat, and other review commments
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <ashton@openrobotics.org>
  • Loading branch information
adlarkin committed Jun 14, 2021
1 parent fc60ae0 commit b128c9c
Show file tree
Hide file tree
Showing 13 changed files with 285 additions and 242 deletions.
2 changes: 1 addition & 1 deletion include/sdf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ set (headers
Filesystem.hh
Frame.hh
Geometry.hh
SatNav.hh
Gui.hh
Heightmap.hh
Imu.hh
Expand All @@ -30,6 +29,7 @@ set (headers
Material.hh
Mesh.hh
Model.hh
NavSat.hh
Noise.hh
Param.hh
parser.hh
Expand Down
64 changes: 32 additions & 32 deletions include/sdf/SatNav.hh → include/sdf/NavSat.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
* limitations under the License.
*
*/
#ifndef SDF_SATNAV_HH_
#define SDF_SATNAV_HH_
#ifndef SDF_NAVSAT_HH_
#define SDF_NAVSAT_HH_

#include <sdf/Error.hh>
#include <sdf/Element.hh>
Expand All @@ -29,19 +29,19 @@ namespace sdf
// Inline bracket to help doxygen filtering.
inline namespace SDF_VERSION_NAMESPACE {
//
class SatNavPrivate;
class NavSatPrivate;

/// \brief SatNav contains information about a SatNav sensor.
/// This sensor can be attached to a link. The SatNav sensor can be defined
/// SDF XML by the "satnav" type.
/// \brief NavSat contains information about a NavSat sensor.
/// This sensor can be attached to a link. The NavSat sensor can be defined
/// SDF XML by the "navsat" type.
///
/// # Example SDF XML using satnav type:
/// # Example SDF XML using navsat type:
///
/// ~~~{.xml}
/// <sensor name="satnav_sensor" type="satnav">
/// <sensor name="navsat_sensor" type="navsat">
/// <pose>1 2 3 0 0 0</pose>
/// <topic>/satnav</topic>
/// <satnav>
/// <topic>/navsat</topic>
/// <navsat>
/// <position_sensing>
/// <horizontal>
/// <noise type="gaussian">
Expand Down Expand Up @@ -70,36 +70,36 @@ namespace sdf
/// </noise>
/// </vertical>
/// </velocity_sensing>
/// </satnav>
/// </navsat>
/// </sensor>
/// ~~~
class SDFORMAT_VISIBLE SatNav
class SDFORMAT_VISIBLE NavSat
{
/// \brief Default constructor
public: SatNav();
public: NavSat();

/// \brief Copy constructor
/// \param[in] _satnav SatNav to copy.
public: SatNav(const SatNav &_satnav);
/// \param[in] _navsat NavSat to copy.
public: NavSat(const NavSat &_navsat);

/// \brief Move constructor
/// \param[in] _satnav SatNav to move.
public: SatNav(SatNav &&_satnav) noexcept;
/// \param[in] _navsat NavSat to move.
public: NavSat(NavSat &&_navsat) noexcept;

/// \brief Destructor
public: ~SatNav();
public: ~NavSat();

/// \brief Assignment operator
/// \param[in] _satnav The satnav to set values from.
/// \param[in] _navsat The navsat to set values from.
/// \return *this
public: SatNav &operator=(const SatNav &_satnav);
public: NavSat &operator=(const NavSat &_navsat);

/// \brief Move assignment operator
/// \param[in] _satnav The satnav to set values from.
/// \param[in] _navsat The navsat to set values from.
/// \return *this
public: SatNav &operator=(SatNav &&_satnav) noexcept;
public: NavSat &operator=(NavSat &&_navsat) noexcept;

/// \brief Load the satnav based on an element pointer. This is *not*
/// \brief Load the navsat 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
Expand Down Expand Up @@ -145,19 +145,19 @@ namespace sdf
/// \return Noise values
public: const Noise &VerticalVelocityNoise() const;

/// \brief Return true if both SatNav objects contain the same values.
/// \param[_in] _satnav SatNav value to compare.
/// \return True if 'this' == _satnav.
public: bool operator==(const SatNav &_satnav) const;
/// \brief Return true if both NavSat objects contain the same values.
/// \param[_in] _navsat NavSat value to compare.
/// \return True if 'this' == _navsat.
public: bool operator==(const NavSat &_navsat) const;

/// \brief Return true this SatNav object does not contain the same
/// \brief Return true this NavSat object does not contain the same
/// values as the passed in parameter.
/// \param[_in] _satnav SatNav value to compare.
/// \return True if 'this' != _satnav.
public: bool operator!=(const SatNav &_satnav) const;
/// \param[_in] _navsat NavSat value to compare.
/// \return True if 'this' != _navsat.
public: bool operator!=(const NavSat &_navsat) const;

/// \brief Private data pointer.
private: SatNavPrivate *dataPtr;
private: NavSatPrivate *dataPtr;
};
}
}
Expand Down
28 changes: 15 additions & 13 deletions include/sdf/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ namespace sdf
class AirPressure;
class Altimeter;
class Camera;
class SatNav;
class Imu;
class Lidar;
class Magnetometer;
class NavSat;
class SensorPrivate;
struct PoseRelativeToGraph;

Expand Down Expand Up @@ -66,8 +66,8 @@ namespace sdf
/// \brief A force-torque sensor.
FORCE_TORQUE = 5,

/// \brief A SatNav sensor, such as GPS.
SATNAV = 6,
/// \brief A GPS sensor.
GPS = 6,

/// \brief A GPU based lidar sensor.
GPU_LIDAR = 7,
Expand Down Expand Up @@ -110,7 +110,10 @@ namespace sdf
RGBD_CAMERA = 19,

/// \brief A thermal camera sensor
THERMAL_CAMERA = 20
THERMAL_CAMERA = 20,

/// \brief A NavSat sensor, such as GPS.
NAVSAT = 21
};

/// \brief Information about an SDF sensor.
Expand Down Expand Up @@ -288,17 +291,16 @@ namespace sdf
/// \sa SensorType Type() const
public: const Camera *CameraSensor() const;

/// \brief Set the SATNAV sensor.
/// \param[in] _satnav The SATNAV sensor.
public: void SetSatNavSensor(const SatNav &_satnav);
/// \brief Set the NAVSAT sensor.
/// \param[in] _navsat The NAVSAT sensor.
public: void SetNavSatSensor(const NavSat &_navsat);

/// \brief Get a pointer to an SATNAV sensor, or nullptr if the sensor
/// does not contain an SATNAV sensor.
/// \return Pointer to the sensor's SATNAV, or nullptr if the sensor
/// is not an SATNAV.
/// \brief Get a pointer to a NAVSAT sensor, or nullptr if the sensor
/// does not contain an NAVSAT sensor.
/// \return Pointer to the sensor's NAVSAT, or nullptr if the sensor
/// is not an NAVSAT.
/// \sa SensorType Type() const
public: const SatNav *SatNavSensor() const;

public: const NavSat *NavSatSensor() const;

/// \brief Set the IMU sensor.
/// \param[in] _imu The IMU sensor.
Expand Down
40 changes: 40 additions & 0 deletions sdf/1.7/navsat.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<element name="navsat" required="0">
<description>These elements are specific to the NAVSAT sensor.</description>

<element name="position_sensing" required="0">
<description>
Parameters related to NAVSAT position measurement.
</description>
<element name="horizontal" required="0">
<description>
Noise parameters for horizontal position measurement, in units of meters.
</description>
<include filename="noise.sdf" required="0"/>
</element>
<element name="vertical" required="0">
<description>
Noise parameters for vertical position measurement, in units of meters.
</description>
<include filename="noise.sdf" required="0"/>
</element>
</element>

<element name="velocity_sensing" required="0">
<description>
Parameters related to NAVSAT position measurement.
</description>
<element name="horizontal" required="0">
<description>
Noise parameters for horizontal velocity measurement, in units of meters/second.
</description>
<include filename="noise.sdf" required="0"/>
</element>
<element name="vertical" required="0">
<description>
Noise parameters for vertical velocity measurement, in units of meters/second.
</description>
<include filename="noise.sdf" required="0"/>
</element>
</element>

</element>
3 changes: 2 additions & 1 deletion sdf/1.7/sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
logical_camera,
magnetometer,
multicamera,
navsat,
ray,
rfid,
rfidtag,
Expand All @@ -30,7 +31,7 @@
thermal_camera, thermal,
wireless_receiver, and
wireless_transmitter.
The "ray" and "gpu_ray" types are equivalent to "lidar" and "gpu_lidar", respectively. It is preferred to use "lidar" and "gpu_lidar" since "ray" and "gpu_ray" will be deprecated. The "ray" and "gpu_ray" types are maintained for legacy support.
The "ray", "gpu_ray", and "gps" types are equivalent to "lidar", "gpu_lidar", and "navsat", respectively. It is preferred to use "lidar", "gpu_lidar", and "navsat" since "ray", "gpu_ray", and "gps" will be deprecated. The "ray", "gpu_ray", and "gps" types are maintained for legacy support.
</description>
</attribute>

Expand Down
4 changes: 2 additions & 2 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ set (sources
FrameSemantics.cc
Filesystem.cc
Geometry.cc
SatNav.cc
Gui.cc
Heightmap.cc
ign.cc
Expand All @@ -41,6 +40,7 @@ set (sources
Material.cc
Mesh.cc
Model.cc
NavSat.cc
Noise.cc
parser.cc
parser_urdf.cc
Expand Down Expand Up @@ -98,7 +98,6 @@ if (BUILD_SDF_TEST)
Frame_TEST.cc
Filesystem_TEST.cc
Geometry_TEST.cc
SatNav_TEST.cc
Gui_TEST.cc
Heightmap_TEST.cc
Imu_TEST.cc
Expand All @@ -111,6 +110,7 @@ if (BUILD_SDF_TEST)
Material_TEST.cc
Mesh_TEST.cc
Model_TEST.cc
NavSat_TEST.cc
Noise_TEST.cc
Param_TEST.cc
parser_TEST.cc
Expand Down
Loading

0 comments on commit b128c9c

Please sign in to comment.