Skip to content

Commit

Permalink
Distortion Camera Sensor (#192)
Browse files Browse the repository at this point in the history
Signed-off-by: William Lew <WilliamMilesLew@gmail.com>
Co-authored-by: Ian Chen <ichen@osrfoundation.org>
  • Loading branch information
WilliamLewww and iche033 authored Mar 29, 2022
1 parent 373e971 commit 8cadf18
Show file tree
Hide file tree
Showing 16 changed files with 1,056 additions and 5 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ if ((NOT ${CMAKE_VERSION} VERSION_LESS 3.11) AND (NOT OpenGL_GL_PREFERENCE))
set(OpenGL_GL_PREFERENCE "GLVND")
endif()

ign_find_package(ignition-rendering6 REQUIRED OPTIONAL_COMPONENTS ogre ogre2)
ign_find_package(ignition-rendering6 REQUIRED VERSION 6.2 OPTIONAL_COMPONENTS ogre ogre2)
set(IGN_RENDERING_VER ${ignition-rendering6_VERSION_MAJOR})

if (TARGET ignition-rendering${IGN_RENDERING_VER}::ogre)
Expand Down
87 changes: 87 additions & 0 deletions include/ignition/sensors/BrownDistortionModel.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
/*
* 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 IGNITION_SENSORS_BROWNDISTORTIONMODEL_HH_
#define IGNITION_SENSORS_BROWNDISTORTIONMODEL_HH_

#include <sdf/sdf.hh>

#include "ignition/sensors/Distortion.hh"
#include "ignition/sensors/Export.hh"
#include "ignition/sensors/config.hh"
#include "ignition/utils/ImplPtr.hh"

namespace ignition
{
namespace sensors
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_SENSORS_VERSION_NAMESPACE {
//
// Forward declarations
class BrownDistortionModelPrivate;

/** \class BrownDistortionModel BrownDistortionModel.hh \
ignition/sensors/BrownDistortionModel.hh
**/
/// \brief Brown Distortion Model class
class IGNITION_SENSORS_VISIBLE BrownDistortionModel : public Distortion
{
/// \brief Constructor.
public: BrownDistortionModel();

/// \brief Destructor.
public: virtual ~BrownDistortionModel();

// Documentation inherited.
public: virtual void Load(const sdf::Camera &_sdf) override;

/// \brief Get the radial distortion coefficient k1.
/// \return Distortion coefficient k1.
public: double K1() const;

/// \brief Get the radial distortion coefficient k2.
/// \return Distortion coefficient k2.
public: double K2() const;

/// \brief Get the radial distortion coefficient k3.
/// \return Distortion coefficient k3.
public: double K3() const;

/// \brief Get the tangential distortion coefficient p1.
/// \return Distortion coefficient p1.
public: double P1() const;

/// \brief Get the tangential distortion coefficient p2.
/// \return Distortion coefficient p2.
public: double P2() const;

/// \brief Get the distortion center.
/// \return Distortion center.
public: math::Vector2d Center() const;

/// Documentation inherited
public: virtual void Print(std::ostream &_out) const override;

/// \brief Private data pointer.
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
}

#endif
108 changes: 108 additions & 0 deletions include/ignition/sensors/Distortion.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
/*
* 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 IGNITION_SENSORS_DISTORTION_HH_
#define IGNITION_SENSORS_DISTORTION_HH_

#include <functional>
#include <string>
#include <vector>

#include <ignition/sensors/Export.hh>
#include <ignition/sensors/SensorTypes.hh>
#include <ignition/sensors/config.hh>
#include <ignition/utils/ImplPtr.hh>

#include <sdf/sdf.hh>

namespace ignition
{
namespace sensors
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_SENSORS_VERSION_NAMESPACE {
// Forward declarations
class DistortionPrivate;

/// \class DistortionFactory Distortion.hh ignition/sensors/Distortion.hh
/// \brief Use this distortion manager for creating and loading distortion
/// models.
class IGNITION_SENSORS_VISIBLE DistortionFactory
{
/// \brief Load a distortion model based on the input sdf parameters and
/// sensor type.
/// \param[in] _sdf Distortion sdf parameters.
/// \param[in] _sensorType Type of sensor. This is currently used to
/// distinguish between image and non image sensors in order to create
/// the appropriate distortion model.
/// \return Pointer to the distortion model created.
public: static DistortionPtr NewDistortionModel(sdf::ElementPtr _sdf,
const std::string &_sensorType = "");

/// \brief Load a distortion model based on the input sdf parameters and
/// sensor type.
/// \param[in] _sdf Distortion sdf parameters.
/// \param[in] _sensorType Type of sensor. This is currently used to
/// distinguish between image and non image sensors in order to create
/// the appropriate distortion model.
/// \return Pointer to the distortion model created.
public: static DistortionPtr NewDistortionModel(
const sdf::Camera &_sdf,
const std::string &_sensorType = "");
};

/// \brief Which distortion types we support
enum class IGNITION_SENSORS_VISIBLE DistortionType : int
{
NONE = 0,
CUSTOM = 1,
BROWN = 2
};

/// \class Distortion Distortion.hh ignition/sensors/Distortion.hh
/// \brief Distortion models for sensor output signals.
class IGNITION_SENSORS_VISIBLE Distortion
{
/// \brief Constructor. This should not be called directly unless creating
/// an empty distortion model. Use DistortionFactory::NewDistortionModel
/// to instantiate a new distortion model.
/// \param[in] _type Type of distortion model.
/// \sa DistortionFactory::NewDistortionModel
public: explicit Distortion(DistortionType _type);

/// \brief Destructor.
public: virtual ~Distortion();

/// \brief Load distortion parameters from sdf.
/// \param[in] _sdf SDF Distortion DOM object.
public: virtual void Load(const sdf::Camera &_sdf);

/// \brief Accessor for DistortionType.
/// \return Type of distortion currently in use.
public: DistortionType Type() const;

/// \brief Output information about the distortion model.
/// \param[in] _out Output stream
public: virtual void Print(std::ostream &_out) const;

/// \brief Private data pointer
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
}
#endif
76 changes: 76 additions & 0 deletions include/ignition/sensors/ImageBrownDistortionModel.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
/*
* 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 IGNITION_SENSORS_IMAGEBROWNDISTORTIONMODEL_HH_
#define IGNITION_SENSORS_IMAGEBROWNDISTORTIONMODEL_HH_

#include <sdf/sdf.hh>

// TODO(WilliamLewww): Remove these pragmas once ign-rendering is disabling the
// warnings
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4251)
#endif
#include <ignition/rendering/Camera.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include "ignition/sensors/config.hh"
#include "ignition/sensors/BrownDistortionModel.hh"
#include "ignition/sensors/rendering/Export.hh"

namespace ignition
{
namespace sensors
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_SENSORS_VERSION_NAMESPACE {
// Forward declarations
class ImageBrownDistortionModelPrivate;

/** \class ImageBrownDistortionModel ImageBrownDistortionModel.hh \
ignition/sensors/ImageBrownDistortionModel.hh
**/
/// \brief Distortion Model class for image sensors
class IGNITION_SENSORS_RENDERING_VISIBLE ImageBrownDistortionModel :
public BrownDistortionModel
{
/// \brief Constructor.
public: ImageBrownDistortionModel();

/// \brief Destructor.
public: virtual ~ImageBrownDistortionModel();

// Documentation inherited.
public: virtual void Load(const sdf::Camera &_sdf) override;

// Documentation inherited.
public: virtual void SetCamera(rendering::CameraPtr _camera);

/// Documentation inherited
public: virtual void Print(std::ostream &_out) const override;

/// \brief Private data pointer.
private: ImageBrownDistortionModelPrivate *dataPtr = nullptr;
};
}
}
}

#endif
67 changes: 67 additions & 0 deletions include/ignition/sensors/ImageDistortion.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*
* 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 IGNITION_SENSORS_IMAGEDISTORTION_HH_
#define IGNITION_SENSORS_IMAGEDISTORTION_HH_

#include <string>

#include <sdf/sdf.hh>

#include "ignition/sensors/config.hh"
#include "ignition/sensors/SensorTypes.hh"
#include "ignition/sensors/rendering/Export.hh"

namespace ignition
{
namespace sensors
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_SENSORS_VERSION_NAMESPACE {
// Forward declarations
class DistortionPrivate;

/// \class ImageDistortionFactory ImageDistortion.hh
/// ignition/sensors/ImageDistortion.hh
/// \brief Use this distortion manager for creating and loading distortion
/// models.
class IGNITION_SENSORS_RENDERING_VISIBLE ImageDistortionFactory
{
/// \brief Load a distortion model based on the input sdf parameters and
/// sensor type.
/// \param[in] _sdf Distortion sdf parameters.
/// \param[in] _sensorType Type of sensor. This is currently used to
/// distinguish between image and non image sensors in order to create
/// the appropriate distortion model.
/// \return Pointer to the distortion model created.
public: static DistortionPtr NewDistortionModel(sdf::ElementPtr _sdf,
const std::string &_sensorType = "");

/// \brief Load a distortion model based on the input sdf parameters and
/// sensor type.
/// \param[in] _sdf Distortion sdf parameters.
/// \param[in] _sensorType Type of sensor. This is currently used to
/// distinguish between image and non image sensors in order to create
/// the appropriate distortion model.
/// \return Pointer to the distortion model created.
public: static DistortionPtr NewDistortionModel(const sdf::Camera &_sdf,
const std::string &_sensorType = "");
};
}
}
}
#endif
1 change: 0 additions & 1 deletion include/ignition/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -229,5 +229,4 @@ namespace ignition
}
}
}

#endif
Loading

0 comments on commit 8cadf18

Please sign in to comment.