Classes | Public Types | Public Member Functions | Protected Slots | Protected Member Functions | Protected Attributes | List of all members
rviz_animated_view_controller::AnimatedViewController Class Reference

An un-constrained "flying" camera, specified by an eye point, focus point, and up vector. More...

#include <rviz_animated_view_controller.h>

Inheritance diagram for rviz_animated_view_controller::AnimatedViewController:
Inheritance graph
[legend]

Classes

struct  OgreCameraMovement
 

Public Types

enum  { TRANSITION_LINEAR = 0, TRANSITION_SPHERICAL }
 
typedef boost::circular_buffer< OgreCameraMovementBufferCamMovements
 

Public Member Functions

 AnimatedViewController ()
 
virtual void handleMouseEvent (rviz::ViewportMouseEvent &evt)
 
void initializePublishers ()
 
void initializeSubscribers ()
 
virtual void lookAt (const Ogre::Vector3 &point)
 Calls beginNewTransition() to move the focus point to the point provided, assumed to be in the Rviz Fixed Frame. More...
 
virtual void mimic (ViewController *source_view)
 Configure the settings of this view controller to give, as much as possible, a similar view as that given by the source_view. More...
 
void move_eye (float x, float y, float z)
 Applies a translation to only the eye point. More...
 
void move_focus_and_eye (float x, float y, float z)
 Applies a translation to the focus and eye points. More...
 
void moveEyeWithFocusTo (const Ogre::Vector3 &point)
 Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed. More...
 
virtual void onActivate ()
 called by activate(). More...
 
virtual void onInitialize ()
 Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ are set. More...
 
void orbitCameraTo (const Ogre::Vector3 &point)
 Calls beginNewTransition() with the focus point fixed, moving the eye to the point given. More...
 
void publishCameraPose ()
 Publishes the current camera pose. More...
 
virtual void reset ()
 Resets the camera parameters to a sane value. More...
 
virtual void transitionFrom (ViewController *previous_view)
 Called by ViewManager when this ViewController is being made current. More...
 
void yaw_pitch_roll (float yaw, float pitch, float roll)
 Applies a body-fixed-axes sequence of rotations; only accurate for small angles. More...
 
virtual ~AnimatedViewController ()
 
- Public Member Functions inherited from rviz::ViewController
void activate ()
 
void emitConfigChanged ()
 
Ogre::Camera * getCamera () const
 
virtual QString getClassId () const
 
virtual QCursor getCursor ()
 
QVariant getViewData (int column, int role) const override
 
Qt::ItemFlags getViewFlags (int column) const override
 
virtual void handleKeyEvent (QKeyEvent *event, RenderPanel *panel)
 
void initialize (DisplayContext *context)
 
bool isActive () const
 
void load (const Config &config) override
 
void lookAt (float x, float y, float z)
 
void save (Config config) const override
 
virtual void setClassId (const QString &class_id)
 
 ViewController ()
 
 ~ViewController () override
 
- Public Member Functions inherited from rviz::Property
virtual void addChild (Property *child, int index=-1)
 
PropertychildAt (int index) const
 
virtual PropertychildAtUnchecked (int index) const
 
virtual void collapse ()
 
bool contains (Property *possible_child) const
 
virtual QWidget * createEditor (QWidget *parent, const QStyleOptionViewItem &option)
 
virtual void expand ()
 
virtual QString getDescription () const
 
virtual bool getDisableChildren ()
 
virtual bool getHidden () const
 
virtual QIcon getIcon () const
 
PropertyTreeModelgetModel () const
 
virtual QString getName () const
 
std::string getNameStd () const
 
PropertygetParent () const
 
virtual bool getReadOnly () const
 
virtual QVariant getValue () const
 
void hide ()
 
bool isAncestorOf (Property *possible_child) const
 
virtual void moveChild (int from_index, int to_index)
 
virtual int numChildren () const
 
virtual bool paint (QPainter *painter, const QStyleOptionViewItem &option) const
 
 Property (const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
 
virtual void removeChildren (int start_index=0, int count=-1)
 
int rowNumberInParent () const
 
virtual void setDescription (const QString &description)
 
virtual void setHidden (bool hidden)
 
virtual void setIcon (const QIcon &icon)
 
void setModel (PropertyTreeModel *model)
 
virtual void setName (const QString &name)
 
void setParent (Property *new_parent)
 
virtual void setReadOnly (bool read_only)
 
void setShouldBeSaved (bool save)
 
virtual bool setValue (const QVariant &new_value)
 
bool shouldBeSaved () const
 
void show ()
 
virtual PropertysubProp (const QString &sub_name)
 
PropertytakeChild (Property *child)
 
virtual PropertytakeChildAt (int index)
 
 ~Property () override
 

Protected Slots

virtual void onDistancePropertyChanged ()
 Called when distance property is changed; computes new eye position. More...
 
virtual void onEyePropertyChanged ()
 Called when eye property is changed; computes new distance. More...
 
virtual void onFocusPropertyChanged ()
 Called focus property is changed; computes new distance. More...
 
virtual void onUpPropertyChanged ()
 Called when up vector property is changed (does nothing for now...). More...
 
virtual void updateAttachedFrame ()
 Called when Target Frame property changes while view is active. Purpose is to change values in the view controller (like a position offset) such that the actual viewpoint does not change. Calls updateTargetSceneNode() and onTargetFrameChanged(). More...
 
void updateTopics ()
 

Protected Member Functions

Ogre::Vector3 attachedLocalToFixedFrame (const Ogre::Vector3 &v)
 
void beginNewTransition (const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up, ros::Duration transition_duration, uint8_t interpolation_speed=view_controller_msgs::CameraMovement::WAVE)
 Begins a camera movement animation to the given goal point. More...
 
void cameraPlacementCallback (const view_controller_msgs::CameraPlacementConstPtr &cp_ptr)
 
void cameraTrajectoryCallback (const view_controller_msgs::CameraTrajectoryConstPtr &ct_ptr)
 Initiate camera motion from incoming CameraTrajectory. More...
 
void cancelTransition ()
 Cancels any currently active camera movement. More...
 
float computeRelativeProgressInSpace (double relative_progress_in_time, uint8_t interpolation_speed)
 Convert the relative progress in time to the corresponding relative progress in space wrt. the interpolation speed profile. More...
 
double computeRelativeProgressInTime (const ros::Duration &transition_duration)
 Computes the fraction of time we already used for the current movement. More...
 
void connectPositionProperties ()
 Convenience function; connects the signals/slots for position properties. More...
 
void convertImage (std::shared_ptr< Ogre::PixelBox > input_image, sensor_msgs::ImagePtr output_image)
 
void disconnectPositionProperties ()
 Convenience function; disconnects the signals/slots for position properties. More...
 
Ogre::Vector3 fixedFrameToAttachedLocal (const Ogre::Vector3 &v)
 
float getDistanceFromCameraToFocalPoint ()
 Return the distance between camera and focal point. More...
 
Ogre::Quaternion getOrientation ()
 Return a Quaternion. More...
 
void getViewImage (std::shared_ptr< Ogre::PixelBox > &pixel_box)
 Get the current image rviz is showing as an Ogre::PixelBox. More...
 
bool isMovementAvailable ()
 Returns true if buffer contains at least one start and end pose needed for one movement. More...
 
virtual void onAttachedFrameChanged (const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation)
 Override to implement the change in properties which nullifies the change in attached frame. More...
 
void pauseAnimationCallback (const std_msgs::Duration::ConstPtr &pause_duration_msg)
 Sets the duration the rendering has to wait for during the next update cycle. More...
 
void pauseAnimationOnRequest ()
 Pauses the animation if pause_animation_duration_ is larger than zero. More...
 
void prepareNextMovement (const ros::Duration &previous_transition_duration)
 Updates the transition_start_time_ and resets the rendered_frames_counter_ for next movement. More...
 
void publishViewImage ()
 Publish the rendered image that is visible to the user in rviz. More...
 
void setPropertiesFromCamera (Ogre::Camera *source_camera)
 
void transformCameraToAttachedFrame (geometry_msgs::PointStamped &eye, geometry_msgs::PointStamped &focus, geometry_msgs::Vector3Stamped &up)
 Transforms the camera defined by eye, focus and up into the attached frame. More...
 
virtual void update (float dt, float ros_dt)
 Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to run repeatedly. More...
 
void updateAttachedSceneNode ()
 Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame property. More...
 
void updateCamera ()
 Updates the Ogre camera properties from the view controller properties. More...
 
void updateWindowSizeProperties ()
 
- Protected Member Functions inherited from rviz::ViewController
void setCursor (CursorType cursor_type)
 
void setCursor (QCursor cursor)
 
void setStatus (const QString &message)
 
- Protected Member Functions inherited from rviz::Property
void loadValue (const Config &config)
 

Protected Attributes

bool animate_
 
rviz::TfFramePropertyattached_frame_property_
 
Ogre::SceneNode * attached_scene_node_
 
BufferCamMovements cam_movements_buffer_
 
rviz::RosTopicPropertycamera_placement_topic_property_
 
rviz::RosTopicPropertycamera_trajectory_topic_property_
 
image_transport::Publisher camera_view_image_publisher_
 
ros::Publisher current_camera_pose_publisher_
 
rviz::FloatPropertydefault_transition_time_property_
 A default time for any animation requests. More...
 
rviz::FloatPropertydistance_property_
 The camera's distance from the focal point. More...
 
bool dragging_
 A flag indicating the dragging state of the mouse. More...
 
rviz::VectorPropertyeye_point_property_
 The position of the camera. More...
 
ros::Publisher finished_animation_publisher_
 
rviz::BoolPropertyfixed_up_property_
 If True, "up" is fixed to ... up. More...
 
rviz::Shapefocal_shape_
 A small ellipsoid to show the focus point. More...
 
rviz::VectorPropertyfocus_point_property_
 The point around which the camera "orbits". More...
 
QCursor interaction_disabled_cursor_
 A cursor for indicating mouse interaction is disabled. More...
 
rviz::EditableEnumPropertyinteraction_mode_property_
 Select between Orbit or FPS control style. More...
 
rviz::BoolPropertymouse_enabled_property_
 If True, most user changes to camera state are disabled. More...
 
ros::NodeHandle nh_
 
ros::WallDuration pause_animation_duration_
 
ros::Subscriber pause_animation_duration_subscriber_
 
ros::Subscriber placement_subscriber_
 
rviz::BoolPropertypublish_view_images_property_
 If True, the camera view is published as images. More...
 
Ogre::Quaternion reference_orientation_
 Used to store the orientation of the attached frame relative to <Fixed Frame> More...
 
Ogre::Vector3 reference_position_
 Used to store the position of the attached frame relative to <Fixed Frame> More...
 
bool render_frame_by_frame_
 
int rendered_frames_counter_
 
int target_fps_
 
ros::Subscriber trajectory_subscriber_
 
ros::WallTime transition_start_time_
 
rviz::VectorPropertyup_vector_property_
 The up vector for the camera. More...
 
rviz::FloatPropertywindow_height_property_
 The height of the rviz visualization window in pixels. More...
 
rviz::FloatPropertywindow_width_property_
 The width of the rviz visualization window in pixels. More...
 
- Protected Attributes inherited from rviz::ViewController
Ogre::Camera * camera_
 
DisplayContextcontext_
 
 Crosshair
 
QCursor cursor_
 
 Default
 
BoolPropertyinvert_z_
 
bool is_active_
 
 MoveXY
 
 MoveZ
 
FloatPropertynear_clip_property_
 
 Rotate2D
 
 Rotate3D
 
BoolPropertystereo_enable_
 
FloatPropertystereo_eye_separation_
 
BoolPropertystereo_eye_swap_
 
FloatPropertystereo_focal_distance_
 
 Zoom
 
- Protected Attributes inherited from rviz::Property
bool child_indexes_valid_
 
QIcon icon_
 
PropertyTreeModelmodel_
 
QVariant value_
 

Additional Inherited Members

- Signals inherited from rviz::ViewController
void configChanged ()
 
- Signals inherited from rviz::Property
void aboutToChange ()
 
void changed ()
 
void childListChanged (Property *this_property)
 
- Static Public Member Functions inherited from rviz::ViewController
static QString formatClassId (const QString &class_id)
 
- Protected Types inherited from rviz::ViewController
enum  CursorType
 

Detailed Description

An un-constrained "flying" camera, specified by an eye point, focus point, and up vector.

Definition at line 77 of file rviz_animated_view_controller.h.

Member Typedef Documentation

◆ BufferCamMovements

Definition at line 110 of file rviz_animated_view_controller.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
TRANSITION_LINEAR 
TRANSITION_SPHERICAL 

Definition at line 82 of file rviz_animated_view_controller.h.

Constructor & Destructor Documentation

◆ AnimatedViewController()

rviz_animated_view_controller::AnimatedViewController::AnimatedViewController ( )

Definition at line 97 of file rviz_animated_view_controller.cpp.

◆ ~AnimatedViewController()

rviz_animated_view_controller::AnimatedViewController::~AnimatedViewController ( )
virtual

Definition at line 159 of file rviz_animated_view_controller.cpp.

Member Function Documentation

◆ attachedLocalToFixedFrame()

Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::attachedLocalToFixedFrame ( const Ogre::Vector3 &  v)
inlineprotected

Definition at line 326 of file rviz_animated_view_controller.h.

◆ beginNewTransition()

void rviz_animated_view_controller::AnimatedViewController::beginNewTransition ( const Ogre::Vector3 &  eye,
const Ogre::Vector3 &  focus,
const Ogre::Vector3 &  up,
ros::Duration  transition_duration,
uint8_t  interpolation_speed = view_controller_msgs::CameraMovement::WAVE 
)
protected

Begins a camera movement animation to the given goal point.

Parameters
[in]eyegoal position of camera.
[in]focusgoal focus point of camera.
[in]upgoal vector of camera pointing up.
[in]transition_durationduration needed for transition.
[in]interpolation_speedthe interpolation speed profile.

Definition at line 570 of file rviz_animated_view_controller.cpp.

◆ cameraPlacementCallback()

void rviz_animated_view_controller::AnimatedViewController::cameraPlacementCallback ( const view_controller_msgs::CameraPlacementConstPtr &  cp_ptr)
protected

Definition at line 619 of file rviz_animated_view_controller.cpp.

◆ cameraTrajectoryCallback()

void rviz_animated_view_controller::AnimatedViewController::cameraTrajectoryCallback ( const view_controller_msgs::CameraTrajectoryConstPtr &  ct_ptr)
protected

Initiate camera motion from incoming CameraTrajectory.

Parameters
[in]ct_ptrincoming CameraTrajectory msg.

Definition at line 656 of file rviz_animated_view_controller.cpp.

◆ cancelTransition()

void rviz_animated_view_controller::AnimatedViewController::cancelTransition ( )
protected

Cancels any currently active camera movement.

Definition at line 603 of file rviz_animated_view_controller.cpp.

◆ computeRelativeProgressInSpace()

float rviz_animated_view_controller::AnimatedViewController::computeRelativeProgressInSpace ( double  relative_progress_in_time,
uint8_t  interpolation_speed 
)
protected

Convert the relative progress in time to the corresponding relative progress in space wrt. the interpolation speed profile.

Example: The camera has to move from point A to point B in a duration D. The camera should accelerate slowly and arrive at full speed - RISING speed profile. At exactly half of the duration D the camera wouldn't be right in the middle between A and B, because it needed time to accelerate. This method converts the relative progress in time specified by a number between zero and one, to the relative progress in space as a number between zero and one.

Interpolation speed profiles: RISING = 0 # Speed of the camera rises smoothly - resembles the first quarter of a sinus wave. DECLINING = 1 # Speed of the camera declines smoothly - resembles the second quarter of a sinus wave. FULL = 2 # Camera is always at full speed - depending on transition_duration. WAVE = 3 # RISING and DECLINING concatenated in one movement.

@params[in] relative_progress_in_time the relative progress in time, between 0 and 1. @params[in] interpolation_speed speed profile.

Returns
relative progress in space as a float between 0 and 1.

Definition at line 852 of file rviz_animated_view_controller.cpp.

◆ computeRelativeProgressInTime()

double rviz_animated_view_controller::AnimatedViewController::computeRelativeProgressInTime ( const ros::Duration transition_duration)
protected

Computes the fraction of time we already used for the current movement.

If we are rendering frame by frame we compute the passed time counting the frames we already rendered. Dividing by the total number of frames we want to render for the current transition results in the progress.

@params[in] transition_duration total duration of the current movement.

Returns
Relative progress in time as a float between 0 and 1.

Definition at line 836 of file rviz_animated_view_controller.cpp.

◆ connectPositionProperties()

void rviz_animated_view_controller::AnimatedViewController::connectPositionProperties ( )
protected

Convenience function; connects the signals/slots for position properties.

Definition at line 239 of file rviz_animated_view_controller.cpp.

◆ convertImage()

void rviz_animated_view_controller::AnimatedViewController::convertImage ( std::shared_ptr< Ogre::PixelBox >  input_image,
sensor_msgs::ImagePtr  output_image 
)
protected

Definition at line 900 of file rviz_animated_view_controller.cpp.

◆ disconnectPositionProperties()

void rviz_animated_view_controller::AnimatedViewController::disconnectPositionProperties ( )
protected

Convenience function; disconnects the signals/slots for position properties.

Definition at line 247 of file rviz_animated_view_controller.cpp.

◆ fixedFrameToAttachedLocal()

Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::fixedFrameToAttachedLocal ( const Ogre::Vector3 &  v)
inlineprotected

Definition at line 325 of file rviz_animated_view_controller.h.

◆ getDistanceFromCameraToFocalPoint()

float rviz_animated_view_controller::AnimatedViewController::getDistanceFromCameraToFocalPoint ( )
protected

Return the distance between camera and focal point.

Definition at line 338 of file rviz_animated_view_controller.cpp.

◆ getOrientation()

Ogre::Quaternion rviz_animated_view_controller::AnimatedViewController::getOrientation ( )
protected

Return a Quaternion.

Definition at line 976 of file rviz_animated_view_controller.cpp.

◆ getViewImage()

void rviz_animated_view_controller::AnimatedViewController::getViewImage ( std::shared_ptr< Ogre::PixelBox > &  pixel_box)
protected

Get the current image rviz is showing as an Ogre::PixelBox.

Definition at line 885 of file rviz_animated_view_controller.cpp.

◆ handleMouseEvent()

void rviz_animated_view_controller::AnimatedViewController::handleMouseEvent ( rviz::ViewportMouseEvent evt)
virtual

Reimplemented from rviz::ViewController.

Definition at line 362 of file rviz_animated_view_controller.cpp.

◆ initializePublishers()

void rviz_animated_view_controller::AnimatedViewController::initializePublishers ( )

Definition at line 176 of file rviz_animated_view_controller.cpp.

◆ initializeSubscribers()

void rviz_animated_view_controller::AnimatedViewController::initializeSubscribers ( )

Definition at line 185 of file rviz_animated_view_controller.cpp.

◆ isMovementAvailable()

bool rviz_animated_view_controller::AnimatedViewController::isMovementAvailable ( )
inlineprotected

Returns true if buffer contains at least one start and end pose needed for one movement.

Definition at line 213 of file rviz_animated_view_controller.h.

◆ lookAt()

void rviz_animated_view_controller::AnimatedViewController::lookAt ( const Ogre::Vector3 &  point)
virtual

Calls beginNewTransition() to move the focus point to the point provided, assumed to be in the Rviz Fixed Frame.

Reimplemented from rviz::ViewController.

Definition at line 737 of file rviz_animated_view_controller.cpp.

◆ mimic()

void rviz_animated_view_controller::AnimatedViewController::mimic ( ViewController source_view)
virtual

Configure the settings of this view controller to give, as much as possible, a similar view as that given by the source_view.

source_view must return a valid Ogre::Camera* from getCamera().

Reimplemented from rviz::ViewController.

Definition at line 525 of file rviz_animated_view_controller.cpp.

◆ move_eye()

void rviz_animated_view_controller::AnimatedViewController::move_eye ( float  x,
float  y,
float  z 
)

Applies a translation to only the eye point.

Definition at line 988 of file rviz_animated_view_controller.cpp.

◆ move_focus_and_eye()

void rviz_animated_view_controller::AnimatedViewController::move_focus_and_eye ( float  x,
float  y,
float  z 
)

Applies a translation to the focus and eye points.

Definition at line 981 of file rviz_animated_view_controller.cpp.

◆ moveEyeWithFocusTo()

void rviz_animated_view_controller::AnimatedViewController::moveEyeWithFocusTo ( const Ogre::Vector3 &  point)

Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed.

Definition at line 759 of file rviz_animated_view_controller.cpp.

◆ onActivate()

void rviz_animated_view_controller::AnimatedViewController::onActivate ( )
virtual

called by activate().

This version calls updateAttachedSceneNode().

Reimplemented from rviz::ViewController.

Definition at line 220 of file rviz_animated_view_controller.cpp.

◆ onAttachedFrameChanged()

void rviz_animated_view_controller::AnimatedViewController::onAttachedFrameChanged ( const Ogre::Vector3 &  old_reference_position,
const Ogre::Quaternion &  old_reference_orientation 
)
protectedvirtual

Override to implement the change in properties which nullifies the change in attached frame.

See also
updateAttachedFrame()

Definition at line 318 of file rviz_animated_view_controller.cpp.

◆ onDistancePropertyChanged

void rviz_animated_view_controller::AnimatedViewController::onDistancePropertyChanged ( )
protectedvirtualslot

Called when distance property is changed; computes new eye position.

Definition at line 265 of file rviz_animated_view_controller.cpp.

◆ onEyePropertyChanged

void rviz_animated_view_controller::AnimatedViewController::onEyePropertyChanged ( )
protectedvirtualslot

Called when eye property is changed; computes new distance.

Definition at line 255 of file rviz_animated_view_controller.cpp.

◆ onFocusPropertyChanged

void rviz_animated_view_controller::AnimatedViewController::onFocusPropertyChanged ( )
protectedvirtualslot

Called focus property is changed; computes new distance.

Definition at line 260 of file rviz_animated_view_controller.cpp.

◆ onInitialize()

void rviz_animated_view_controller::AnimatedViewController::onInitialize ( )
virtual

Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ are set.

This version sets up the attached_scene_node, focus shape, and subscribers.

Reimplemented from rviz::ViewController.

Definition at line 197 of file rviz_animated_view_controller.cpp.

◆ onUpPropertyChanged

void rviz_animated_view_controller::AnimatedViewController::onUpPropertyChanged ( )
protectedvirtualslot

Called when up vector property is changed (does nothing for now...).

Definition at line 273 of file rviz_animated_view_controller.cpp.

◆ orbitCameraTo()

void rviz_animated_view_controller::AnimatedViewController::orbitCameraTo ( const Ogre::Vector3 &  point)

Calls beginNewTransition() with the focus point fixed, moving the eye to the point given.

Definition at line 752 of file rviz_animated_view_controller.cpp.

◆ pauseAnimationCallback()

void rviz_animated_view_controller::AnimatedViewController::pauseAnimationCallback ( const std_msgs::Duration::ConstPtr &  pause_duration_msg)
protected

Sets the duration the rendering has to wait for during the next update cycle.

@params[in] pause_duration_msg duration to wait for.

Definition at line 191 of file rviz_animated_view_controller.cpp.

◆ pauseAnimationOnRequest()

void rviz_animated_view_controller::AnimatedViewController::pauseAnimationOnRequest ( )
protected

Pauses the animation if pause_animation_duration_ is larger than zero.

Adds the pause_animation_duration_ to the transition_start_time_ to continue the animation from where it was paused.

Definition at line 826 of file rviz_animated_view_controller.cpp.

◆ prepareNextMovement()

void rviz_animated_view_controller::AnimatedViewController::prepareNextMovement ( const ros::Duration previous_transition_duration)
protected

Updates the transition_start_time_ and resets the rendered_frames_counter_ for next movement.

Definition at line 919 of file rviz_animated_view_controller.cpp.

◆ publishCameraPose()

void rviz_animated_view_controller::AnimatedViewController::publishCameraPose ( )

Publishes the current camera pose.

Definition at line 485 of file rviz_animated_view_controller.cpp.

◆ publishViewImage()

void rviz_animated_view_controller::AnimatedViewController::publishViewImage ( )
protected

Publish the rendered image that is visible to the user in rviz.

Definition at line 869 of file rviz_animated_view_controller.cpp.

◆ reset()

void rviz_animated_view_controller::AnimatedViewController::reset ( )
virtual

Resets the camera parameters to a sane value.

Implements rviz::ViewController.

Definition at line 343 of file rviz_animated_view_controller.cpp.

◆ setPropertiesFromCamera()

void rviz_animated_view_controller::AnimatedViewController::setPropertiesFromCamera ( Ogre::Camera *  source_camera)
protected

Definition at line 510 of file rviz_animated_view_controller.cpp.

◆ transformCameraToAttachedFrame()

void rviz_animated_view_controller::AnimatedViewController::transformCameraToAttachedFrame ( geometry_msgs::PointStamped &  eye,
geometry_msgs::PointStamped &  focus,
geometry_msgs::Vector3Stamped &  up 
)
protected

Transforms the camera defined by eye, focus and up into the attached frame.

Parameters
[in,out]eyeposition of the camera.
[in,out]focusfocus point of the camera.
[in,out]upvector pointing up from the camera.

Definition at line 709 of file rviz_animated_view_controller.cpp.

◆ transitionFrom()

void rviz_animated_view_controller::AnimatedViewController::transitionFrom ( ViewController previous_view)
virtual

Called by ViewManager when this ViewController is being made current.

Parameters
previous_viewis the previous "current" view, and will not be NULL.

This gives ViewController subclasses an opportunity to implement a smooth transition from a previous viewpoint to the new viewpoint.

Reimplemented from rviz::ViewController.

Definition at line 553 of file rviz_animated_view_controller.cpp.

◆ update()

void rviz_animated_view_controller::AnimatedViewController::update ( float  dt,
float  ros_dt 
)
protectedvirtual

Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to run repeatedly.

Reimplemented from rviz::ViewController.

Definition at line 767 of file rviz_animated_view_controller.cpp.

◆ updateAttachedFrame

void rviz_animated_view_controller::AnimatedViewController::updateAttachedFrame ( )
protectedvirtualslot

Called when Target Frame property changes while view is active. Purpose is to change values in the view controller (like a position offset) such that the actual viewpoint does not change. Calls updateTargetSceneNode() and onTargetFrameChanged().

Definition at line 290 of file rviz_animated_view_controller.cpp.

◆ updateAttachedSceneNode()

void rviz_animated_view_controller::AnimatedViewController::updateAttachedSceneNode ( )
protected

Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame property.

Definition at line 300 of file rviz_animated_view_controller.cpp.

◆ updateCamera()

void rviz_animated_view_controller::AnimatedViewController::updateCamera ( )
protected

Updates the Ogre camera properties from the view controller properties.

Definition at line 925 of file rviz_animated_view_controller.cpp.

◆ updateTopics

void rviz_animated_view_controller::AnimatedViewController::updateTopics ( )
protectedslot

Definition at line 165 of file rviz_animated_view_controller.cpp.

◆ updateWindowSizeProperties()

void rviz_animated_view_controller::AnimatedViewController::updateWindowSizeProperties ( )
protected

Definition at line 214 of file rviz_animated_view_controller.cpp.

◆ yaw_pitch_roll()

void rviz_animated_view_controller::AnimatedViewController::yaw_pitch_roll ( float  yaw,
float  pitch,
float  roll 
)

Applies a body-fixed-axes sequence of rotations; only accurate for small angles.

Definition at line 934 of file rviz_animated_view_controller.cpp.

Member Data Documentation

◆ animate_

bool rviz_animated_view_controller::AnimatedViewController::animate_
protected

Definition at line 365 of file rviz_animated_view_controller.h.

◆ attached_frame_property_

rviz::TfFrameProperty* rviz_animated_view_controller::AnimatedViewController::attached_frame_property_
protected

Definition at line 358 of file rviz_animated_view_controller.h.

◆ attached_scene_node_

Ogre::SceneNode* rviz_animated_view_controller::AnimatedViewController::attached_scene_node_
protected

Definition at line 359 of file rviz_animated_view_controller.h.

◆ cam_movements_buffer_

BufferCamMovements rviz_animated_view_controller::AnimatedViewController::cam_movements_buffer_
protected

Definition at line 367 of file rviz_animated_view_controller.h.

◆ camera_placement_topic_property_

rviz::RosTopicProperty* rviz_animated_view_controller::AnimatedViewController::camera_placement_topic_property_
protected

Definition at line 350 of file rviz_animated_view_controller.h.

◆ camera_trajectory_topic_property_

rviz::RosTopicProperty* rviz_animated_view_controller::AnimatedViewController::camera_trajectory_topic_property_
protected

Definition at line 351 of file rviz_animated_view_controller.h.

◆ camera_view_image_publisher_

image_transport::Publisher rviz_animated_view_controller::AnimatedViewController::camera_view_image_publisher_
protected

Definition at line 380 of file rviz_animated_view_controller.h.

◆ current_camera_pose_publisher_

ros::Publisher rviz_animated_view_controller::AnimatedViewController::current_camera_pose_publisher_
protected

Definition at line 378 of file rviz_animated_view_controller.h.

◆ default_transition_time_property_

rviz::FloatProperty* rviz_animated_view_controller::AnimatedViewController::default_transition_time_property_
protected

A default time for any animation requests.

Definition at line 348 of file rviz_animated_view_controller.h.

◆ distance_property_

rviz::FloatProperty* rviz_animated_view_controller::AnimatedViewController::distance_property_
protected

The camera's distance from the focal point.

Definition at line 344 of file rviz_animated_view_controller.h.

◆ dragging_

bool rviz_animated_view_controller::AnimatedViewController::dragging_
protected

A flag indicating the dragging state of the mouse.

Definition at line 370 of file rviz_animated_view_controller.h.

◆ eye_point_property_

rviz::VectorProperty* rviz_animated_view_controller::AnimatedViewController::eye_point_property_
protected

The position of the camera.

Definition at line 345 of file rviz_animated_view_controller.h.

◆ finished_animation_publisher_

ros::Publisher rviz_animated_view_controller::AnimatedViewController::finished_animation_publisher_
protected

Definition at line 379 of file rviz_animated_view_controller.h.

◆ fixed_up_property_

rviz::BoolProperty* rviz_animated_view_controller::AnimatedViewController::fixed_up_property_
protected

If True, "up" is fixed to ... up.

Definition at line 342 of file rviz_animated_view_controller.h.

◆ focal_shape_

rviz::Shape* rviz_animated_view_controller::AnimatedViewController::focal_shape_
protected

A small ellipsoid to show the focus point.

Definition at line 369 of file rviz_animated_view_controller.h.

◆ focus_point_property_

rviz::VectorProperty* rviz_animated_view_controller::AnimatedViewController::focus_point_property_
protected

The point around which the camera "orbits".

Definition at line 346 of file rviz_animated_view_controller.h.

◆ interaction_disabled_cursor_

QCursor rviz_animated_view_controller::AnimatedViewController::interaction_disabled_cursor_
protected

A cursor for indicating mouse interaction is disabled.

Definition at line 372 of file rviz_animated_view_controller.h.

◆ interaction_mode_property_

rviz::EditableEnumProperty* rviz_animated_view_controller::AnimatedViewController::interaction_mode_property_
protected

Select between Orbit or FPS control style.

Definition at line 341 of file rviz_animated_view_controller.h.

◆ mouse_enabled_property_

rviz::BoolProperty* rviz_animated_view_controller::AnimatedViewController::mouse_enabled_property_
protected

If True, most user changes to camera state are disabled.

Definition at line 340 of file rviz_animated_view_controller.h.

◆ nh_

ros::NodeHandle rviz_animated_view_controller::AnimatedViewController::nh_
protected

Definition at line 338 of file rviz_animated_view_controller.h.

◆ pause_animation_duration_

ros::WallDuration rviz_animated_view_controller::AnimatedViewController::pause_animation_duration_
protected

Definition at line 386 of file rviz_animated_view_controller.h.

◆ pause_animation_duration_subscriber_

ros::Subscriber rviz_animated_view_controller::AnimatedViewController::pause_animation_duration_subscriber_
protected

Definition at line 376 of file rviz_animated_view_controller.h.

◆ placement_subscriber_

ros::Subscriber rviz_animated_view_controller::AnimatedViewController::placement_subscriber_
protected

Definition at line 374 of file rviz_animated_view_controller.h.

◆ publish_view_images_property_

rviz::BoolProperty* rviz_animated_view_controller::AnimatedViewController::publish_view_images_property_
protected

If True, the camera view is published as images.

Definition at line 356 of file rviz_animated_view_controller.h.

◆ reference_orientation_

Ogre::Quaternion rviz_animated_view_controller::AnimatedViewController::reference_orientation_
protected

Used to store the orientation of the attached frame relative to <Fixed Frame>

Definition at line 361 of file rviz_animated_view_controller.h.

◆ reference_position_

Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::reference_position_
protected

Used to store the position of the attached frame relative to <Fixed Frame>

Definition at line 362 of file rviz_animated_view_controller.h.

◆ render_frame_by_frame_

bool rviz_animated_view_controller::AnimatedViewController::render_frame_by_frame_
protected

Definition at line 382 of file rviz_animated_view_controller.h.

◆ rendered_frames_counter_

int rviz_animated_view_controller::AnimatedViewController::rendered_frames_counter_
protected

Definition at line 384 of file rviz_animated_view_controller.h.

◆ target_fps_

int rviz_animated_view_controller::AnimatedViewController::target_fps_
protected

Definition at line 383 of file rviz_animated_view_controller.h.

◆ trajectory_subscriber_

ros::Subscriber rviz_animated_view_controller::AnimatedViewController::trajectory_subscriber_
protected

Definition at line 375 of file rviz_animated_view_controller.h.

◆ transition_start_time_

ros::WallTime rviz_animated_view_controller::AnimatedViewController::transition_start_time_
protected

Definition at line 366 of file rviz_animated_view_controller.h.

◆ up_vector_property_

rviz::VectorProperty* rviz_animated_view_controller::AnimatedViewController::up_vector_property_
protected

The up vector for the camera.

Definition at line 347 of file rviz_animated_view_controller.h.

◆ window_height_property_

rviz::FloatProperty* rviz_animated_view_controller::AnimatedViewController::window_height_property_
protected

The height of the rviz visualization window in pixels.

Definition at line 354 of file rviz_animated_view_controller.h.

◆ window_width_property_

rviz::FloatProperty* rviz_animated_view_controller::AnimatedViewController::window_width_property_
protected

The width of the rviz visualization window in pixels.

Definition at line 353 of file rviz_animated_view_controller.h.


The documentation for this class was generated from the following files:


rviz_animated_view_controller
Author(s): Adam Leeper
autogenerated on Wed Mar 2 2022 01:03:32