simulate_robot_camera.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "simulate_robot_camera.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/camera.h"
00037 #include <rve_transformer/transformer_manager.h>
00038 #include <rve_transformer/frame_manager.h>
00039 #include <rve_common_transformers/urdf.h>
00040 #include <rve_common_transformers/camera_following_camera.h>
00041 #include <rve_properties/property_node.h>
00042 #include <rve_properties/messages.h>
00043 
00044 #include <rve_qt/render_widget.h>
00045 
00046 #include <rve_msgs/make_vector3.h>
00047 #include <rve_msgs/make_quaternion.h>
00048 
00049 #include <urdf/model.h>
00050 
00051 #include <Eigen/Geometry>
00052 
00053 #include <ros/package.h>
00054 #include <ros/time.h>
00055 
00056 #include <ros/time.h>
00057 #include <ros/ros.h>
00058 
00059 #include <QtGui/QtGui>
00060 
00061 using namespace rve_render_client;
00062 
00063 MyWidget::MyWidget(const ClientContextPtr& context, QWidget* parent)
00064 : RenderWidget(context.get(), parent)
00065 , private_nh_("~")
00066 {
00067   context_ = context;
00068 
00069   scene_ = rve_render_client::createScene(context_);
00070   camera_ = rve_render_client::createCamera(scene_.get());
00071   camera_->setPosition(rve_msgs::makeVector3(-10, 0, 0));
00072   camera_->lookAt(rve_msgs::makeVector3(0, 0, 0));
00073   getRemoteRenderWindow()->attachCamera(camera_);
00074 
00075   transformer_manager_.reset(new rve_transformer::TransformerManager());
00076   transformer_manager_->getFrameManager()->setFixedFrame("base_footprint");
00077 
00078   rve_common_transformers::URDFPtr urdf = transformer_manager_->createTransformer<rve_common_transformers::URDF>();
00079   urdf->attachToScene(scene_.get());
00080   urdf->attachToContext(context_.get());
00081 
00082   rve_common_transformers::CameraFollowingCameraPtr cam =
00083     transformer_manager_->createTransformer<rve_common_transformers::CameraFollowingCamera>();
00084   cam->setCamera(camera_);
00085 
00086   // Change this to match the camera you want to use.
00087   cam->setSubscription("camera_info", "wide_stereo/left/camera_info");
00088 
00089   QTimer* timer = new QTimer(this);
00090   connect(timer, SIGNAL(timeout()), this, SLOT(update()));
00091   timer->start(33);
00092 }
00093 
00094 void MyWidget::update()
00095 {
00096   try
00097   {
00098     transformer_manager_->update();
00099     getRemoteRenderWindow()->requestRender();
00100   }
00101   catch (std::exception& e)
00102   {
00103     ROS_ERROR("%s", e.what());
00104   }
00105 }
00106 
00107 int main(int argc, char** argv)
00108 {
00109   int ret = 0;
00110 
00111   try
00112   {
00113     QApplication app(argc, argv);
00114     ros::init(argc, argv, "simulate_robot_camera", ros::init_options::NoSigintHandler);
00115     rve_render_server::init(true, "render_server");
00116     rve_render_client::init();
00117     ros::AsyncSpinner as(0);
00118     as.start();
00119 
00120     ClientContextPtr context = createContext("render_server", ros::NodeHandle("render_server"));
00121     MyWidget window(context);
00122     window.resize(640, 480);
00123     window.show();
00124     window.setWindowTitle(QApplication::translate("toplevel", "simulate_robot_camera"));
00125 
00126     ret = app.exec();
00127 
00128   }
00129   catch (std::exception& e)
00130   {
00131     ROS_ERROR("Caught exception: %s", e.what());
00132   }
00133 
00134   rve_render_client::shutdown();
00135   rve_render_server::shutdown();
00136   return ret;
00137 }
00138 


test_rve
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:32:08