Skip to content

Commit

Permalink
Camera: add camera zoom plugin
Browse files Browse the repository at this point in the history
- fix gimbal test world
- add example world for gimbal and camera
- add gimbal_small_3d
- update command topic names in gimbal test world
- update quote style in gimbal_small_3d
- rename zoom plugin and attach to sensor
- resolve parent model and subscribe to zoom command
- implement zoom for standard camera
- remove whitespace for linter
- provide alternative to gz::sim::Sensor
- handle RenderTeardown event to exit cleanly
- find package gz-common5
- use degrees for pose in gimbal world
- format plugin attributes.

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
  • Loading branch information
srmainwaring committed Jan 14, 2024
1 parent 894f455 commit 36f3048
Show file tree
Hide file tree
Showing 11 changed files with 3,278 additions and 30 deletions.
26 changes: 26 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,12 @@ if("$ENV{GZ_VERSION}" STREQUAL "harmonic")
find_package(gz-cmake3 REQUIRED)
set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR})

gz_find_package(gz-common5 REQUIRED)
set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR})

gz_find_package(gz-rendering8 REQUIRED)
set(GZ_RENDERING_VER ${gz-rendering8_VERSION_MAJOR})

gz_find_package(gz-sim8 REQUIRED)
set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR})

Expand All @@ -31,6 +37,12 @@ elseif("$ENV{GZ_VERSION}" STREQUAL "garden" OR NOT DEFINED "ENV{GZ_VERSION}")
find_package(gz-cmake3 REQUIRED)
set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR})

gz_find_package(gz-common5 REQUIRED)
set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR})

gz_find_package(gz-rendering7 REQUIRED)
set(GZ_RENDERING_VER ${gz-rendering7_VERSION_MAJOR})

gz_find_package(gz-sim7 REQUIRED)
set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR})

Expand Down Expand Up @@ -70,13 +82,27 @@ target_link_libraries(ParachutePlugin PRIVATE
gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
)

add_library(CameraZoomPlugin
SHARED
src/CameraZoomPlugin.cc
)
target_include_directories(CameraZoomPlugin PRIVATE
include
)
target_link_libraries(CameraZoomPlugin PRIVATE
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
gz-rendering${GZ_RENDERING_VER}::gz-rendering${GZ_RENDERING_VER}
gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
)

# --------------------------------------------------------------------------- #
# Install.

install(
TARGETS
ArduPilotPlugin
ParachutePlugin
CameraZoomPlugin
DESTINATION lib/${PROJECT_NAME}
)

Expand Down
67 changes: 67 additions & 0 deletions include/CameraZoomPlugin.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*
Copyright (C) 2023 ArduPilot.org
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef CAMERAZOOMPLUGIN_HH_
#define CAMERAZOOMPLUGIN_HH_

#include <memory>

#include <gz/sim/System.hh>

namespace gz {
namespace sim {
inline namespace GZ_SIM_VERSION_NAMESPACE {
namespace systems {

/// \brief Camera zoom plugin.
class CameraZoomPlugin :
public System,
public ISystemConfigure,
public ISystemPreUpdate,
public ISystemPostUpdate
{
/// \brief Destructor
public: virtual ~CameraZoomPlugin();

/// \brief Constructor
public: CameraZoomPlugin();

// Documentation inherited
public: void PreUpdate(const gz::sim::UpdateInfo &_info,
gz::sim::EntityComponentManager &_ecm) final;

// Documentation inherited
public: void PostUpdate(const gz::sim::UpdateInfo &_info,
const gz::sim::EntityComponentManager &_ecm) final;

// Documentation inherited
public: void Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm,
EventManager &) final;

/// \internal
/// \brief Private implementation
private: class Impl;
private: std::unique_ptr<Impl> impl;
};

} // namespace systems
}
} // namespace sim
} // namespace gz

#endif // CAMERAZOOMPLUGIN_HH_

0 comments on commit 36f3048

Please sign in to comment.