VirtualCamera.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
10 #ifndef __APPLE__
11 #include <GL/glu.h>
12 #else
13 #include <OpenGL/gl.h>
14 #endif
15 #include <rtm/CorbaNaming.h>
16 #include <hrpModel/ModelLoaderUtil.h>
17 #include "hrpsys/util/Project.h"
18 #include "hrpsys/util/VectorConvert.h"
19 #include "hrpsys/util/GLcamera.h"
20 #include "hrpsys/util/GLbody.h"
21 #include "hrpsys/util/GLlink.h"
22 #include "hrpsys/util/GLutil.h"
23 #include "VirtualCamera.h"
24 #include "RTCGLbody.h"
25 #include "GLscene.h"
26 
27 // Module specification
28 // <rtc-template block="module_spec">
29 static const char* virtualcamera_spec[] =
30 {
31  "implementation_id", "VirtualCamera",
32  "type_name", "VirtualCamera",
33  "description", "virtual camera component",
34  "version", HRPSYS_PACKAGE_VERSION,
35  "vendor", "AIST",
36  "category", "example",
37  "activity_type", "DataFlowComponent",
38  "max_instance", "10",
39  "language", "C++",
40  "lang_type", "compile",
41  // Configuration variables
42  "conf.default.rangerMaxAngle", "0.25",
43  "conf.default.rangerMinAngle", "-0.25",
44  "conf.default.rangerAngularRes", "0.01",
45  "conf.default.rangerMaxRange", "5.0",
46  "conf.default.rangerMinRange", "0.5",
47  "conf.default.generateRange", "1",
48  "conf.default.generatePointCloud", "0",
49  "conf.default.generatePointCloudStep", "1",
50  "conf.default.pcFormat", "xyz",
51  "conf.default.generateMovie", "0",
52  "conf.default.debugLevel", "0",
53  "conf.default.project", "",
54  "conf.default.camera", "",
55 
56  ""
57 };
58 // </rtc-template>
59 
61  : RTC::DataFlowComponentBase(manager),
62  // <rtc-template block="initializer">
63  m_sceneStateIn("state", m_sceneState),
64  m_basePosIn("basePos", m_basePos),
65  m_baseRpyIn("baseRpy", m_baseRpy),
66  m_qIn("q", m_q),
67  m_imageOut("image", m_image),
68  m_rangeOut("range", m_range),
69  m_cloudOut("cloud", m_cloud),
70  m_poseSensorOut("poseSensor", m_poseSensor),
71  // </rtc-template>
72  m_scene(&m_log),
73  m_window(&m_scene, &m_log),
74  m_camera(NULL),
75  m_generateRange(true),
76  m_generatePointCloud(false),
77  m_generateMovie(false),
78  m_isGeneratingMovie(false),
79  m_debugLevel(0),
80  dummy(0)
81 {
82  m_scene.showFloorGrid(false);
83  m_scene.showInfo(false);
84 }
85 
87 {
88 }
89 
90 
91 
92 RTC::ReturnCode_t VirtualCamera::onInitialize()
93 {
94  std::cout << m_profile.instance_name << ": onInitialize()" << std::endl;
95  // <rtc-template block="bind_config">
96  // Bind variables and configuration variable
98  bindParameter("rangerMaxAngle", m_range.config.maxAngle, "0.25");
99  bindParameter("rangerMinAngle", m_range.config.minAngle, "-0.25");
100  bindParameter("rangerAngularRes", m_range.config.angularRes, "0.01");
101  bindParameter("rangerMaxRange", m_range.config.maxRange, "5.0");
102  bindParameter("rangerMinRange", m_range.config.minRange, "0.5");
103  bindParameter("generateRange", m_generateRange, "1");
104  bindParameter("generatePointCloud", m_generatePointCloud, "0");
105  bindParameter("generatePointCloudStep", m_generatePointCloudStep, "1");
106  bindParameter("pcFormat", m_pcFormat, ref["conf.default.pcFormat"].c_str());
107  bindParameter("generateMovie", m_generateMovie, "0");
108  bindParameter("debugLevel", m_debugLevel, "0");
109  bindParameter("project", m_projectName, ref["conf.default.project"].c_str());
110  bindParameter("camera", m_cameraName, ref["conf.default.camera"].c_str());
111 
112  // </rtc-template>
113 
114  // Registration: InPort/OutPort/Service
115  // <rtc-template block="registration">
116  // Set InPort buffers
117  addInPort("state", m_sceneStateIn);
118  addInPort("basePos", m_basePosIn);
119  addInPort("baseRpy", m_baseRpyIn);
120  addInPort("q", m_qIn);
121 
122  // Set OutPort buffer
123  addOutPort("image", m_imageOut);
124  addOutPort("range", m_rangeOut);
125  addOutPort("cloud", m_cloudOut);
126  addOutPort("poseSensor", m_poseSensorOut);
127 
128  // Set service provider to Ports
129 
130  // Set service consumers to Ports
131 
132  // Set CORBA Service Ports
133 
134  // </rtc-template>
135 
136  return RTC::RTC_OK;
137 }
138 
139 
140 
141 /*
142  RTC::ReturnCode_t VirtualCamera::onFinalize()
143  {
144  return RTC::RTC_OK;
145  }
146 */
147 
148 /*
149  RTC::ReturnCode_t VirtualCamera::onStartup(RTC::UniqueId ec_id)
150  {
151  return RTC::RTC_OK;
152  }
153 */
154 
155 /*
156  RTC::ReturnCode_t VirtualCamera::onShutdown(RTC::UniqueId ec_id)
157  {
158  return RTC::RTC_OK;
159  }
160 */
161 
163 {
164  std::cout << m_profile.instance_name<< ": onActivated(" << ec_id << ")" << std::endl;
165 
166  //RTC::Properties& prop = getProperties();
167 
168  RTC::Manager& rtcManager = RTC::Manager::instance();
169  RTC::CorbaNaming naming(rtcManager.getORB(), "localhost:2809");
170  CORBA::Object_ptr obj = naming.resolve("ModelLoader");
171  if (!CORBA::is_nil(obj)){
172  std::cout << "found ModelLoader on localhost:2809" << std::endl;
173  }else{
174  std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
175  int comPos = nameServer.find(",");
176  if (comPos < 0){
177  comPos = nameServer.length();
178  }
179  nameServer = nameServer.substr(0, comPos);
180  naming.init(nameServer.c_str());
181  }
182 
183  if (m_projectName == ""){
184  std::cerr << "Project file is not specified." << std::endl;
185  return RTC::RTC_ERROR;
186  }
187 
188  Project prj;
189  if (!prj.parse(m_projectName)) return RTC::RTC_ERROR;
190 
191  unsigned int pos = m_cameraName.find(':',0);
192  std::string bodyName, cameraName;
193  if (pos == std::string::npos){
194  std::cerr << "can't find a separator in the camera name" << std::endl;
195  return RTC::RTC_ERROR;
196  }else{
197  bodyName = m_cameraName.substr(0, pos);
198  cameraName = m_cameraName.substr(pos+1);
199  std::cout << "body:" << bodyName << ", camera:" << cameraName << std::endl;
200  }
201 
202  std::vector<std::pair<std::string, OpenHRP::BodyInfo_var> > binfos;
203  int w=0, h=0;
204  OpenHRP::ModelLoader_var ml = hrp::getModelLoader(CosNaming::NamingContext::_duplicate(naming.getRootContext()));
205  for (std::map<std::string, ModelItem>::iterator it=prj.models().begin();
206  it != prj.models().end(); it++){
207 
208  OpenHRP::BodyInfo_var binfo;
209  OpenHRP::ModelLoader::ModelLoadOption opt;
210  opt.readImage = true;
211  opt.AABBdata.length(0);
212  opt.AABBtype = OpenHRP::ModelLoader::AABB_NUM;
213  binfo = ml->getBodyInfoEx(it->second.url.c_str(), opt);
214  if (CORBA::is_nil(binfo)){
215  std::cerr << "failed to load model[" << it->second.url << "]"
216  << std::endl;
217  return RTC::RTC_ERROR;
218  }
219 
220  // look for camera
221  if (it->first == bodyName){
222  OpenHRP::LinkInfoSequence_var lis = binfo->links();
223  for (unsigned int i=0; i<lis->length(); i++){
224  const OpenHRP::SensorInfoSequence& sensors = lis[i].sensors;
225  for (unsigned int j=0; j<sensors.length(); j++){
226  const OpenHRP::SensorInfo& si = sensors[j];
227  std::string type(si.type);
228  std::string name(si.name);
229  if (type == "Vision" && name == cameraName){
230  w = si.specValues[4];
231  h = si.specValues[5];
232  break;
233  }
234  }
235  }
236  if (!w || !h){
237  std::cout << "invalid image size:" << w << "x" << h << std::endl;
238  return RTC::RTC_ERROR;
239  }
240  }
241  binfos.push_back(std::make_pair(it->first, binfo));
242  }
243 
244  m_window.init(w,h,false);
245  RTCGLbody *robot=NULL;
246  for (unsigned int i=0; i<binfos.size(); i++){
247  GLbody *glbody = new GLbody();
248  hrp::BodyPtr body(glbody);
249  hrp::loadBodyFromBodyInfo(body, binfos[i].second, false, GLlinkFactory);
250  loadShapeFromBodyInfo(glbody, binfos[i].second);
251  body->setName(binfos[i].first);
252  m_scene.WorldBase::addBody(body);
253  RTCGLbody *rtcglbody = new RTCGLbody(glbody, this);
254  m_bodies[binfos[i].first] = rtcglbody;
255  if (binfos[i].first == bodyName){
256  robot = rtcglbody;
257  }
258  }
259  if (!robot) {
260  std::cerr << "can't find a robot named " << bodyName << std::endl;
261  }
262  m_camera = robot->body()->findCamera(cameraName.c_str());
263  if (!m_camera){
264  std::cerr << "VirtualCamera: can't find camera("
265  << cameraName << ")" << std::endl;
266  return RTC::RTC_ERROR;
267  }
269 
270  m_image.data.image.width = m_camera->width();
271  m_image.data.image.height = m_camera->height();
272  m_image.data.image.format = Img::CF_RGB;
273  m_image.data.image.raw_data.length(m_image.data.image.width*m_image.data.image.height*3);
274 
275  return RTC::RTC_OK;
276 }
277 
279 {
280  std::cout << m_profile.instance_name<< ": onDeactivated(" << ec_id << ")" << std::endl;
281  return RTC::RTC_OK;
282 }
283 
284 void capture(int w, int h, unsigned char *o_buffer)
285 {
286  glReadBuffer(GL_BACK);
287  glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
288  for (int i=0; i<h; i++){
289  glReadPixels(0,(h-1-i),w,1,GL_RGB,GL_UNSIGNED_BYTE,
290  o_buffer + i*3*w);
291  }
292 }
293 
294 RTC::ReturnCode_t VirtualCamera::onExecute(RTC::UniqueId ec_id)
295 {
296  if (m_debugLevel > 0) std::cout << m_profile.instance_name<< ": onExecute(" << ec_id << ") " << std::endl;
298 
299  if (m_sceneStateIn.isNew()){
300  do{
302  }while(m_sceneStateIn.isNew());
303  for (unsigned int i=0; i<m_sceneState.states.length(); i++){
304  const OpenHRP::RobotState& state = m_sceneState.states[i];
305  std::string name(state.name);
306  RTCGLbody *rtcglb=m_bodies[name];
307  if (rtcglb){
308  GLbody *body = rtcglb->body();
309  body->setPosition(state.basePose.position.x,
310  state.basePose.position.y,
311  state.basePose.position.z);
312  body->setRotation(state.basePose.orientation.r,
313  state.basePose.orientation.p,
314  state.basePose.orientation.y);
315  body->setPosture(state.q.get_buffer());
316  }
317  }
318  }
319  GLbody *body = dynamic_cast<GLbody *>(m_camera->link()->body);
320  if (m_basePosIn.isNew()){
321  do{
322  m_basePosIn.read();
323  }while(m_basePosIn.isNew());
324  body->setPosition(m_basePos.data.x, m_basePos.data.y, m_basePos.data.z);
325  }
326  if (m_baseRpyIn.isNew()){
327  do{
328  m_baseRpyIn.read();
329  }while(m_baseRpyIn.isNew());
330  body->setRotation(m_baseRpy.data.r, m_baseRpy.data.p, m_baseRpy.data.y);
331  }
332  if (m_qIn.isNew()){
333  do{
334  m_qIn.read();
335  }while(m_qIn.isNew());
336  body->setPosture(m_q.data.get_buffer());
337  }
338 
339  for (std::map<std::string, RTCGLbody *>::iterator it=m_bodies.begin();
340  it != m_bodies.end(); it++){
341  it->second->input();
342  }
343 
345  m_window.draw();
347  capture(m_camera->width(), m_camera->height(), m_image.data.image.raw_data.get_buffer());
349 
350  double *T = m_camera->getAbsTransform();
351  hrp::Vector3 p;
352  p[0] = T[12];
353  p[1] = T[13];
354  p[2] = T[14];
356  R(0,0) = T[0]; R(0,1) = T[4]; R(0,2) = T[8];
357  R(1,0) = T[1]; R(1,1) = T[5]; R(1,2) = T[9];
358  R(2,0) = T[2]; R(2,1) = T[6]; R(2,2) = T[10];
359  hrp::Vector3 rpy = hrp::rpyFromRot(R);
360  m_poseSensor.data.position.x = p[0];
361  m_poseSensor.data.position.y = p[1];
362  m_poseSensor.data.position.z = p[2];
363  m_poseSensor.data.orientation.r = rpy[0];
364  m_poseSensor.data.orientation.p = rpy[1];
365  m_poseSensor.data.orientation.y = rpy[2];
366 
372  if (m_generateMovie){
373  if (!m_isGeneratingMovie){
374  std::string fname(m_profile.instance_name);
375  fname += ".avi";
376  m_videoWriter = cvCreateVideoWriter(
377  fname.c_str(),
378  CV_FOURCC('D','I','V','X'),
379  10,
380  cvSize(m_image.data.image.width, m_image.data.image.height));
381  m_cvImage = cvCreateImage(
382  cvSize(m_image.data.image.width, m_image.data.image.height),
383  IPL_DEPTH_8U, 3);
384  m_isGeneratingMovie = true;
385  }
386  // RGB -> BGR
387  char *dst = m_cvImage->imageData;
388  for (int i=0; i<m_image.data.image.width*m_image.data.image.height; i++){
389  dst[i*3 ] = m_image.data.image.raw_data[i*3+2];
390  dst[i*3+1] = m_image.data.image.raw_data[i*3+1];
391  dst[i*3+2] = m_image.data.image.raw_data[i*3 ];
392  }
393  cvWriteFrame(m_videoWriter, m_cvImage);
394  }else{
395  if (m_isGeneratingMovie){
396  cvReleaseVideoWriter(&m_videoWriter);
397  cvReleaseImage(&m_cvImage);
398  m_isGeneratingMovie = false;
399  }
400  }
401 
402  m_imageOut.write();
406 
408  if (m_debugLevel > 0){
409  coil::TimeValue dt;
410  dt = t5-t1;
411  std::cout << "VirtualCamera::onExecute() : total:"
412  << dt.sec()*1e3+dt.usec()/1e3;
413  dt = t7-t6;
414  std::cout << ", render:"
415  << dt.sec()*1e3+dt.usec()/1e3;
416 
417  if (m_generateRange){
418  dt = t3 - t2;
419  std::cout << ", range2d:" << dt.sec()*1e3+dt.usec()/1e3;
420  }
422  dt = t4 - t3;
423  std::cout << ", range3d:" << dt.sec()*1e3+dt.usec()/1e3;
424  }
425  std::cout << "[ms]" << std::endl;
426  }
427 
428  return RTC::RTC_OK;
429 }
430 
432 {
433  int w = m_camera->width();
434  int h = m_camera->height();
435  float depth[w];
436  glReadPixels(0, h/2, w, 1, GL_DEPTH_COMPONENT, GL_FLOAT, depth);
437  double far = m_camera->far();
438  double near = m_camera->near();
439  double fovx = 2*atan(w*tan(m_camera->fovy()/2)/h);
440  RangerConfig &rc = m_range.config;
441  double max = ((int)(fovx/2/rc.angularRes))*rc.angularRes;
442  if (rc.maxAngle > max) rc.maxAngle = max;
443  if (rc.minAngle < -max) rc.minAngle = -max;
444  unsigned int nrange = round((rc.maxAngle - rc.minAngle)/rc.angularRes)+1;
445  //std::cout << "nrange = " << nrange << std::endl;
446  m_range.ranges.length(nrange);
447 #define THETA(x) (-atan(((x)-w/2)*2*tan(fovx/2)/w))
448 #define RANGE(d,th) (-far*near/((d)*(far-near)-far)/cos(th))
449  double dth, alpha, th, th_old = THETA(w-1);
450  double r, r_old = RANGE(depth[w-1], th_old);
451  int idx = w-2;
452  double angle;
453  for (unsigned int i=0; i<nrange; i++){
454  angle = rc.minAngle + rc.angularRes*i;
455  while(idx >= 0){
456  th = THETA(idx);
457  r = RANGE(depth[idx], th);
458  idx--;
459  if (th > angle){
460  //std::cout << idx << ":" << th << std::endl;
461  dth = th - th_old;
462  alpha = atan2(r*sin(dth), fabs(r_old - r*cos(dth)));
463  //std::cout << "alpha:" << alpha << std::endl;
464  if (r != 0 && r_old != 0 && alpha > 0.01){
465  m_range.ranges[i] = ((th - angle)*r_old + (angle - th_old)*r)/dth;
466  }else if (th - angle < dth/2){
467  m_range.ranges[i] = r;
468  }else{
469  m_range.ranges[i] = r_old;
470  }
471  if (m_range.ranges[i] > rc.maxRange
472  || m_range.ranges[i] < rc.minRange){
473  m_range.ranges[i] = rc.maxRange;
474  }
475  th_old = th;
476  r_old = r;
477  break;
478  }
479  th_old = th;
480  r_old = r;
481  }
482 #if 0
483  std::cout << angle << " " << depth[idx] << " " << m_range.ranges[i] << " "
484  << m_range.ranges[i]*cos(angle) << " " << m_range.ranges[i]*sin(angle) << std::endl;
485 #endif
486  }
487 }
488 
490 {
491  int w = m_camera->width();
492  int h = m_camera->height();
493  float depth[w*h];
494  m_cloud.width = w;
495  m_cloud.height = h;
496  m_cloud.type = m_pcFormat.c_str();
497  bool colored = false;
498  if (m_pcFormat == "xyz"){
499  m_cloud.fields.length(3);
500  }else if (m_pcFormat == "xyzrgb"){
501  m_cloud.fields.length(6);
502  colored = true;
503  }else{
504  std::cerr << "unknown point cloud format:[" << m_pcFormat << "]" << std::endl;
505  }
506  m_cloud.fields[0].name = "x";
507  m_cloud.fields[0].offset = 0;
508  m_cloud.fields[0].data_type = PointCloudTypes::FLOAT32;
509  m_cloud.fields[0].count = 4;
510  m_cloud.fields[1].name = "y";
511  m_cloud.fields[1].offset = 4;
512  m_cloud.fields[1].data_type = PointCloudTypes::FLOAT32;
513  m_cloud.fields[1].count = 4;
514  m_cloud.fields[2].name = "z";
515  m_cloud.fields[2].offset = 8;
516  m_cloud.fields[2].data_type = PointCloudTypes::FLOAT32;
517  m_cloud.fields[2].count = 4;
518  if (m_pcFormat == "xyzrgb"){
519  m_cloud.fields[3].name = "r";
520  m_cloud.fields[3].offset = 12;
521  m_cloud.fields[3].data_type = PointCloudTypes::UINT8;
522  m_cloud.fields[3].count = 1;
523  m_cloud.fields[4].name = "g";
524  m_cloud.fields[4].offset = 13;
525  m_cloud.fields[4].data_type = PointCloudTypes::UINT8;
526  m_cloud.fields[4].count = 1;
527  m_cloud.fields[5].name = "b";
528  m_cloud.fields[5].offset = 14;
529  m_cloud.fields[5].data_type = PointCloudTypes::UINT8;
530  m_cloud.fields[5].count = 1;
531  }
532  m_cloud.is_bigendian = false;
533  m_cloud.point_step = 16;
534  m_cloud.data.length(w*h*m_cloud.point_step);// will be shrinked later
535  m_cloud.row_step = m_cloud.point_step*w;
536  m_cloud.is_dense = true;
537  double far = m_camera->far();
538  double near = m_camera->near();
539  double fovx = 2*atan(w*tan(m_camera->fovy()/2)/h);
540  double zs = w/(2*tan(fovx/2));
541  unsigned int npoints=0;
542  float *ptr = (float *)m_cloud.data.get_buffer();
543  unsigned char *rgb = m_image.data.image.raw_data.get_buffer();
544  glReadPixels(0,0, w, h, GL_DEPTH_COMPONENT, GL_FLOAT, depth);
545  for (int i=0; i<h; i+=m_generatePointCloudStep){
546  for (int j=0; j<w; j+=m_generatePointCloudStep){
547  float d = depth[i*w+j];
548  if (d == 1.0) {
549  continue;
550  }
551  ptr[2] = far*near/(d*(far-near)-far);
552  ptr[0] = -(j-w/2)*ptr[2]/zs;
553  ptr[1] = -(i-h/2)*ptr[2]/zs;
554  if (colored){
555  unsigned char *c = (unsigned char *)(ptr + 3);
556  int offset = ((h-1-i)*w+j)*3;
557  c[0] = rgb[offset];
558  c[1] = rgb[offset+1];
559  c[2] = rgb[offset+2];
560  }
561  ptr += 4;
562  npoints++;
563  }
564  }
565  m_cloud.data.length(npoints*m_cloud.point_step);
566 }
567 /*
568  RTC::ReturnCode_t VirtualCamera::onAborting(RTC::UniqueId ec_id)
569  {
570  return RTC::RTC_OK;
571  }
572 */
573 
574 /*
575  RTC::ReturnCode_t VirtualCamera::onError(RTC::UniqueId ec_id)
576  {
577  return RTC::RTC_OK;
578  }
579 */
580 
581 /*
582  RTC::ReturnCode_t VirtualCamera::onReset(RTC::UniqueId ec_id)
583  {
584  return RTC::RTC_OK;
585  }
586 */
587 
588 /*
589  RTC::ReturnCode_t VirtualCamera::onStateUpdate(RTC::UniqueId ec_id)
590  {
591  return RTC::RTC_OK;
592  }
593 */
594 
595 /*
596  RTC::ReturnCode_t VirtualCamera::onRateChanged(RTC::UniqueId ec_id)
597  {
598  return RTC::RTC_OK;
599  }
600 */
601 
602 
603 
604 extern "C"
605 {
606 
608  {
610  manager->registerFactory(profile,
611  RTC::Create<VirtualCamera>,
612  RTC::Delete<VirtualCamera>);
613  }
614 
615 };
616 
617 
ComponentProfile m_profile
d
GLcamera * m_camera
png_infop png_charpp int png_charpp profile
unsigned int height()
Definition: GLcamera.h:31
bool m_generatePointCloud
#define max(a, b)
double * getAbsTransform()
Definition: GLcamera.cpp:108
void draw()
Definition: SDLUtil.cpp:308
RTC::TimedOrientation3D m_baseRpy
void VirtualCameraInit(RTC::Manager *manager)
std::map< std::string, RTCGLbody * > m_bodies
InPort< RTC::TimedOrientation3D > m_baseRpyIn
png_infop png_charp png_int_32 png_int_32 int * type
VirtualCamera(RTC::Manager *manager)
Constructor.
void showFloorGrid(bool flag)
virtual ~VirtualCamera()
Destructor.
long int sec() const
virtual RTC::ReturnCode_t onInitialize()
HRPMODEL_API OpenHRP::ModelLoader_var getModelLoader(CosNaming::NamingContext_var cxt)
state
void setPosition(double x, double y, double z)
Definition: GLbody.cpp:27
bool parse(const std::string &filename)
Definition: Project.cpp:32
double near()
Definition: GLcamera.h:27
png_voidp ptr
void capture(int w, int h, unsigned char *o_buffer)
virtual camera component
png_infop png_charpp name
bool init(int w=0, int h=0, bool resizable=true)
Definition: SDLUtil.cpp:54
HRPMODEL_API bool loadBodyFromBodyInfo(BodyPtr body, OpenHRP::BodyInfo_ptr bodyInfo, bool loadGeometryForCollisionDetection=false, Link *(*f)()=NULL)
CORBA::ORB_ptr getORB()
w
void loadShapeFromBodyInfo(GLbody *body, BodyInfo_var i_binfo, GLshape *(*shapeFactory)())
Definition: GLutil.cpp:181
OutPort< RangeData > m_rangeOut
bool m_isGeneratingMovie
png_uint_32 i
double fovy()
Definition: GLcamera.h:29
coil::Properties & getProperties()
static Manager & instance()
Img::TimedCameraImage m_image
bool addOutPort(const char *name, OutPortBase &outport)
GLlink * link()
Definition: GLcamera.cpp:112
#define RANGE(d, th)
Definition: GLbody.h:11
Eigen::Vector3d Vector3
SDLwindow m_window
#define THETA(x)
void setRotation(const double *R)
Definition: GLbody.cpp:37
Eigen::Matrix3d Matrix33
InPort< RTC::TimedPoint3D > m_basePosIn
int gettimeofday(struct timeval *tv, struct timezone *tz)
coil::Properties & getConfig()
ExecutionContextHandle_t UniqueId
int m_generatePointCloudStep
unsigned int width()
Definition: GLcamera.h:30
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
std::string m_cameraName
IplImage * m_cvImage
def j(str, encoding="cp932")
OutPort< Img::TimedCameraImage > m_imageOut
std::string m_pcFormat
GLcamera * findCamera(const char *i_name)
Definition: GLbody.cpp:71
std::map< std::string, ModelItem > & models()
Definition: Project.h:114
TimedPose3D m_poseSensor
CvVideoWriter * m_videoWriter
HRP_UTIL_EXPORT Vector3 rpyFromRot(const Matrix33 &m)
naming
InPort< OpenHRP::SceneState > m_sceneStateIn
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
typedef int
void setPosture(const double *i_angles)
Definition: GLbody.cpp:21
void setCamera(GLcamera *i_camera)
Definition: GLmodel.cpp:420
OutPort< TimedPose3D > m_poseSensorOut
void showInfo(bool flag)
virtual bool isNew()
virtual bool write(DataType &value)
OpenHRP::SceneState m_sceneState
void swapBuffers()
Definition: SDLUtil.cpp:337
PointCloudTypes::PointCloud m_cloud
OutPort< PointCloudTypes::PointCloud > m_cloudOut
void setupPointCloud()
long int usec() const
static const char * virtualcamera_spec[]
InPort< RTC::TimedDoubleSeq > m_qIn
bool addInPort(const char *name, InPortBase &inport)
obj
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
RTC::TimedDoubleSeq m_q
RTC::TimedPoint3D m_basePos
std::string m_projectName
RangeData m_range
double far()
Definition: GLcamera.h:28
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
GLbody * body()


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