49 #include "view_controller_msgs/CameraPlacement.h" 51 #include <OGRE/OgreViewport.h> 52 #include <OGRE/OgreQuaternion.h> 53 #include <OGRE/OgreVector3.h> 54 #include <OGRE/OgreSceneNode.h> 55 #include <OGRE/OgreSceneManager.h> 56 #include <OGRE/OgreCamera.h> 57 #include <OGRE/OgreRenderWindow.h> 76 static inline Ogre::Vector3
vectorFromMsg(
const geometry_msgs::Point &m) {
return Ogre::Vector3(m.x, m.y, m.z); }
77 static inline Ogre::Vector3
vectorFromMsg(
const geometry_msgs::Vector3 &m) {
return Ogre::Vector3(m.x, m.y, m.z); }
80 geometry_msgs::Point m;
81 m.x = o.x; m.y = o.y; m.z = o.z;
84 static inline void pointOgreToMsg(
const Ogre::Vector3 &o, geometry_msgs::Point &m) { m.x = o.x; m.y = o.y; m.z = o.z; }
88 geometry_msgs::Vector3 m;
89 m.x = o.x; m.y = o.y; m.z = o.z;
92 static inline void vectorOgreToMsg(
const Ogre::Vector3 &o, geometry_msgs::Vector3 &m) { m.x = o.x; m.y = o.y; m.z = o.z; }
99 , cam_movements_buffer_(100)
102 , render_frame_by_frame_(false)
104 , rendered_frames_counter_(0)
105 , pause_animation_duration_(0.0)
110 "Enables mouse control of the camera.",
113 "Select the style of mouse interaction.",
120 "If enabled, the camera is not allowed to roll side-to-side.",
124 "TF frame the camera is attached to.",
127 "Position of the camera.",
this );
129 "Position of the focus/orbit point.",
this );
131 "The vector which maps to \"up\" in the camera image plane.",
this );
133 "The distance between the camera position and the focus point.",
137 "The default time to use for camera transitions.",
140 QString::fromStdString(ros::message_traits::datatype<view_controller_msgs::CameraPlacement>() ),
141 "Topic for CameraPlacement messages",
this, SLOT(
updateTopics()));
144 QString::fromStdString(
145 ros::message_traits::datatype<view_controller_msgs::CameraTrajectory>()),
146 "Topic for CameraTrajectory messages",
this,
153 "If enabled, publishes images of what the user sees in the visualization window during an animation.",
204 camera_->setProjectionType( Ogre::PT_PERSPECTIVE );
285 camera_->setFixedYawAxis(
false);
302 Ogre::Vector3 new_reference_position;
303 Ogre::Quaternion new_reference_orientation;
307 new_reference_position, new_reference_orientation ))
367 setStatus(
"<b>Mouse interaction is disabled. You can enable it by checking the \"Mouse Enabled\" check-box in the Views panel." );
370 else if ( event.
shift() )
372 setStatus(
"TODO: Fix me! <b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
376 setStatus(
"TODO: Fix me! <b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
380 setStatus(
"TODO: Fix me! <b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom. <b>Shift</b>: More options." );
388 if( event.
type == QEvent::MouseButtonPress )
395 else if( event.
type == QEvent::MouseButtonRelease )
403 diff_x =
event.x -
event.last_x;
404 diff_y =
event.y -
event.last_y;
409 if( event.
left() && !
event.shift() )
415 else if( event.
middle() || (
event.shift() &&
event.left() ))
420 float fovY =
camera_->getFOVy().valueRadians();
421 float fovX = 2.0f *
atan(
tan( fovY / 2.0
f ) *
camera_->getAspectRatio() );
423 int width =
camera_->getViewport()->getActualWidth();
424 int height =
camera_->getViewport()->getActualHeight();
427 ((
float)diff_y / (
float)height) * distance *
tan( fovY / 2.0f ) * 2.0f,
435 else if( event.
right() )
445 move_eye( 0, 0, diff_y * 0.01 * distance );
455 int diff =
event.wheel_delta;
467 move_eye( 0, 0, -diff * 0.001 * distance );
472 if(event.
type == QEvent::MouseButtonPress && event.
left() &&
event.control() &&
event.shift())
487 geometry_msgs::Pose cam_pose;
488 cam_pose.position.x =
camera_->getPosition().x;
489 cam_pose.position.y =
camera_->getPosition().y;
490 cam_pose.position.z =
camera_->getPosition().z;
491 cam_pose.orientation.w =
camera_->getOrientation().w;
492 cam_pose.orientation.x =
camera_->getOrientation().x;
493 cam_pose.orientation.y =
camera_->getOrientation().y;
494 cam_pose.orientation.z =
camera_->getOrientation().z;
513 Ogre::Vector3 direction = source_camera->getOrientation() * Ogre::Vector3::NEGATIVE_UNIT_Z;
528 if( target_frame.isValid() )
533 Ogre::Camera* source_camera = source_view->
getCamera();
534 Ogre::Vector3 position = source_camera->getPosition();
535 Ogre::Quaternion orientation = source_camera->getOrientation();
537 if( source_view->
getClassId() ==
"rviz/Orbit" )
571 const Ogre::Vector3 &focus,
572 const Ogre::Vector3 &up,
574 uint8_t interpolation_speed)
576 if(transition_duration.
toSec() < 0.0)
580 if(transition_duration.
isZero())
592 interpolation_speed)));
612 std_msgs::Bool finished_animation;
613 finished_animation.data = 1;
621 CameraPlacement cp = *cp_ptr;
626 if(cp.mouse_interaction_mode != cp.NO_CHANGE)
628 std::string name =
"";
629 if(cp.mouse_interaction_mode == cp.ORBIT) name =
MODE_ORBIT;
630 else if(cp.mouse_interaction_mode == cp.FPS) name =
MODE_FPS;
634 if(cp.target_frame !=
"")
640 if(cp.time_from_start.toSec() >= 0)
658 view_controller_msgs::CameraTrajectory ct = *ct_ptr;
660 if(ct.trajectory.empty())
666 if(ct.mouse_interaction_mode != view_controller_msgs::CameraTrajectory::NO_CHANGE)
668 std::string name =
"";
669 if(ct.mouse_interaction_mode == view_controller_msgs::CameraTrajectory::ORBIT)
671 else if(ct.mouse_interaction_mode == view_controller_msgs::CameraTrajectory::FPS)
676 if(ct.render_frame_by_frame > 0)
679 target_fps_ =
static_cast<int>(ct.frames_per_second);
683 for(
auto& cam_movement : ct.trajectory)
685 if(cam_movement.transition_duration.toSec() >= 0.0)
687 if(ct.target_frame !=
"")
698 Ogre::Vector3 focus =
vectorFromMsg(cam_movement.focus.point);
700 beginNewTransition(eye, focus, up, cam_movement.transition_duration, cam_movement.interpolation_speed);
704 ROS_WARN(
"Transition duration of camera movement is below zero. Skipping that movement.");
710 geometry_msgs::PointStamped& focus,
711 geometry_msgs::Vector3Stamped& up)
713 Ogre::Vector3 position_fixed_eye, position_fixed_focus, position_fixed_up;
714 Ogre::Quaternion rotation_fixed_eye, rotation_fixed_focus, rotation_fixed_up;
781 bool finished_current_movement =
false;
782 if(relative_progress_in_time >= 1.0)
784 relative_progress_in_time = 1.0;
785 finished_current_movement =
true;
789 goal->interpolation_speed);
791 Ogre::Vector3 new_position =
start->eye + relative_progress_in_space * (goal->eye -
start->eye);
792 Ogre::Vector3 new_focus =
start->focus + relative_progress_in_space * (goal->focus -
start->focus);
793 Ogre::Vector3 new_up =
start->up + relative_progress_in_space * (goal->up -
start->up);
811 if(finished_current_movement)
838 double relative_progress_in_time = 0.0;
847 relative_progress_in_time = duration_from_start.
toSec() / transition_duration.
toSec();
849 return relative_progress_in_time;
853 uint8_t interpolation_speed)
855 switch(interpolation_speed)
857 case view_controller_msgs::CameraMovement::RISING:
858 return 1.f -
static_cast<float>(
cos(relative_progress_in_time * M_PI_2));
859 case view_controller_msgs::CameraMovement::DECLINING:
860 return static_cast<float>(-
cos(relative_progress_in_time * M_PI_2 + M_PI_2));
861 case view_controller_msgs::CameraMovement::FULL:
862 return static_cast<float>(relative_progress_in_time);
863 case view_controller_msgs::CameraMovement::WAVE:
865 return 0.5f * (1.f -
static_cast<float>(
cos(relative_progress_in_time * M_PI)));
873 std::shared_ptr<Ogre::PixelBox> pixel_box = std::make_shared<Ogre::PixelBox>();
876 sensor_msgs::ImagePtr image_msg = sensor_msgs::ImagePtr(
new sensor_msgs::Image());
881 delete[] (
unsigned char*)pixel_box->data;
891 const Ogre::PixelFormat pixel_format = Ogre::PF_BYTE_BGR;
892 const auto bytes_per_pixel = Ogre::PixelUtil::getNumElemBytes(pixel_format);
893 auto image_data =
new unsigned char[image_width * image_height * bytes_per_pixel];
894 Ogre::Box image_extents(0, 0, image_width, image_height);
895 pixel_box = std::make_shared<Ogre::PixelBox>(image_extents, pixel_format, image_data);
897 Ogre::RenderTarget::FB_AUTO);
901 sensor_msgs::ImagePtr output_image)
903 const auto bytes_per_pixel = Ogre::PixelUtil::getNumElemBytes(input_image->format);
904 const auto image_height = input_image->getHeight();
905 const auto image_width = input_image->getWidth();
909 output_image->height = image_height;
910 output_image->width = image_width;
912 output_image->is_bigendian =
false;
913 output_image->step =
static_cast<unsigned int>(image_width * bytes_per_pixel);
914 size_t size = image_width * image_height * bytes_per_pixel;
915 output_image->data.resize(size);
916 memcpy((
char*)(&output_image->data[0]), input_image->data, size);
936 Ogre::Quaternion old_camera_orientation =
camera_->getOrientation();
937 Ogre::Radian old_pitch = old_camera_orientation.getPitch(
false);
941 Ogre::Quaternion yaw_quat, pitch_quat, roll_quat;
942 yaw_quat.FromAngleAxis( Ogre::Radian( yaw ), Ogre::Vector3::UNIT_Y );
943 pitch_quat.FromAngleAxis( Ogre::Radian( pitch ), Ogre::Vector3::UNIT_X );
944 roll_quat.FromAngleAxis( Ogre::Radian( roll ), Ogre::Vector3::UNIT_Z );
945 Ogre::Quaternion orientation_change = yaw_quat * pitch_quat * roll_quat;
946 Ogre::Quaternion new_camera_orientation = old_camera_orientation * orientation_change;
947 Ogre::Radian new_pitch = new_camera_orientation.getPitch(
false);
950 ((new_pitch > PITCH_LIMIT_HIGH && new_pitch > old_pitch) || (new_pitch < PITCH_LIMIT_LOW && new_pitch < old_pitch)) )
952 orientation_change = yaw_quat * roll_quat;
953 new_camera_orientation = old_camera_orientation * orientation_change;
960 camera_->setOrientation( new_camera_orientation );
966 camera_->setPosition(new_eye_position);
978 return camera_->getOrientation();
983 Ogre::Vector3 translate( x, y, z );
990 Ogre::Vector3 translate( x, y, z );
void updateAttachedSceneNode()
Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame pro...
static const Ogre::Radian PITCH_LIMIT_LOW
Ogre::Quaternion reference_orientation_
Used to store the orientation of the attached frame relative to <Fixed frame>=""> ...
void moveEyeWithFocusTo(const Ogre::Vector3 &point)
Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed...
std::string getFrameStd() const
Ogre::Vector3 reference_position_
Used to store the position of the attached frame relative to <Fixed frame>="">
static geometry_msgs::Point pointOgreToMsg(const Ogre::Vector3 &o)
rviz::TfFrameProperty * attached_frame_property_
void setPropertiesFromCamera(Ogre::Camera *source_camera)
void move_focus_and_eye(float x, float y, float z)
Applies a translation to the focus and eye points.
rviz::BoolProperty * mouse_enabled_property_
If True, most user changes to camera state are disabled.
virtual bool setVector(const Ogre::Vector3 &vector)
QCursor makeIconCursor(QString url, bool fill_cache)
rviz::FloatProperty * distance_property_
The camera's distance from the focal point.
uint32_t getNumSubscribers() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void prepareNextMovement(const ros::Duration &previous_transition_duration)
Updates the transition_start_time_ and resets the rendered_frames_counter_ for next movement...
virtual ViewManager * getViewManager() const=0
void setScale(const Ogre::Vector3 &scale) override
static const Ogre::Radian PITCH_LIMIT_HIGH
ros::Subscriber trajectory_subscriber_
int rendered_frames_counter_
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
virtual void mimic(ViewController *source_view)
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
void setCursor(CursorType cursor_type)
Ogre::Camera * getCamera() const
bool isMovementAvailable()
Returns true if buffer contains at least one start and end pose needed for one movement.
virtual Ogre::Vector3 getVector() const
void initializePublishers()
static const std::string MODE_ORBIT
void getViewImage(std::shared_ptr< Ogre::PixelBox > &pixel_box)
Get the current image rviz is showing as an Ogre::PixelBox.
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...
rviz::FloatProperty * window_width_property_
The width of the rviz visualization window in pixels.
virtual void transitionFrom(ViewController *previous_view)
Called by ViewManager when this ViewController is being made current.
void addOptionStd(const std::string &option)
void setColor(float r, float g, float b, float a) override
bool setValue(const QVariant &new_value) override
bool add(const Ogre::Vector3 &offset)
rviz::BoolProperty * fixed_up_property_
If True, "up" is fixed to ... up.
virtual void reset()
Resets the camera parameters to a sane value.
virtual QString getClassId() const
virtual void lookAt(const Ogre::Vector3 &point)
Calls beginNewTransition() to move the focus point to the point provided, assumed to be in the Rviz F...
void pauseAnimationOnRequest()
Pauses the animation if pause_animation_duration_ is larger than zero.
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.
virtual void onFocusPropertyChanged()
Called focus property is changed; computes new distance.
std::string getStdString()
Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v)
static Ogre::Vector3 vectorFromMsg(const geometry_msgs::Point &m)
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...
void initializeSubscribers()
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
bool setFloat(float new_value)
virtual Property * subProp(const QString &sub_name)
bool dragging_
A flag indicating the dragging state of the mouse.
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.
void yaw_pitch_roll(float yaw, float pitch, float roll)
Applies a body-fixed-axes sequence of rotations; only accurate for small angles.
void publish(const boost::shared_ptr< M > &message) const
double computeRelativeProgressInTime(const ros::Duration &transition_duration)
Computes the fraction of time we already used for the current movement.
void connectPositionProperties()
Convenience function; connects the signals/slots for position properties.
rviz::BoolProperty * publish_view_images_property_
If True, the camera view is published as images.
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
virtual void onUpPropertyChanged()
Called when up vector property is changed (does nothing for now...).
WallDuration & fromSec(double t)
ros::WallTime transition_start_time_
ros::Publisher current_camera_pose_publisher_
RenderPanel * getRenderPanel() const
rviz::RosTopicProperty * camera_placement_topic_property_
void setStatus(const QString &message)
virtual void updateAttachedFrame()
Called when Target Frame property changes while view is active. Purpose is to change values in the vi...
virtual FrameManager * getFrameManager() const=0
virtual void handleMouseEvent(rviz::ViewportMouseEvent &evt)
void convertImage(std::shared_ptr< Ogre::PixelBox > input_image, sensor_msgs::ImagePtr output_image)
void publishViewImage()
Publish the rendered image that is visible to the user in rviz.
rviz::FloatProperty * window_height_property_
The height of the rviz visualization window in pixels.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void cancelTransition()
Cancels any currently active camera movement.
ros::Subscriber placement_subscriber_
virtual void onDistancePropertyChanged()
Called when distance property is changed; computes new eye position.
#define ROS_DEBUG_STREAM(args)
void publish(const sensor_msgs::Image &message) const
static geometry_msgs::Vector3 vectorOgreToMsg(const Ogre::Vector3 &o)
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 r...
void pauseAnimationCallback(const std_msgs::Duration::ConstPtr &pause_duration_msg)
Sets the duration the rendering has to wait for during the next update cycle.
void setPosition(const Ogre::Vector3 &position) override
bool render_frame_by_frame_
virtual Ogre::SceneManager * getSceneManager() const=0
void updateWindowSizeProperties()
virtual void queueRender()=0
rviz::EditableEnumProperty * interaction_mode_property_
Select between Orbit or FPS control style.
ros::Subscriber pause_animation_duration_subscriber_
void updateCamera()
Updates the Ogre camera properties from the view controller properties.
void disconnectPositionProperties()
Convenience function; disconnects the signals/slots for position properties.
static const QString FIXED_FRAME_STRING
virtual float getFloat() const
QCursor interaction_disabled_cursor_
A cursor for indicating mouse interaction is disabled.
static const std::string MODE_FPS
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setFrameManager(FrameManager *frame_manager)
Ogre::Quaternion getOrientation()
Return a Quaternion.
rviz::FloatProperty * default_transition_time_property_
A default time for any animation requests.
virtual ~AnimatedViewController()
virtual void onEyePropertyChanged()
Called when eye property is changed; computes new distance.
void move_eye(float x, float y, float z)
Applies a translation to only the eye point.
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
BufferCamMovements cam_movements_buffer_
void publishCameraPose()
Publishes the current camera pose.
rviz::VectorProperty * eye_point_property_
The position of the camera.
float getDistanceFromCameraToFocalPoint()
Return the distance between camera and focal point.
void orbitCameraTo(const Ogre::Vector3 &point)
Calls beginNewTransition() with the focus point fixed, moving the eye to the point given...
virtual QVariant getValue() const
rviz::Shape * focal_shape_
A small ellipsoid to show the focus point.
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
Ogre::SceneNode * getRootNode()
rviz::VectorProperty * up_vector_property_
The up vector for the camera.
ros::Publisher finished_animation_publisher_
void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr)
virtual bool getBool() const
bool setStdString(const std::string &std_str)
DisplayContext * context_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::RosTopicProperty * camera_trajectory_topic_property_
image_transport::Publisher camera_view_image_publisher_
An un-constrained "flying" camera, specified by an eye point, focus point, and up vector...
ros::WallDuration pause_animation_duration_
rviz::VectorProperty * focus_point_property_
The point around which the camera "orbits".
void cameraTrajectoryCallback(const view_controller_msgs::CameraTrajectoryConstPtr &ct_ptr)
Initiate camera motion from incoming CameraTrajectory.
virtual void onActivate()
called by activate().
Ogre::SceneNode * attached_scene_node_