Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 #include <geometry_msgs/TransformStamped.h>
00031 #include <rve_transformer/transformer_manager.h>
00032 #include <rve_transformer/frame_manager.h>
00033 #include <rve_render_client/camera.h>
00034 
00035 #include "rve_common_transformers/frame_relative_camera_controller.h"
00036 
00037 namespace rve_common_transformers
00038 {
00039 
00040 FrameRelativeCameraController::FrameRelativeCameraController()
00041   : relative_position_( 0, 0, 0 )
00042   , relative_orientation_( 1, 0, 0, 0 ) 
00043 {
00044 }
00045 
00046 void FrameRelativeCameraController::setReferenceFrame( const std::string& frame_id )
00047 {
00048   reference_frame_id_ = frame_id;
00049 }
00050 
00051 void FrameRelativeCameraController::onInit()
00052 {
00053 }
00054 
00055 void FrameRelativeCameraController::onUpdate()
00056 {
00057   
00058   updateRelativePose();
00059 
00060   
00061   geometry_msgs::TransformStamped reference = getManager()->getFrameManager()->lookupTransform(reference_frame_id_, ros::Time());
00062   
00063   
00064   geometry_msgs::Vector3 p = reference.transform.translation;
00065   Eigen::Vector3f reference_pos(p.x, p.y, p.z);
00066 
00067   geometry_msgs::Quaternion q = reference.transform.rotation;
00068   Eigen::Quaternionf reference_rot(q.w, q.x, q.y, q.z);
00069 
00070   absolute_position_ = reference_pos + reference_rot * getRelativePosition();
00071   absolute_orientation_ = reference_rot * getRelativeOrientation();
00072 
00073   if( getCamera() )
00074   {
00075     getCamera()->setPosition(rve_common::eigenToMsg( absolute_position_ ));
00076     getCamera()->setOrientation(rve_common::eigenToMsg( absolute_orientation_ ));
00077   }
00078 }
00079 
00080 void FrameRelativeCameraController::onCameraSet()
00081 {
00082   if( getCamera() )
00083   {
00084     getCamera()->setPosition(rve_common::eigenToMsg( absolute_position_ ));
00085     getCamera()->setOrientation(rve_common::eigenToMsg( absolute_orientation_ ));
00086   }
00087 }
00088 
00089 }