PCDLoader.h
Go to the documentation of this file.
1 // -*- C++ -*-
10 #ifndef PCD_LOADER_H
11 #define PCD_LOADER_H
12 
13 #include <rtm/idl/BasicDataType.hh>
14 #include "hrpsys/idl/pointcloud.hh"
15 #include "hrpsys/idl/PCDLoaderService.hh"
16 #include <rtm/Manager.h>
17 #include <rtm/DataFlowComponentBase.h>
18 #include <rtm/CorbaPort.h>
19 #include <rtm/DataInPort.h>
20 #include <rtm/DataOutPort.h>
21 #include <rtm/idl/BasicDataTypeSkel.h>
22 #include <pcl/io/pcd_io.h>
23 #include <boost/unordered_map.hpp>
24 #include <hrpUtil/Eigen3d.h>
25 #include "PCDLoaderService_impl.h"
26 
27 // Service implementation headers
28 // <rtc-template block="service_impl_h">
29 
30 // </rtc-template>
31 
32 // Service Consumer stub headers
33 // <rtc-template block="consumer_stub_h">
34 
35 // </rtc-template>
36 
37 using namespace RTC;
38 
42 class PCDLoader
44 {
45  public:
54  virtual ~PCDLoader();
55 
56  // The initialize action (on CREATED->ALIVE transition)
57  // formaer rtc_init_entry()
58  virtual RTC::ReturnCode_t onInitialize();
59 
60  // The finalize action (on ALIVE->END transition)
61  // formaer rtc_exiting_entry()
62  // virtual RTC::ReturnCode_t onFinalize();
63 
64  // The startup action when ExecutionContext startup
65  // former rtc_starting_entry()
66  // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id);
67 
68  // The shutdown action when ExecutionContext stop
69  // former rtc_stopping_entry()
70  // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id);
71 
72  // The activated action (Active state entry action)
73  // former rtc_active_entry()
74  virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
75 
76  // The deactivated action (Active state exit action)
77  // former rtc_active_exit()
78  virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
79 
80  // The execution action that is invoked periodically
81  // former rtc_active_do()
82  virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
83 
84  // The aborting action when main logic error occurred.
85  // former rtc_aborting_entry()
86  // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id);
87 
88  // The error action in ERROR state
89  // former rtc_error_do()
90  // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id);
91 
92  // The reset action that is invoked resetting
93  // This is same but different the former rtc_init_entry()
94  // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id);
95 
96  // The state update action that is invoked after onExecute() action
97  // no corresponding operation exists in OpenRTm-aist-0.2.0
98  // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id);
99 
100  // The action that is invoked when execution context's rate is changed
101  // no corresponding operation exists in OpenRTm-aist-0.2.0
102  // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id);
103 
104  bool load(const std::string& filename, const std::string& label);
105 
106 protected:
107  // Configuration variable declaration
108  // <rtc-template block="config_declare">
109 
110  // </rtc-template>
111 
112  PointCloudTypes::PointCloud m_cloud;
113  OpenHRP::PCDOffsetSeq m_offset;
114  RTC::TimedBoolean m_isOutput;
115 
116  // DataInPort declaration
117  // <rtc-template block="inport_declare">
118 
120 
121  // </rtc-template>
122 
123  // DataOutPort declaration
124  // <rtc-template block="outport_declare">
127 
128  // </rtc-template>
129 
130  // CORBA Port declaration
131  // <rtc-template block="corbaport_declare">
133 
134  // </rtc-template>
135 
136  // Service declaration
137  // <rtc-template block="service_declare">
139 
140  // </rtc-template>
141 
142  // Consumer declaration
143  // <rtc-template block="consumer_declare">
144 
145  // </rtc-template>
146 
147  void setCloudXYZ(PointCloudTypes::PointCloud& cloud, const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_raw);
148 
149  void setCloudXYZRGB(PointCloudTypes::PointCloud& cloud, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_raw);
150 
151  void updateOffsetToCloudXYZ(void);
152 
153  void updateOffsetToCloudXYZRGB(void);
154 
155  private:
156  std::string m_path, m_fields;
157  int dummy;
158  boost::unordered_map<std::string, pcl::PointCloud<pcl::PointXYZ>::Ptr> m_clouds_xyz;
159  boost::unordered_map<std::string, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> m_clouds_xyzrgb;
160 };
161 
162 
163 extern "C"
164 {
166 };
167 
168 #endif // PCD_LOADER_H
ec_id
std::string m_path
Definition: PCDLoader.h:156
boost::unordered_map< std::string, pcl::PointCloud< pcl::PointXYZ >::Ptr > m_clouds_xyz
Definition: PCDLoader.h:158
char * filename
manager
boost::unordered_map< std::string, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > m_clouds_xyzrgb
Definition: PCDLoader.h:159
PCDLoaderService_impl m_service0
Definition: PCDLoader.h:138
InPort< OpenHRP::PCDOffsetSeq > m_offsetIn
Definition: PCDLoader.h:119
ExecutionContextHandle_t UniqueId
OutPort< PointCloudTypes::PointCloud > m_cloudOut
Definition: PCDLoader.h:125
OutPort< RTC::TimedBoolean > m_isOutputOut
Definition: PCDLoader.h:126
sample RT component which has one data input port and one data output port
Definition: PCDLoader.h:42
int dummy
Definition: PCDLoader.h:157
OpenHRP::PCDOffsetSeq m_offset
Definition: PCDLoader.h:113
RTC::CorbaPort m_PCDLoaderServicePort
Definition: PCDLoader.h:132
PointCloudTypes::PointCloud m_cloud
Definition: PCDLoader.h:112
RTC::TimedBoolean m_isOutput
Definition: PCDLoader.h:114
void PCDLoaderInit(RTC::Manager *manager)
Definition: PCDLoader.cpp:395


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