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
00031 #ifndef _wrapper_collada_H_
00032 #define _wrapper_collada_H_
00033
00042
00045
00046
00047
00050 #include <ros/ros.h>
00051
00052 #include <dae.h>
00053 #include <dom/domConstants.h>
00054 #include <dom/domCOLLADA.h>
00055 #include <dom/domProfile_common.h>
00056 #include <dae/daeSIDResolver.h>
00057 #include <dom/domInstance_controller.h>
00058 #include <dae/domAny.h>
00059 #include <dae/daeErrorHandler.h>
00060 #include <dae/daeUtils.h>
00061 #include <dom/domImage.h>
00062 #include <modules/stdErrPlugin.h>
00063 #include <dom/domEllipsoid.h>
00064 #include <dom/domInput_global.h>
00065 #include <dom/domAsset.h>
00066
00067
00068
00069 #include <pcl_ros/point_cloud.h>
00070 #include <pcl/point_types.h>
00071
00072
00073
00076
00077 using namespace ColladaDOM150;
00078
00079 class wrapper_collada
00080 {
00081 public:
00082 wrapper_collada(std::string fl)
00083 {
00084 file_name = fl;
00085 root = dae.add(file_name);
00086 daeElement* asset = root->add("asset");
00087
00088 daeElement* created = asset->add("created");
00089 daeElement* modified = asset->add("modified");
00090 const char* date = "2008-04-08T13:07:52-08:00";
00091 created->setCharData(date);
00092 modified->setCharData(date);
00093
00094
00095 daeElement* visualSceneLib = root->add("library_visual_scenes");
00096 visualScene = visualSceneLib->add("visual_scene");
00097 visualScene->setAttribute("id", "defaultScene");
00098
00099
00100 root->add("scene instance_visual_scene")->setAttribute("url", makeUriRef("defaultScene").c_str());
00101 }
00102
00103 ~wrapper_collada(){};
00104
00105 void add_polygon_fixed_color(std::string polygon_name, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::PointCloud<pcl::PointXYZ>::Ptr normal, float r, float g, float b, float a);
00106
00107 void add_polygon_fixed_color_on_both_sides(std::string polygon_name, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::PointCloud<pcl::PointXYZ>::Ptr normal, float r, float g, float b, float a)
00108 {
00109
00110 add_polygon_fixed_color(polygon_name, cloud, normal, r, g, b, a);
00111
00112
00113
00114 pcl::PointCloud<pcl::PointXYZ> normal_flip;
00115 pcl::PointXYZ p;
00116 p.x = -normal->points[0].x;
00117 p.y = -normal->points[0].y;
00118 p.z = -normal->points[0].z;
00119 normal_flip.points.push_back(p);
00120
00121
00122 pcl::PointCloud<pcl::PointXYZ> cloud_flip;
00123
00124 for (int i=((int)cloud->points.size()-1); i>=0; i--)
00125 {
00126 cloud_flip.points.push_back(cloud->points[i]);
00127 }
00128
00129
00130 add_polygon_fixed_color((polygon_name + "_flip").c_str(), cloud_flip.makeShared(), normal_flip.makeShared(), r, g, b, a);
00131
00132 };
00133
00134
00135 void write_file()
00136 {
00137 ROS_INFO("Writting collada file %s",file_name.c_str());
00138 dae.writeAll();
00139 }
00140
00141
00142 private:
00143
00144 DAE dae;
00145 std::string file_name;
00146 daeElement* root;
00147 daeElement* visualScene;
00148
00149
00150 void my_addInput(daeElement* triangles,
00151 const std::string& semantic,
00152 const std::string& srcID,
00153 int offset);
00154
00155
00156 std::string makeUriRef(const std::string& id);
00157
00158 void my_addGeometry(daeElement* root);
00159 void my_addVisualScene(daeElement* root);
00160 void my_addEffect(daeElement* root);
00161 void my_addMaterial(daeElement* root);
00162 void my_addImage(daeElement* root);
00163 void my_addSource(daeElement* mesh,
00164 const std::string& srcID,
00165 const std::string& paramNames,
00166 domFloat values[],
00167 int valueCount);
00168 daeTArray<double> pcl_pointcloud_tp_daearray(pcl::PointCloud<pcl::PointXYZ>::Ptr pc);
00169 template<typename T_wc>
00170 daeTArray<T_wc> rawArrayToDaeArray(T_wc rawArray[], size_t count);
00171
00172 };
00173
00174 #endif
00175