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 "test_transformer.h"
00031 #include "rve_render_client/client_context.h"
00032 #include "rve_render_server/init.h"
00033 #include "rve_render_client/init.h"
00034 #include "rve_render_client/render_window.h"
00035 #include "rve_render_client/scene.h"
00036 #include "rve_render_client/mesh_instance.h"
00037 #include "rve_render_client/camera.h"
00038 #include "rve_render_client/sphere.h"
00039 #include "rve_render_client/billboard_text.h"
00040 #include <rve_transformer/transformer_manager.h>
00041 #include <rve_transformer/frame_manager.h>
00042 #include <rve_common_transformers/urdf.h>
00043 #include <rve_common_transformers/orbit_camera.h>
00044 #include <rve_properties/property_node.h>
00045 #include <rve_properties/messages.h>
00046 
00047 #include <rve_qt/render_widget.h>
00048 
00049 #include <rve_msgs/make_vector3.h>
00050 #include <rve_msgs/make_quaternion.h>
00051 
00052 #include <urdf/model.h>
00053 
00054 #include <Eigen/Geometry>
00055 
00056 #include <ros/package.h>
00057 #include <ros/time.h>
00058 
00059 #include <ros/time.h>
00060 #include <ros/ros.h>
00061 
00062 #include <QtGui/QtGui>
00063 
00064 using namespace rve_render_client;
00065 
00066 MyWidget::MyWidget(const ClientContextPtr& context, QWidget* parent)
00067 : RenderWidget(context.get(), parent)
00068 , private_nh_("~")
00069 , left_mouse_down_( false )
00070 , middle_mouse_down_( false )
00071 , right_mouse_down_( false )
00072 , mouse_x_( 0 )
00073 , mouse_y_( 0 )
00074 {
00075   context_ = context;
00076 
00077   scene_ = rve_render_client::createScene(context_);
00078   camera_ = rve_render_client::createCamera(scene_.get());
00079   camera_->setPosition(rve_msgs::makeVector3(-10, 0, 0));
00080   camera_->lookAt(rve_msgs::makeVector3(0, 0, 0));
00081   getRemoteRenderWindow()->attachCamera(camera_);
00082 
00083   transformer_manager_.reset(new rve_transformer::TransformerManager());
00084   transformer_manager_->getFrameManager()->setFixedFrame("base_footprint");
00085 
00086 
00087 
00088 
00089 
00090   cam_ = transformer_manager_->createTransformer<rve_common_transformers::OrbitCamera>();
00091   cam_->setCamera(camera_);
00092   cam_->setSubscription("mouse_input", getMouseEventTopic());
00093   cam_->getPropertyNode()->set("target_frame", "wide_stereo_optical_frame");
00094 
00095   text_ = rve_render_client::createBillboardText( scene_.get(), "Cheese monkey" );
00096   text_->setPosition(rve_msgs::makeVector3(0,10,0));
00097   text_->setCharacterHeight(0.1);
00098   rve_msgs::ColorRGB c;
00099   c.r = 1;
00100   c.g = 0;
00101   c.b = 0;
00102   text_->setColor(c);
00103   text_->setHorizontalAlignment(rve_msgs::TextAlignment::H_CENTER);
00104   text_->setVerticalAlignment(rve_msgs::TextAlignment::V_CENTER);
00105 
00106   ball_ = rve_render_client::createSphere( scene_.get() );
00107   ball_->setPosition(rve_msgs::makeVector3(10,0,0));
00108 
00109   flag_ = rve_render_client::createMeshInstance(scene_.get(), "package://test_rve/flag.dae");
00110   flag_->setPosition(rve_msgs::makeVector3(0,0,0));
00111 
00112   QTimer* timer = new QTimer(this);
00113   connect(timer, SIGNAL(timeout()), this, SLOT(update()));
00114   timer->start(33);
00115 }
00116 
00117 void MyWidget::update()
00118 {
00119   try
00120   {
00121     transformer_manager_->update();
00122     getRemoteRenderWindow()->requestRender();
00123   }
00124   catch (std::exception& e)
00125   {
00126     ROS_ERROR("%s", e.what());
00127   }
00128 }
00129 
00130 int main(int argc, char** argv)
00131 {
00132   int ret = 0;
00133 
00134   try
00135   {
00136     QApplication app(argc, argv);
00137     ros::init(argc, argv, "test_playpen", ros::init_options::NoSigintHandler);
00138     rve_render_server::init(true, "render_server");
00139     rve_render_client::init();
00140     ros::AsyncSpinner as(0);
00141     as.start();
00142 
00143     ClientContextPtr context = createContext("render_server", ros::NodeHandle("render_server"));
00144     MyWidget window(context);
00145     window.resize(1024, 768);
00146     window.show();
00147     window.setWindowTitle(QApplication::translate("toplevel", "test_transformer"));
00148 
00149     ret = app.exec();
00150 
00151   }
00152   catch (std::exception& e)
00153   {
00154     ROS_ERROR("Caught exception: %s", e.what());
00155   }
00156 
00157   rve_render_client::shutdown();
00158   rve_render_server::shutdown();
00159   return ret;
00160 }
00161