Go to the documentation of this file.00001 #include <rve_transformer/frame_manager.h>
00002 #include <rve_common_transformers/urdf.h>
00003 #include <rve_common_transformers/camera_following_camera.h>
00004
00005 #include <rve_msgs/make_vector3.h>
00006 #include <rve_msgs/make_quaternion.h>
00007
00008 #include "offscreenRenderer.h"
00009
00010 static const unsigned IMAGE_WIDTH = 640;
00011 static const unsigned IMAGE_HEIGHT = 480;
00012 static const unsigned IMAGE_QUEUE = 50;
00013
00014 namespace offscreen_renderer
00015 {
00016 OffscreenRenderer::OffscreenRenderer(const rve_render_client::ClientContextPtr& p_context,
00017 const std::string &p_camera_topic,
00018 ros::NodeHandle &p_nh)
00019 : context_(p_context)
00020 , scene_(rve_render_client::createScene(context_))
00021 , camera_(rve_render_client::createCamera(scene_.get()))
00022 , transformer_manager_(new rve_transformer::TransformerManager(p_nh))
00023 , tf_subs_(p_nh.subscribe("/tf",IMAGE_QUEUE,&OffscreenRenderer::tfSubscriberCb,this))
00024 , render_offscreen_(new rve_render_client::RenderOffscreen(IMAGE_WIDTH,IMAGE_HEIGHT))
00025 {
00026
00027 render_offscreen_->create(context_.get());
00028
00029
00030 camera_->setPosition(rve_msgs::makeVector3(-10, 0, 0));
00031 camera_->lookAt(rve_msgs::makeVector3(0, 0, 0));
00032 render_offscreen_->attachCamera(camera_);
00033
00034 transformer_manager_->getFrameManager()->setFixedFrame("base_footprint");
00035
00036 rve_common_transformers::URDFPtr urdf = transformer_manager_->createTransformer<rve_common_transformers::URDF>();
00037 urdf->attachToScene(scene_.get());
00038 urdf->attachToContext(context_.get());
00039
00040 rve_common_transformers::CameraFollowingCameraPtr cam =
00041 transformer_manager_->createTransformer<rve_common_transformers::CameraFollowingCamera>();
00042 cam->setCamera(camera_);
00043
00044 cam->setSubscription("camera_info", p_camera_topic);
00045 }
00046
00047
00048 void OffscreenRenderer::tfSubscriberCb(const boost::shared_ptr<tf::tfMessage const>& p_msg)
00049 {
00050 ROS_DEBUG("received tf; updating the render");
00051 try
00052 {
00053 transformer_manager_->update();
00054 render_offscreen_->requestRender();
00055 }
00056 catch (std::exception& e)
00057 {
00058 ROS_ERROR("%s", e.what());
00059 }
00060 }
00061 }