Gazebo Rendering

API Reference

3.7.2
gz/rendering/MoveToHelper.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2021 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 GZ_RENDERING_MOVETOHELPER_HH_
18 #define GZ_RENDERING_MOVETOHELPER_HH_
19 
20 #include <memory>
21 
22 #include <gz/common/Animation.hh>
23 #include <gz/common/KeyFrame.hh>
24 
25 #include <gz/math/Box.hh>
26 #include <gz/math/Pose3.hh>
27 
28 #include "gz/rendering/Camera.hh"
29 
30 namespace ignition
31 {
32  namespace rendering
33  {
34  // Inline bracket to help doxygen filtering.
35  inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
36  // forward declaration
37  class MoveToHelperPrivate;
38 
41  class IGNITION_RENDERING_VISIBLE MoveToHelper
42  {
43  public: MoveToHelper();
44 
45  public: ~MoveToHelper();
46 
53  public: void MoveTo(const rendering::CameraPtr &_camera,
54  const rendering::NodePtr &_target, double _duration,
55  std::function<void()> _onAnimationComplete);
56 
63  public: void MoveTo(const rendering::CameraPtr &_camera,
64  const math::Pose3d &_target, double _duration,
65  std::function<void()> _onAnimationComplete);
66 
75  public: void LookDirection(const rendering::CameraPtr &_camera,
76  const math::Vector3d &_direction, const math::Vector3d &_lookAt,
77  double _duration, std::function<void()> _onAnimationComplete);
78 
81  public: void AddTime(double _time);
82 
86  public: bool Idle() const;
87 
90  public: void SetInitCameraPose(const math::Pose3d &_pose);
91 
93  private: std::unique_ptr<MoveToHelperPrivate> dataPtr;
95  };
96  }
97  }
98 }
99 #endif
STL class.
#define IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
void LookDirection(const rendering::CameraPtr &_camera, const math::Vector3d &_direction, const math::Vector3d &_lookAt, double _duration, std::function< void()> _onAnimationComplete)
Move the camera to look at the specified target param[in] _camera Camera to be moved param[in] _direc...
void MoveTo(const rendering::CameraPtr &_camera, const rendering::NodePtr &_target, double _duration, std::function< void()> _onAnimationComplete)
Move the camera to look at the specified target param[in] _camera Camera to be moved param[in] _targe...
void AddTime(double _time)
Add time to the animation.
bool Idle() const
Get whether the move to helper is idle, i.e. no animation is being executed.
void SetInitCameraPose(const math::Pose3d &_pose)
Set the initial camera pose param[in] _pose The init pose of the camera.
Helper class for animating a user camera to move to a target entity.
Definition: gz/rendering/MoveToHelper.hh:41
#define IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING