OGMap3DViewer.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
10 #include <rtm/CorbaNaming.h>
11 #include <GL/gl.h>
12 #include "IrrModel.h"
13 #include <math.h>
14 #include <hrpModel/ModelLoaderUtil.h>
15 #include "OGMap3DViewer.h"
16 
17 using namespace irr;
18 using namespace core;
19 using namespace scene;
20 using namespace video;
21 
22 class CMapSceneNode : public irr::scene::ISceneNode
23 {
24 public:
25  CMapSceneNode(ISceneNode *i_parent, ISceneManager *i_mgr, s32 i_id,
26  double i_origin[3], double i_size[3]) :
27  ISceneNode(i_parent, i_mgr, i_id),
28  m_map(NULL){
29  // bounding box
30  m_vertices[0] = vector3df(i_origin[0], -i_origin[1], i_origin[2]);
31  m_vertices[1] = vector3df(i_origin[0]+i_size[0], -i_origin[1], i_origin[2]);
32  m_vertices[2] = vector3df(i_origin[0]+i_size[0], -(i_origin[1]+i_size[1]), i_origin[2]);
33  m_vertices[3] = vector3df(i_origin[0], -(i_origin[1]+i_size[1]), i_origin[2]);
34 
35  m_vertices[4] = m_vertices[0]; m_vertices[4].Z += i_size[2];
36  m_vertices[5] = m_vertices[1]; m_vertices[5].Z += i_size[2];
37  m_vertices[6] = m_vertices[2]; m_vertices[6].Z += i_size[2];
38  m_vertices[7] = m_vertices[3]; m_vertices[7].Z += i_size[2];
39 
40  m_box.reset(m_vertices[0]);
41  for (int i=1; i<8; i++) m_box.addInternalPoint(m_vertices[i]);
42 
43  // vertex indices of cube
44  m_cubeIndices[ 0] = 0; m_cubeIndices[ 1] = 1; m_cubeIndices[ 2] = 2;
45  m_cubeIndices[ 3] = 2; m_cubeIndices[ 4] = 3; m_cubeIndices[ 5] = 0;
46 
47  m_cubeIndices[ 6] = 4; m_cubeIndices[ 7] = 5; m_cubeIndices[ 8] = 6;
48  m_cubeIndices[ 9] = 6; m_cubeIndices[10] = 7; m_cubeIndices[11] = 4;
49 
50  m_cubeIndices[12] = 8; m_cubeIndices[13] = 9; m_cubeIndices[14] = 10;
51  m_cubeIndices[15] = 10; m_cubeIndices[16] = 11; m_cubeIndices[17] = 8;
52 
53  m_cubeIndices[18] = 12; m_cubeIndices[19] = 13; m_cubeIndices[20] = 14;
54  m_cubeIndices[21] = 14; m_cubeIndices[22] = 15; m_cubeIndices[23] = 12;
55 
56  m_cubeIndices[24] = 16; m_cubeIndices[25] = 17; m_cubeIndices[26] = 18;
57  m_cubeIndices[27] = 18; m_cubeIndices[28] = 19; m_cubeIndices[29] = 16;
58 
59  m_cubeIndices[30] = 20; m_cubeIndices[31] = 21; m_cubeIndices[32] = 22;
60  m_cubeIndices[33] = 22; m_cubeIndices[34] = 23; m_cubeIndices[35] = 20;
61  }
62 
63  void setMap(OpenHRP::OGMap3D *i_map) { m_map = i_map; }
64 
65  void setupCubeVertices(double i_res){
66  SColor white(0xff, 0xff, 0xff, 0xff);
67  // +z
68  m_cubeVerts[0] = S3DVertex(-i_res/2, -i_res/2, i_res/2,
69  0,0,1, white,0,0);
70  m_cubeVerts[1] = S3DVertex( i_res/2, -i_res/2, i_res/2,
71  0,0,1, white,0,0);
72  m_cubeVerts[2] = S3DVertex( i_res/2, i_res/2, i_res/2,
73  0,0,1, white,0,0);
74  m_cubeVerts[3] = S3DVertex(-i_res/2, i_res/2, i_res/2,
75  0,0,1, white,0,0);
76  // -z
77  m_cubeVerts[4] = S3DVertex(-i_res/2, i_res/2, -i_res/2,
78  0,0,-1, white,0,0);
79  m_cubeVerts[5] = S3DVertex( i_res/2, i_res/2, -i_res/2,
80  0,0,-1, white,0,0);
81  m_cubeVerts[6] = S3DVertex( i_res/2, -i_res/2, -i_res/2,
82  0,0,-1, white,0,0);
83  m_cubeVerts[7] = S3DVertex(-i_res/2, -i_res/2, -i_res/2,
84  0,0,-1, white,0,0);
85  // +x
86  m_cubeVerts[8] = S3DVertex(i_res/2, -i_res/2, i_res/2,
87  1,0,0, white,0,0);
88  m_cubeVerts[9] = S3DVertex(i_res/2, -i_res/2, -i_res/2,
89  1,0,0, white,0,0);
90  m_cubeVerts[10] = S3DVertex(i_res/2, i_res/2, -i_res/2,
91  1,0,0, white,0,0);
92  m_cubeVerts[11] = S3DVertex(i_res/2, i_res/2, i_res/2,
93  1,0,0, white,0,0);
94  // -x
95  m_cubeVerts[12] = S3DVertex(-i_res/2, i_res/2, i_res/2,
96  -1,0,0, white,0,0);
97  m_cubeVerts[13] = S3DVertex(-i_res/2, i_res/2, -i_res/2,
98  -1,0,0, white,0,0);
99  m_cubeVerts[14] = S3DVertex(-i_res/2, -i_res/2, -i_res/2,
100  -1,0,0, white,0,0);
101  m_cubeVerts[15] = S3DVertex(-i_res/2, -i_res/2, i_res/2,
102  -1,0,0, white,0,0);
103  // +y
104  m_cubeVerts[16] = S3DVertex(i_res/2, i_res/2, i_res/2,
105  0,1,0, white,0,0);
106  m_cubeVerts[17] = S3DVertex(i_res/2, i_res/2, -i_res/2,
107  0,1,0, white,0,0);
108  m_cubeVerts[18] = S3DVertex(-i_res/2,i_res/2, -i_res/2,
109  0,1,0, white,0,0);
110  m_cubeVerts[19] = S3DVertex(-i_res/2,i_res/2, i_res/2,
111  0,1,0, white,0,0);
112  // -y
113  m_cubeVerts[20] = S3DVertex(-i_res/2,-i_res/2, i_res/2,
114  0,-1,0, white,0,0);
115  m_cubeVerts[21] = S3DVertex(-i_res/2,-i_res/2, -i_res/2,
116  0,-1,0, white,0,0);
117  m_cubeVerts[22] = S3DVertex(i_res/2, -i_res/2, -i_res/2,
118  0,-1,0, white,0,0);
119  m_cubeVerts[23] = S3DVertex(i_res/2, -i_res/2, i_res/2,
120  0,-1,0, white,0,0);
121 
122  }
123  virtual void OnRegisterSceneNode(){
124  if (IsVisible)
125  SceneManager->registerNodeForRendering(this);
126 
127  ISceneNode::OnRegisterSceneNode();
128  }
129  virtual void render() {
130  IVideoDriver *driver = SceneManager->getVideoDriver();
131  matrix4 m;
132  driver->setTransform(ETS_WORLD, m);
133 
134  // bottom
135  driver->draw3DLine(m_vertices[0], m_vertices[1]);
136  driver->draw3DLine(m_vertices[1], m_vertices[2]);
137  driver->draw3DLine(m_vertices[2], m_vertices[3]);
138  driver->draw3DLine(m_vertices[3], m_vertices[0]);
139  // top
140  driver->draw3DLine(m_vertices[4], m_vertices[5]);
141  driver->draw3DLine(m_vertices[5], m_vertices[6]);
142  driver->draw3DLine(m_vertices[6], m_vertices[7]);
143  driver->draw3DLine(m_vertices[7], m_vertices[4]);
144  // vertical lines
145  driver->draw3DLine(m_vertices[0], m_vertices[4]);
146  driver->draw3DLine(m_vertices[1], m_vertices[5]);
147  driver->draw3DLine(m_vertices[2], m_vertices[6]);
148  driver->draw3DLine(m_vertices[3], m_vertices[7]);
149 
150  if (!m_map) return;
151  setupCubeVertices(m_map->resolution);
152  double res = m_map->resolution;
153  int rank=0;
154  int nxny = m_map->nx*m_map->ny;
155 
156  for (int i=0; i<m_map->nx; i++){
157  m[12] = m_map->pos.x + i*res;
158  for (int j=0; j<m_map->ny; j++){
159  m[13] = -(m_map->pos.y + j*res);
160  for (int k=0; k<m_map->nz; k++){
161  m[14] = m_map->pos.z + k*res;
162  unsigned char p = m_map->cells[rank++];
163  if (p != OpenHRP::gridUnknown
164  && p != OpenHRP::gridEmpty){
165  driver->setTransform(ETS_WORLD, m);
166  driver->drawIndexedTriangleList(m_cubeVerts, 24,
167  m_cubeIndices, 12);
168  }
169  }
170 
171  }
172 
173  }
174  }
175  virtual const aabbox3d<f32>& getBoundingBox() const { return m_box; }
176 private:
177  irr::core::aabbox3d<f32> m_box;
178  vector3df m_vertices[8];
179  S3DVertex m_tileVerts[4], m_cubeVerts[24];
180  u16 m_tileIndices[4], m_cubeIndices[36];
181  float m_scale[3], m_origin[3];
182  OpenHRP::OGMap3D* m_map;
183 };
184 
185 // Module specification
186 // <rtc-template block="module_spec">
187 static const char* nullcomponent_spec[] =
188  {
189  "implementation_id", "OGMap3DViewer",
190  "type_name", "OGMap3DViewer",
191  "description", "null component",
192  "version", HRPSYS_PACKAGE_VERSION,
193  "vendor", "AIST",
194  "category", "example",
195  "activity_type", "DataFlowComponent",
196  "max_instance", "10",
197  "language", "C++",
198  "lang_type", "compile",
199  // Configuration variables
200  "conf.default.generateImageSequence", "0",
201  "conf.default.generateMovie", "0",
202  "conf.default.xSize", "4",
203  "conf.default.ySize", "4",
204  "conf.default.zSize", "4",
205  "conf.default.xOrigin", "0",
206  "conf.default.yOrigin", "-2",
207  "conf.default.zOrigin", "0",
208 
209  ""
210  };
211 // </rtc-template>
212 
214  : RTC::DataFlowComponentBase(manager),
215  // <rtc-template block="initializer">
216  m_qIn("q", m_q),
217  m_pIn("p", m_p),
218  m_rpyIn("rpy", m_rpy),
219  m_OGMap3DServicePort("OGMap3DService"),
220  // </rtc-template>
221  dummy(0),
222  m_isopen(false),
223  m_generateImageSequence(false),
224  m_body(NULL),
225  m_imageCount(0),
226  m_ogmap(NULL),
227  m_generateMovie(false),
228  m_isGeneratingMovie(false)
229 {
230 }
231 
233 {
234 }
235 
236 
237 
238 RTC::ReturnCode_t OGMap3DViewer::onInitialize()
239 {
240  std::cout << m_profile.instance_name << ": onInitialize()" << std::endl;
241  // <rtc-template block="bind_config">
242  // Bind variables and configuration variable
243  bindParameter("generateImageSequence", m_generateImageSequence, "0");
244  bindParameter("generateMovie", m_generateMovie, "0");
245  bindParameter("xSize", m_xSize, "4");
246  bindParameter("ySize", m_ySize, "4");
247  bindParameter("zSize", m_zSize, "4");
248  bindParameter("xOrigin", m_xOrigin, "0");
249  bindParameter("yOrigin", m_yOrigin, "-2");
250  bindParameter("zOrigin", m_zOrigin, "0");
251 
252  // </rtc-template>
253 
254  // Registration: InPort/OutPort/Service
255  // <rtc-template block="registration">
256  // Set InPort buffers
257  addInPort("q", m_qIn);
258  addInPort("p", m_pIn);
259  addInPort("rpy", m_rpyIn);
260 
261  // Set OutPort buffer
262 
263  // Set service provider to Ports
264 
265  // Set service consumers to Ports
266  m_OGMap3DServicePort.registerConsumer("service1","OGMap3DService",m_OGMap3DService);
267 
268  // Set CORBA Service Ports
270 
271  // </rtc-template>
272 
274 
275  return RTC::RTC_OK;
276 }
277 
278 
279 
280 /*
281 RTC::ReturnCode_t OGMap3DViewer::onFinalize()
282 {
283  return RTC::RTC_OK;
284 }
285 */
286 
287 /*
288 RTC::ReturnCode_t OGMap3DViewer::onStartup(RTC::UniqueId ec_id)
289 {
290  return RTC::RTC_OK;
291 }
292 */
293 
294 /*
295 RTC::ReturnCode_t OGMap3DViewer::onShutdown(RTC::UniqueId ec_id)
296 {
297  return RTC::RTC_OK;
298 }
299 */
300 
302 {
303  std::cout << m_profile.instance_name<< ": onActivated(" << ec_id << ")" << std::endl;
304  return RTC::RTC_OK;
305 }
306 
308 {
309  std::cout << m_profile.instance_name<< ": onDeactivated(" << ec_id << ")" << std::endl;
310  return RTC::RTC_OK;
311 }
312 
313 void capture(int w, int h, unsigned char *o_buffer)
314 {
315  glReadBuffer(GL_BACK);
316  glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
317  for (int i=0; i<h; i++){
318  glReadPixels(0,(h-1-i),w,1,GL_RGB,GL_UNSIGNED_BYTE,
319  o_buffer + i*3*w);
320  }
321 }
322 
323 void save(int w, int h, const char *i_fname)
324 {
325  unsigned char *buffer = new unsigned char[w*h*3];
326 
327  capture(w, h, buffer);
328  std::ofstream ofs("test.ppm", std::ios::out | std::ios::trunc | std::ios::binary );
329  char buf[10];
330  sprintf(buf, "%d %d", w, h);
331  ofs << "P6" << std::endl << buf << std::endl << "255" << std::endl;
332  for (int i=h-1; i>=0; i--){
333  ofs.write((char *)(buffer+i*w*3), w*3);
334  }
335  delete [] buffer;
336 }
337 
338 
339 RTC::ReturnCode_t OGMap3DViewer::onExecute(RTC::UniqueId ec_id)
340 {
341  if (m_qIn.isNew()) m_qIn.read();
342  if (m_pIn.isNew()) m_pIn.read();
343  if (m_rpyIn.isNew()) m_rpyIn.read();
344 
345  if (!m_isopen){
347 
348  scene->init();
349 
351  RTC::Manager& rtcManager = RTC::Manager::instance();
352  std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
353  int comPos = nameServer.find(",");
354  if (comPos < 0){
355  comPos = nameServer.length();
356  }
357  nameServer = nameServer.substr(0, comPos);
358  RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
359  if (prop["model"] != ""){
360  std::cerr << "model = " << prop["model"] << std::endl;
361  OpenHRP::BodyInfo_var binfo = hrp::loadBodyInfo(
362  prop["model"].c_str(),
363  CosNaming::NamingContext::_duplicate(naming.getRootContext()));
364  m_body = scene->addBody(binfo);
365  }
366 
367  double origin[] = {m_xOrigin, m_yOrigin, m_zOrigin};
368  double size[] = {m_xSize, m_ySize, m_zSize};
369  ISceneManager *smgr = scene->getSceneManager();
370  m_mapNode = new CMapSceneNode(smgr->getRootSceneNode(), smgr, -1, origin, size);
371 
372  m_isopen = true;
373  }
374 
375  OpenHRP::AABB region;
376  region.pos.x = m_xOrigin;
377  region.pos.y = m_yOrigin;
378  region.pos.z = m_zOrigin;
379  region.size.l = m_xSize;
380  region.size.w = m_ySize;
381  region.size.h = m_zSize;
382 
383  if (m_ogmap){
384  delete m_ogmap;
385  m_ogmap = NULL;
386  }
387  if (!CORBA::is_nil(m_OGMap3DService.getObject())){
388  try{
389  m_ogmap = m_OGMap3DService->getOGMap3D(region);
390  }catch(CORBA::SystemException& ex){
391  // provider is not activated
392  }
393  }
395 
397  GLcamera *camera=scene->getCamera();
398 
399  if (m_body && m_q.data.length() > 0){
400  double pos[] = {m_p.data.x, m_p.data.y, m_p.data.z};
401  double rpy[] = {m_rpy.data.r, m_rpy.data.p, m_rpy.data.y};
402  m_body->setPosture(m_q.data.get_buffer(), pos, rpy);
403  }
404 
405  scene->draw();
406 
408  char buf[30];
409  sprintf(buf, "OGMap3DViewer%03d.ppm", m_imageCount++);
410  save(camera->width(), camera->height(), buf);
411  }
412 
413  if (m_generateMovie){
414  if (!m_isGeneratingMovie){
415  std::string fname(m_profile.instance_name);
416  fname += ".avi";
417  m_videoWriter = cvCreateVideoWriter(
418  fname.c_str(),
419  CV_FOURCC('D','I','V','X'),
420  10,
421  cvSize(camera->width(), camera->height()));
422  m_cvImage = cvCreateImage(
423  cvSize(camera->width(), camera->height()),
424  IPL_DEPTH_8U, 3);
425  m_isGeneratingMovie = true;
426  }
427  // RGB -> BGR
428  unsigned char rgb[camera->width()*camera->height()*3];
429  capture(camera->width(), camera->height(), rgb);
430  char *bgr = m_cvImage->imageData;
431  for (int i=0; i<camera->width()*camera->height(); i++){
432  bgr[i*3 ] = rgb[i*3+2];
433  bgr[i*3+1] = rgb[i*3+1];
434  bgr[i*3+2] = rgb[i*3 ];
435  }
436  cvWriteFrame(m_videoWriter, m_cvImage);
437  }else{
438  if (m_isGeneratingMovie){
439  cvReleaseVideoWriter(&m_videoWriter);
440  cvReleaseImage(&m_cvImage);
441  m_isGeneratingMovie = false;
442  }
443  }
444 
445 
446 
447  return RTC::RTC_OK;
448 }
449 
450 /*
451 RTC::ReturnCode_t OGMap3DViewer::onAborting(RTC::UniqueId ec_id)
452 {
453  return RTC::RTC_OK;
454 }
455 */
456 
457 /*
458 RTC::ReturnCode_t OGMap3DViewer::onError(RTC::UniqueId ec_id)
459 {
460  return RTC::RTC_OK;
461 }
462 */
463 
464 /*
465 RTC::ReturnCode_t OGMap3DViewer::onReset(RTC::UniqueId ec_id)
466 {
467  return RTC::RTC_OK;
468 }
469 */
470 
471 /*
472 RTC::ReturnCode_t OGMap3DViewer::onStateUpdate(RTC::UniqueId ec_id)
473 {
474  return RTC::RTC_OK;
475 }
476 */
477 
478 /*
479 RTC::ReturnCode_t OGMap3DViewer::onRateChanged(RTC::UniqueId ec_id)
480 {
481  return RTC::RTC_OK;
482 }
483 */
484 
485 
486 
487 extern "C"
488 {
489 
491  {
493  manager->registerFactory(profile,
494  RTC::Create<OGMap3DViewer>,
495  RTC::Delete<OGMap3DViewer>);
496  }
497 
498 };
499 
500 
ComponentProfile m_profile
png_infop png_charpp int png_charpp profile
unsigned int height()
Definition: GLcamera.h:31
void save(int w, int h, const char *i_fname)
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
virtual void render()
void init()
Definition: GLmodel.cpp:362
void draw(bool swap=true)
Definition: GLmodel.cpp:297
HRPMODEL_API OpenHRP::BodyInfo_var loadBodyInfo(const char *url, int &argc, char *argv[])
GLbody * m_body
InPort< TimedDoubleSeq > m_qIn
void addBody(GLbody *i_body)
Definition: GLmodel.cpp:293
png_uint_32 size
void white()
OGMap3DViewer(RTC::Manager *manager)
Constructor.
virtual const aabbox3d< f32 > & getBoundingBox() const
int rank
InPort< TimedPoint3D > m_pIn
CORBA::ORB_ptr getORB()
void OGMap3DViewerInit(RTC::Manager *manager)
unsigned int m_imageCount
OpenHRP::OGMap3D * m_ogmap
png_uint_32 i
coil::Properties & getProperties()
TimedOrientation3D m_rpy
static Manager & instance()
bool m_isGeneratingMovie
irr::core::aabbox3d< f32 > m_box
RTC::CorbaConsumer< OpenHRP::OGMap3DService > m_OGMap3DService
OpenHRP::OGMap3D * m_map
GLcamera * getCamera()
Definition: GLmodel.cpp:429
bool m_generateImageSequence
static GLscene * getInstance()
Definition: GLmodel.cpp:332
virtual ~OGMap3DViewer()
Destructor.
coil::Properties & getConfig()
IplImage * m_cvImage
TimedDoubleSeq m_q
ExecutionContextHandle_t UniqueId
InPort< TimedOrientation3D > m_rpyIn
unsigned int width()
Definition: GLcamera.h:30
void setMap(OpenHRP::OGMap3D *i_map)
void setupCubeVertices(double i_res)
CMapSceneNode(ISceneNode *i_parent, ISceneManager *i_mgr, s32 i_id, double i_origin[3], double i_size[3])
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
RTC::CorbaPort m_OGMap3DServicePort
def j(str, encoding="cp932")
null component
irr::scene::ISceneManager * getSceneManager()
Definition: IrrModel.cpp:572
CMapSceneNode * m_mapNode
png_bytep buf
prop
TimedPoint3D m_p
CvVideoWriter * m_videoWriter
virtual void OnRegisterSceneNode()
naming
static const char * nullcomponent_spec[]
virtual RTC::ReturnCode_t onInitialize()
void setPosture(const double *i_angles)
Definition: GLbody.cpp:21
void capture(int w, int h, unsigned char *o_buffer)
std::string sprintf(char const *__restrict fmt,...)
virtual bool isNew()
png_infop png_bytep buffer
bool addPort(PortBase &port)
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
bool addInPort(const char *name, InPortBase &inport)
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
bool registerConsumer(const char *instance_name, const char *type_name, CorbaConsumerBase &consumer)
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
virtual CORBA::Object_ptr getObject()


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:50