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 "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
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