Helper class for animating a user camera to move to a target entity. More...
#include <MoveToHelper.hh>
Public Member Functions | |
| MoveToHelper () | |
| ~MoveToHelper () | |
| 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 | 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] _direction The pose to assume relative to the entit(y/ies), (0, 0, 0) indicates to return the camera back to the home pose originally loaded in from the sdf. param[in] _duration Duration of the move to animation, in seconds. param[in] _onAnimationComplete Callback function when animation is complete. | |
| void | MoveTo (const rendering::CameraPtr &_camera, const math::Pose3d &_target, double _duration, std::function< void()> _onAnimationComplete) |
| Move the camera to the specified pose. param[in] _camera Camera to be moved param[in] _target Pose to move to param[in] _duration Duration of the move to animation, in seconds. param[in] _onAnimationComplete Callback function when animation is complete. | |
| 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] _target Target to look at param[in] _duration Duration of the move to animation, in seconds. param[in] _onAnimationComplete Callback function when animation is complete. | |
| void | SetInitCameraPose (const math::Pose3d &_pose) |
| Set the initial camera pose param[in] _pose The init pose of the camera. | |
Detailed Description
Helper class for animating a user camera to move to a target entity.
Constructor & Destructor Documentation
◆ MoveToHelper()
| MoveToHelper | ( | ) |
◆ ~MoveToHelper()
| ~MoveToHelper | ( | ) |
Member Function Documentation
◆ AddTime()
| void AddTime | ( | double | _time | ) |
Add time to the animation.
- Parameters
-
[in] _time Time to add in seconds
◆ Idle()
| bool Idle | ( | ) | const |
Get whether the move to helper is idle, i.e. no animation is being executed.
- Returns
- True if idle, false otherwise
◆ LookDirection()
| 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] _direction The pose to assume relative to the entit(y/ies), (0, 0, 0) indicates to return the camera back to the home pose originally loaded in from the sdf. param[in] _duration Duration of the move to animation, in seconds. param[in] _onAnimationComplete Callback function when animation is complete.
◆ MoveTo() [1/2]
| void MoveTo | ( | const rendering::CameraPtr & | _camera, |
| const math::Pose3d & | _target, | ||
| double | _duration, | ||
| std::function< void()> | _onAnimationComplete | ||
| ) |
Move the camera to the specified pose. param[in] _camera Camera to be moved param[in] _target Pose to move to param[in] _duration Duration of the move to animation, in seconds. param[in] _onAnimationComplete Callback function when animation is complete.
◆ MoveTo() [2/2]
| 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] _target Target to look at param[in] _duration Duration of the move to animation, in seconds. param[in] _onAnimationComplete Callback function when animation is complete.
◆ SetInitCameraPose()
| void SetInitCameraPose | ( | const math::Pose3d & | _pose | ) |
Set the initial camera pose param[in] _pose The init pose of the camera.
The documentation for this class was generated from the following file: