ROS插件:rviz tool

建立一个ros package如上图所示,插件需要描述文件plugin_description.xml ,flag.dae文件是插件使用的显示效果。插件做好后效果如下:

point_grabber.h代码如下:

#ifndef POINT_GRABBER_H
#define POINT_GRABBER_H

#ifndef Q_MOC_RUN
#include <ros/ros.h>
#include <rviz/panel.h>
#include <rviz/tool.h>
#include <xcb/xcb.h>
#endif

#include <geometry_msgs/PoseArray.h>
#include <geometry_msgs/PoseStamped.h>
#include <std_msgs/Bool.h>
#include <std_msgs/String.h>

#include <OGRE/OgreEntity.h>
#include <OGRE/OgreSceneManager.h>
#include <OGRE/OgreSceneNode.h>


class PointGrabber : public rviz::Tool {
  Q_OBJECT

 public:
  PointGrabber();
  virtual int processMouseEvent(rviz::ViewportMouseEvent &event);
  virtual void activate();
  virtual void deactivate();
  virtual void onInitialize();

 private:
  void makeFlag(const Ogre::Vector3 &position);

  ros::Publisher pub_click_up;
  ros::NodeHandle nh_;
  geometry_msgs::Pose leftdown_ps;
  std::vector<Ogre::SceneNode *> flag_nodes_;
  Ogre::SceneNode *moving_flag_node_;
  std::string flag_resource_;
};

#endif  // SIMU_PARAM_PANEL_H

point_grabber.cpp代码如下:

#include <geometry_msgs/PoseArray.h>
#include <ros/package.h>
#include <rviz/frame_manager.h>
#include <rviz/geometry.h>
#include <rviz/mesh_loader.h>
#include <rviz/viewport_mouse_event.h>
#include <rviz/visualization_manager.h>
#include <std_msgs/Bool.h>
#include <std_msgs/String.h>

#include "point_grabber.h"

PointGrabber::PointGrabber() : moving_flag_node_(NULL) {
  pub_click_up = nh_.advertise<geometry_msgs::Pose>("/grab_a_point", 1);
}

void PointGrabber::onInitialize() {
  flag_resource_ = "package://point_grabber/media/flag.dae";
  if (rviz::loadMeshFromResource(flag_resource_).isNull()) {
    ROS_ERROR("PointGrabber: failed to load model resource '%s'.",flag_resource_.c_str());
    return;
  }
  moving_flag_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
  Ogre::Entity *entity = scene_manager_->createEntity(flag_resource_);
  moving_flag_node_->attachObject(entity);
  moving_flag_node_->setVisible(false);
}

void PointGrabber::activate() {
  if (moving_flag_node_) moving_flag_node_->setVisible(true);
}

void PointGrabber::deactivate() {
  if (moving_flag_node_) moving_flag_node_->setVisible(false);
  for (unsigned i = 0; i < flag_nodes_.size(); i++)
    scene_manager_->destroySceneNode(flag_nodes_[i]);
  flag_nodes_.clear();
}

int PointGrabber::processMouseEvent(rviz::ViewportMouseEvent &event) {
  if (!moving_flag_node_) return Render;
  Ogre::Vector3 intersection;
  Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, 0.0f);
  if (rviz::getPointOnPlaneFromWindowXY(event.viewport, ground_plane, event.x,
                                        event.y, intersection)) {
    moving_flag_node_->setVisible(true);
    moving_flag_node_->setPosition(intersection);
    if (event.leftDown()) {
      makeFlag(intersection);
      leftdown_ps.position.x = intersection.x /*+ transform_.getOrigin().x()*/;  // event.x;
      leftdown_ps.position.y = intersection.y /*+ transform_.getOrigin().y()*/;  // event.y;
      leftdown_ps.position.z = 0;                           // 0;
      pub_click_up.publish(leftdown_ps);
      return Render;
    } else if (event.rightDown()) {
      return Render | Finished;
    }
  }
  return Render;
}

void PointGrabber::makeFlag(const Ogre::Vector3 &position) {
  Ogre::SceneNode *node =
      scene_manager_->getRootSceneNode()->createChildSceneNode();
  Ogre::Entity *entity = scene_manager_->createEntity(flag_resource_);
  node->attachObject(entity);
  node->setVisible(true);
  node->setPosition(position);
  flag_nodes_.push_back(node);
}

#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(PointGrabber,rviz::Tool)

CMakeLists.txt代码如下:

cmake_minimum_required(VERSION 3.0.2)
project(point_grabber)

SET(CMAKE_CXX_FLAGS "-std=c++11 -O2 -g -Wall -Wno-unused-result -DROS ${CMAKE_CXX_FLAGS}")
add_definitions(-DQT_NO_KEYWORDS -g)
set(CMAKE_AUTOMOC ON)

find_package(catkin REQUIRED COMPONENTS  
               std_msgs
               rviz)

if(rviz_QT_VERSION VERSION_LESS "5")
     message(STATUS "Using Qt4 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}")
     find_package(Qt4 ${rviz_QT_VERSION} EXACT REQUIRED QtCore QtGui)
     include(${QT_USE_FILE})
else()
     message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}")
     find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets)
     set(QT_LIBRARIES Qt5::Widgets)
endif()


catkin_package(
     CATKIN_DEPENDS rviz std_msgs 
     DEPENDS rviz
)

include_directories(${catkin_INCLUDE_DIRS})

add_library(${PROJECT_NAME} 
     src/point_grabber.cpp
     ${UIC_FILES}
     )

target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES} ${rviz_DEFAULT_PLUGIN_LIBRARIES})

package.xml代码如下:

<?xml version="1.0"?>
<package>
  <name>point_grabber</name>
  <version>0.0.0</version>
  <description>The point_grabber package</description>
  <maintainer email="zubing.liu@allride.ai">zubing.liu</maintainer>

  <license>BSD</license>
  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>rviz</build_depend>
  <build_depend>std_msgs</build_depend>
  <build_depend>qtbase5-dev</build_depend>

  <run_depend>rviz</run_depend>
  <run_depend>std_msgs</run_depend>
  <run_depend>libqt5-core</run_depend>
  <run_depend>libqt5-widgets</run_depend>

  <export>
      <rviz plugin="${prefix}/plugin_description.xml"/>
  </export>

</package>

plugin_description.xml代码如下:

<library path="lib/libpoint_grabber">
  <class name="point_grabber/PointGrabber"
         type="PointGrabber"
         base_class_type="rviz::Tool">
    <description>
      liuzubing test point_grabber_tool.
    </description>
  </class>
</library>

flag.dae代码如下:

<?xml version="1.0" encoding="utf-8"?>
<COLLADA version="1.4.0" xmlns="http://www.collada.org/2005/11/COLLADASchema">
	<asset>
		<contributor>
			<author>Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com</author>
			<authoring_tool>Blender v:249 - Illusoft Collada Exporter v:0.3.162</authoring_tool>
			<comments></comments>
			<copyright></copyright>
			<source_data>file:///u/hersh/flag.blend</source_data>
		</contributor>
		<created>2011-03-16T15:32:31.374173</created>
		<modified>2011-03-16T15:32:31.374204</modified>
		<up_axis>Z_UP</up_axis>
	</asset>
	<library_effects>
		<effect id="blue_alpha-fx" name="blue_alpha-fx">
			<profile_COMMON>
				<technique sid="blender">
					<phong>
						<emission>
							<color>0.00000 0.00000 0.00000 1</color>
						</emission>
						<ambient>
							<color>0.04706 0.37059 0.44706 1</color>
						</ambient>
						<diffuse>
							<color>0.09412 0.74118 0.89412 1</color>
						</diffuse>
						<specular>
							<color>0.50000 0.50000 0.50000 1</color>
						</specular>
						<shininess>
							<float>12.5</float>
						</shininess>
						<reflective>
							<color>1.00000 1.00000 1.00000 1</color>
						</reflective>
						<reflectivity>
							<float>0.0</float>
						</reflectivity>
						<transparent>
							<color>1 1 1 1</color>
						</transparent>
						<transparency>
							<float>0.5</float>
						</transparency>
					</phong>
				</technique>
			</profile_COMMON>
		</effect>
		<effect id="red-fx" name="red-fx">
			<profile_COMMON>
				<technique sid="blender">
					<phong>
						<emission>
							<color>0.00000 0.00000 0.00000 1</color>
						</emission>
						<ambient>
							<color>0.50000 0.00000 0.00000 1</color>
						</ambient>
						<diffuse>
							<color>1.00000 0.00000 0.00000 1</color>
						</diffuse>
						<specular>
							<color>0.50000 0.50000 0.50000 1</color>
						</specular>
						<shininess>
							<float>12.5</float>
						</shininess>
						<reflective>
							<color>1.00000 1.00000 1.00000 1</color>
						</reflective>
						<reflectivity>
							<float>0.0</float>
						</reflectivity>
						<transparent>
							<color>1 1 1 1</color>
						</transparent>
						<transparency>
							<float>0.0</float>
						</transparency>
					</phong>
				</technique>
			</profile_COMMON>
		</effect>
		<effect id="white-fx" name="white-fx">
			<profile_COMMON>
				<technique sid="blender">
					<phong>
						<emission>
							<color>0.00000 0.00000 0.00000 1</color>
						</emission>
						<ambient>
							<color>0.50000 0.50000 0.50000 1</color>
						</ambient>
						<diffuse>
							<color>1.00000 1.00000 1.00000 1</color>
						</diffuse>
						<specular>
							<color>0.50000 0.50000 0.50000 1</color>
						</specular>
						<shininess>
							<float>12.5</float>
						</shininess>
						<reflective>
							<color>1.00000 1.00000 1.00000 1</color>
						</reflective>
						<reflectivity>
							<float>0.0</float>
						</reflectivity>
						<transparent>
							<color>1 1 1 1</color>
						</transparent>
						<transparency>
							<float>0.0</float>
						</transparency>
					</phong>
				</technique>
			</profile_COMMON>
		</effect>
	</library_effects>
	<library_lights>
		<light id="Lamp_001" name="Lamp_001">
			<technique_common>
				<directional>
					<color>1.00000 1.00000 1.00000</color>
				</directional>
			</technique_common>
		</light>
	</library_lights>
	<library_materials>
		<material id="blue_alpha" name="blue_alpha">
			<instance_effect url="#blue_alpha-fx"/>
		</material>
		<material id="red" name="red">
			<instance_effect url="#red-fx"/>
		</material>
		<material id="white" name="white">
			<instance_effect url="#white-fx"/>
		</material>
	</library_materials>
	<library_geometries>
		<geometry id="Cylinder_001-Geometry" name="Cylinder_001-Geometry">
			<mesh>
				<source id="Cylinder_001-Geometry-Position">
					<float_array count="198" id="Cylinder_001-Geometry-Position-array">0.70711 0.70711 -0.01000 0.83147 0.55557 -0.01000 0.92388 0.38268 -0.01000 0.98079 0.19509 -0.01000 1.00000 0.00000 -0.01000 0.98079 -0.19509 -0.01000 0.92388 -0.38268 -0.01000 0.83147 -0.55557 -0.01000 0.70711 -0.70711 -0.01000 0.55557 -0.83147 -0.01000 0.38268 -0.92388 -0.01000 0.19509 -0.98079 -0.01000 -0.00000 -1.00000 -0.01000 -0.19509 -0.98079 -0.01000 -0.38268 -0.92388 -0.01000 -0.55557 -0.83147 -0.01000 -0.70711 -0.70711 -0.01000 -0.83147 -0.55557 -0.01000 -0.92388 -0.38268 -0.01000 -0.98079 -0.19509 -0.01000 -1.00000 0.00000 -0.01000 -0.98079 0.19509 -0.01000 -0.92388 0.38268 -0.01000 -0.83147 0.55557 -0.01000 -0.70711 0.70711 -0.01000 -0.55557 0.83147 -0.01000 -0.38268 0.92388 -0.01000 -0.19509 0.98079 -0.01000 0.00000 1.00000 -0.01000 0.19509 0.98078 -0.01000 0.38269 0.92388 -0.01000 0.55557 0.83147 -0.01000 0.70711 0.70711 0.01000 0.83147 0.55557 0.01000 0.92388 0.38268 0.01000 0.98079 0.19509 0.01000 1.00000 -0.00000 0.01000 0.98078 -0.19509 0.01000 0.92388 -0.38268 0.01000 0.83147 -0.55557 0.01000 0.70711 -0.70711 0.01000 0.55557 -0.83147 0.01000 0.38268 -0.92388 0.01000 0.19509 -0.98079 0.01000 0.00000 -1.00000 0.01000 -0.19509 -0.98079 0.01000 -0.38268 -0.92388 0.01000 -0.55557 -0.83147 0.01000 -0.70710 -0.70711 0.01000 -0.83147 -0.55557 0.01000 -0.92388 -0.38269 0.01000 -0.98078 -0.19509 0.01000 -1.00000 -0.00000 0.01000 -0.98079 0.19509 0.01000 -0.92388 0.38268 0.01000 -0.83147 0.55557 0.01000 -0.70711 0.70710 0.01000 -0.55558 0.83147 0.01000 -0.38269 0.92388 0.01000 -0.19510 0.98078 0.01000 -0.00001 1.00000 0.01000 0.19508 0.98079 0.01000 0.38268 0.92388 0.01000 0.55556 0.83147 0.01000 0.00000 0.00000 -0.01000 0.00000 0.00000 0.01000</float_array>
					<technique_common>
						<accessor count="66" source="#Cylinder_001-Geometry-Position-array" stride="3">
							<param type="float" name="X"></param>
							<param type="float" name="Y"></param>
							<param type="float" name="Z"></param>
						</accessor>
					</technique_common>
				</source>
				<source id="Cylinder_001-Geometry-Normals">
					<float_array count="288" id="Cylinder_001-Geometry-Normals-array">-0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.77301 0.63439 0.00000 0.88192 0.47140 -0.00000 0.95694 0.29028 -0.00000 0.99518 0.09802 -0.00000 0.99518 -0.09802 -0.00000 0.95694 -0.29029 -0.00000 0.88192 -0.47140 -0.00000 0.77301 -0.63439 -0.00000 0.63439 -0.77301 -0.00000 0.47140 -0.88192 -0.00000 0.29028 -0.95694 -0.00000 0.09802 -0.99518 -0.00000 -0.09802 -0.99518 -0.00000 -0.29028 -0.95694 -0.00000 -0.47140 -0.88192 -0.00000 -0.63439 -0.77301 0.00000 -0.77301 -0.63439 0.00000 -0.88192 -0.47140 0.00000 -0.95694 -0.29029 -0.00000 -0.99518 -0.09802 -0.00000 -0.99518 0.09802 -0.00000 -0.95694 0.29028 -0.00000 -0.88192 0.47139 -0.00000 -0.77301 0.63439 -0.00000 -0.63440 0.77301 -0.00000 -0.47140 0.88192 -0.00000 -0.29029 0.95694 -0.00000 -0.09802 0.99518 -0.00000 0.09801 0.99519 -0.00000 0.29028 0.95694 -0.00000 0.47139 0.88192 -0.00000 0.63439 0.77301 0.00003</float_array>
					<technique_common>
						<accessor count="96" source="#Cylinder_001-Geometry-Normals-array" stride="3">
							<param type="float" name="X"></param>
							<param type="float" name="Y"></param>
							<param type="float" name="Z"></param>
						</accessor>
					</technique_common>
				</source>
				<source id="Cylinder_001-Geometry-UV">
					<float_array count="768" id="Cylinder_001-Geometry-UV-array">0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000</float_array>
					<technique_common>
						<accessor count="384" source="#Cylinder_001-Geometry-UV-array" stride="2">
							<param type="float" name="S"></param>
							<param type="float" name="T"></param>
						</accessor>
					</technique_common>
				</source>
				<vertices id="Cylinder_001-Geometry-Vertex">
					<input semantic="POSITION" source="#Cylinder_001-Geometry-Position"/>
				</vertices>
				<triangles count="128" material="blue_alpha">
					<input offset="0" semantic="VERTEX" source="#Cylinder_001-Geometry-Vertex"/>
					<input offset="1" semantic="NORMAL" source="#Cylinder_001-Geometry-Normals"/>
					<input offset="2" semantic="TEXCOORD" source="#Cylinder_001-Geometry-UV"/>
					<p>64 0 0 0 0 1 1 0 2 65 1 3 33 1 4 32 1 5 64 2 6 1 2 7 2 2 8 65 3 9 34 3 10 33 3 11 64 4 12 2 4 13 3 4 14 65 5 15 35 5 16 34 5 17 64 6 18 3 6 19 4 6 20 65 7 21 36 7 22 35 7 23 64 8 24 4 8 25 5 8 26 65 9 27 37 9 28 36 9 29 64 10 30 5 10 31 6 10 32 65 11 33 38 11 34 37 11 35 64 12 36 6 12 37 7 12 38 65 13 39 39 13 40 38 13 41 64 14 42 7 14 43 8 14 44 65 15 45 40 15 46 39 15 47 64 16 48 8 16 49 9 16 50 65 17 51 41 17 52 40 17 53 64 18 54 9 18 55 10 18 56 65 19 57 42 19 58 41 19 59 64 20 60 10 20 61 11 20 62 65 21 63 43 21 64 42 21 65 64 22 66 11 22 67 12 22 68 65 23 69 44 23 70 43 23 71 64 24 72 12 24 73 13 24 74 65 25 75 45 25 76 44 25 77 64 26 78 13 26 79 14 26 80 65 27 81 46 27 82 45 27 83 64 28 84 14 28 85 15 28 86 65 29 87 47 29 88 46 29 89 64 30 90 15 30 91 16 30 92 65 31 93 48 31 94 47 31 95 64 32 96 16 32 97 17 32 98 65 33 99 49 33 100 48 33 101 64 34 102 17 34 103 18 34 104 65 35 105 50 35 106 49 35 107 64 36 108 18 36 109 19 36 110 65 37 111 51 37 112 50 37 113 64 38 114 19 38 115 20 38 116 65 39 117 52 39 118 51 39 119 64 40 120 20 40 121 21 40 122 65 41 123 53 41 124 52 41 125 64 42 126 21 42 127 22 42 128 65 43 129 54 43 130 53 43 131 64 44 132 22 44 133 23 44 134 65 45 135 55 45 136 54 45 137 64 46 138 23 46 139 24 46 140 65 47 141 56 47 142 55 47 143 64 48 144 24 48 145 25 48 146 65 49 147 57 49 148 56 49 149 64 50 150 25 50 151 26 50 152 65 51 153 58 51 154 57 51 155 64 52 156 26 52 157 27 52 158 65 53 159 59 53 160 58 53 161 64 54 162 27 54 163 28 54 164 65 55 165 60 55 166 59 55 167 64 56 168 28 56 169 29 56 170 65 57 171 61 57 172 60 57 173 64 58 174 29 58 175 30 58 176 65 59 177 62 59 178 61 59 179 64 60 180 30 60 181 31 60 182 65 61 183 63 61 184 62 61 185 31 62 186 0 62 187 64 62 188 65 63 189 32 63 190 63 63 191 0 64 192 32 64 193 33 64 194 33 64 195 1 64 196 0 64 197 1 65 198 33 65 199 34 65 200 34 65 201 2 65 202 1 65 203 2 66 204 34 66 205 35 66 206 35 66 207 3 66 208 2 66 209 3 67 210 35 67 211 36 67 212 36 67 213 4 67 214 3 67 215 4 68 216 36 68 217 37 68 218 37 68 219 5 68 220 4 68 221 5 69 222 37 69 223 38 69 224 38 69 225 6 69 226 5 69 227 6 70 228 38 70 229 39 70 230 39 70 231 7 70 232 6 70 233 7 71 234 39 71 235 40 71 236 40 71 237 8 71 238 7 71 239 8 72 240 40 72 241 41 72 242 41 72 243 9 72 244 8 72 245 9 73 246 41 73 247 42 73 248 42 73 249 10 73 250 9 73 251 10 74 252 42 74 253 43 74 254 43 74 255 11 74 256 10 74 257 11 75 258 43 75 259 44 75 260 44 75 261 12 75 262 11 75 263 12 76 264 44 76 265 45 76 266 45 76 267 13 76 268 12 76 269 13 77 270 45 77 271 46 77 272 46 77 273 14 77 274 13 77 275 14 78 276 46 78 277 47 78 278 47 78 279 15 78 280 14 78 281 15 79 282 47 79 283 48 79 284 48 79 285 16 79 286 15 79 287 16 80 288 48 80 289 49 80 290 49 80 291 17 80 292 16 80 293 17 81 294 49 81 295 50 81 296 50 81 297 18 81 298 17 81 299 18 82 300 50 82 301 51 82 302 51 82 303 19 82 304 18 82 305 19 83 306 51 83 307 52 83 308 52 83 309 20 83 310 19 83 311 20 84 312 52 84 313 53 84 314 53 84 315 21 84 316 20 84 317 21 85 318 53 85 319 54 85 320 54 85 321 22 85 322 21 85 323 22 86 324 54 86 325 55 86 326 55 86 327 23 86 328 22 86 329 23 87 330 55 87 331 56 87 332 56 87 333 24 87 334 23 87 335 24 88 336 56 88 337 57 88 338 57 88 339 25 88 340 24 88 341 25 89 342 57 89 343 58 89 344 58 89 345 26 89 346 25 89 347 26 90 348 58 90 349 59 90 350 59 90 351 27 90 352 26 90 353 27 91 354 59 91 355 60 91 356 60 91 357 28 91 358 27 91 359 28 92 360 60 92 361 61 92 362 61 92 363 29 92 364 28 92 365 29 93 366 61 93 367 62 93 368 62 93 369 30 93 370 29 93 371 30 94 372 62 94 373 63 94 374 63 94 375 31 94 376 30 94 377 32 95 378 0 95 379 31 95 380 31 95 381 63 95 382 32 95 383</p>
				</triangles>
			</mesh>
		</geometry>
		<geometry id="flag_001" name="flag_001">
			<mesh>
				<source id="flag_001-Position">
					<float_array count="18" id="flag_001-Position-array">1.00000 0.00000 0.00621 -1.00000 -0.00000 -0.99379 -1.00000 0.00000 1.00621 -1.00000 0.05590 1.00621 -1.00000 0.05590 -0.99379 1.00000 0.05590 0.00621</float_array>
					<technique_common>
						<accessor count="6" source="#flag_001-Position-array" stride="3">
							<param type="float" name="X"></param>
							<param type="float" name="Y"></param>
							<param type="float" name="Z"></param>
						</accessor>
					</technique_common>
				</source>
				<source id="flag_001-Normals">
					<float_array count="15" id="flag_001-Normals-array">0.00000 -1.00000 0.00000 0.44721 0.00000 -0.89443 -1.00000 0.00000 0.00000 0.44721 0.00000 0.89443 -0.00000 1.00000 -0.00000</float_array>
					<technique_common>
						<accessor count="5" source="#flag_001-Normals-array" stride="3">
							<param type="float" name="X"></param>
							<param type="float" name="Y"></param>
							<param type="float" name="Z"></param>
						</accessor>
					</technique_common>
				</source>
				<vertices id="flag_001-Vertex">
					<input semantic="POSITION" source="#flag_001-Position"/>
				</vertices>
				<triangles count="8" material="red">
					<input offset="0" semantic="VERTEX" source="#flag_001-Vertex"/>
					<input offset="1" semantic="NORMAL" source="#flag_001-Normals"/>
					<p>1 0 0 0 2 0 0 1 1 1 4 1 4 1 5 1 0 1 1 2 2 2 3 2 3 2 4 2 1 2 2 3 0 3 5 3 5 3 3 3 2 3 3 4 5 4 4 4</p>
				</triangles>
			</mesh>
		</geometry>
		<geometry id="Cylinder-Geometry" name="Cylinder-Geometry">
			<mesh>
				<source id="Cylinder-Geometry-Position">
					<float_array count="198" id="Cylinder-Geometry-Position-array">0.03536 0.03536 -1.00000 0.04157 0.02778 -1.00000 0.04619 0.01913 -1.00000 0.04904 0.00975 -1.00000 0.05000 0.00000 -1.00000 0.04904 -0.00975 -1.00000 0.04619 -0.01913 -1.00000 0.04157 -0.02778 -1.00000 0.03536 -0.03536 -1.00000 0.02778 -0.04157 -1.00000 0.01913 -0.04619 -1.00000 0.00975 -0.04904 -1.00000 -0.00000 -0.05000 -1.00000 -0.00975 -0.04904 -1.00000 -0.01913 -0.04619 -1.00000 -0.02778 -0.04157 -1.00000 -0.03536 -0.03536 -1.00000 -0.04157 -0.02778 -1.00000 -0.04619 -0.01913 -1.00000 -0.04904 -0.00975 -1.00000 -0.05000 0.00000 -1.00000 -0.04904 0.00975 -1.00000 -0.04619 0.01913 -1.00000 -0.04157 0.02778 -1.00000 -0.03536 0.03536 -1.00000 -0.02778 0.04157 -1.00000 -0.01913 0.04619 -1.00000 -0.00975 0.04904 -1.00000 0.00000 0.05000 -1.00000 0.00975 0.04904 -1.00000 0.01913 0.04619 -1.00000 0.02778 0.04157 -1.00000 0.03536 0.03536 1.00000 0.04157 0.02778 1.00000 0.04619 0.01913 1.00000 0.04904 0.00975 1.00000 0.05000 -0.00000 1.00000 0.04904 -0.00975 1.00000 0.04619 -0.01913 1.00000 0.04157 -0.02778 1.00000 0.03536 -0.03536 1.00000 0.02778 -0.04157 1.00000 0.01913 -0.04619 1.00000 0.00975 -0.04904 1.00000 0.00000 -0.05000 1.00000 -0.00975 -0.04904 1.00000 -0.01913 -0.04619 1.00000 -0.02778 -0.04157 1.00000 -0.03536 -0.03536 1.00000 -0.04157 -0.02778 1.00000 -0.04619 -0.01913 1.00000 -0.04904 -0.00975 1.00000 -0.05000 -0.00000 1.00000 -0.04904 0.00975 1.00000 -0.04619 0.01913 1.00000 -0.04157 0.02778 1.00000 -0.03536 0.03536 1.00000 -0.02778 0.04157 1.00000 -0.01913 0.04619 1.00000 -0.00975 0.04904 1.00000 -0.00000 0.05000 1.00000 0.00975 0.04904 1.00000 0.01913 0.04619 1.00000 0.02778 0.04157 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000</float_array>
					<technique_common>
						<accessor count="66" source="#Cylinder-Geometry-Position-array" stride="3">
							<param type="float" name="X"></param>
							<param type="float" name="Y"></param>
							<param type="float" name="Z"></param>
						</accessor>
					</technique_common>
				</source>
				<source id="Cylinder-Geometry-Normals">
					<float_array count="288" id="Cylinder-Geometry-Normals-array">-0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.77301 0.63439 0.00000 0.88192 0.47140 0.00000 0.95694 0.29028 -0.00000 0.99518 0.09802 -0.00000 0.99518 -0.09802 -0.00000 0.95694 -0.29029 -0.00000 0.88192 -0.47140 -0.00000 0.77301 -0.63439 -0.00000 0.63439 -0.77301 0.00000 0.47140 -0.88192 -0.00000 0.29028 -0.95694 -0.00000 0.09802 -0.99518 -0.00000 -0.09802 -0.99518 -0.00000 -0.29028 -0.95694 -0.00000 -0.47140 -0.88192 -0.00000 -0.63439 -0.77301 -0.00000 -0.77301 -0.63439 -0.00000 -0.88192 -0.47140 0.00000 -0.95694 -0.29029 0.00000 -0.99518 -0.09802 -0.00000 -0.99518 0.09802 -0.00000 -0.95694 0.29028 -0.00000 -0.88192 0.47140 -0.00000 -0.77301 0.63439 -0.00000 -0.63440 0.77301 -0.00000 -0.47140 0.88192 0.00000 -0.29029 0.95694 -0.00000 -0.09802 0.99518 -0.00000 0.09801 0.99519 -0.00000 0.29028 0.95694 -0.00000 0.47139 0.88192 -0.00000 0.63439 0.77301 0.00000</float_array>
					<technique_common>
						<accessor count="96" source="#Cylinder-Geometry-Normals-array" stride="3">
							<param type="float" name="X"></param>
							<param type="float" name="Y"></param>
							<param type="float" name="Z"></param>
						</accessor>
					</technique_common>
				</source>
				<source id="Cylinder-Geometry-UV">
					<float_array count="768" id="Cylinder-Geometry-UV-array">0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000</float_array>
					<technique_common>
						<accessor count="384" source="#Cylinder-Geometry-UV-array" stride="2">
							<param type="float" name="S"></param>
							<param type="float" name="T"></param>
						</accessor>
					</technique_common>
				</source>
				<vertices id="Cylinder-Geometry-Vertex">
					<input semantic="POSITION" source="#Cylinder-Geometry-Position"/>
				</vertices>
				<triangles count="128" material="white">
					<input offset="0" semantic="VERTEX" source="#Cylinder-Geometry-Vertex"/>
					<input offset="1" semantic="NORMAL" source="#Cylinder-Geometry-Normals"/>
					<input offset="2" semantic="TEXCOORD" source="#Cylinder-Geometry-UV"/>
					<p>64 0 0 0 0 1 1 0 2 65 1 3 33 1 4 32 1 5 64 2 6 1 2 7 2 2 8 65 3 9 34 3 10 33 3 11 64 4 12 2 4 13 3 4 14 65 5 15 35 5 16 34 5 17 64 6 18 3 6 19 4 6 20 65 7 21 36 7 22 35 7 23 64 8 24 4 8 25 5 8 26 65 9 27 37 9 28 36 9 29 64 10 30 5 10 31 6 10 32 65 11 33 38 11 34 37 11 35 64 12 36 6 12 37 7 12 38 65 13 39 39 13 40 38 13 41 64 14 42 7 14 43 8 14 44 65 15 45 40 15 46 39 15 47 64 16 48 8 16 49 9 16 50 65 17 51 41 17 52 40 17 53 64 18 54 9 18 55 10 18 56 65 19 57 42 19 58 41 19 59 64 20 60 10 20 61 11 20 62 65 21 63 43 21 64 42 21 65 64 22 66 11 22 67 12 22 68 65 23 69 44 23 70 43 23 71 64 24 72 12 24 73 13 24 74 65 25 75 45 25 76 44 25 77 64 26 78 13 26 79 14 26 80 65 27 81 46 27 82 45 27 83 64 28 84 14 28 85 15 28 86 65 29 87 47 29 88 46 29 89 64 30 90 15 30 91 16 30 92 65 31 93 48 31 94 47 31 95 64 32 96 16 32 97 17 32 98 65 33 99 49 33 100 48 33 101 64 34 102 17 34 103 18 34 104 65 35 105 50 35 106 49 35 107 64 36 108 18 36 109 19 36 110 65 37 111 51 37 112 50 37 113 64 38 114 19 38 115 20 38 116 65 39 117 52 39 118 51 39 119 64 40 120 20 40 121 21 40 122 65 41 123 53 41 124 52 41 125 64 42 126 21 42 127 22 42 128 65 43 129 54 43 130 53 43 131 64 44 132 22 44 133 23 44 134 65 45 135 55 45 136 54 45 137 64 46 138 23 46 139 24 46 140 65 47 141 56 47 142 55 47 143 64 48 144 24 48 145 25 48 146 65 49 147 57 49 148 56 49 149 64 50 150 25 50 151 26 50 152 65 51 153 58 51 154 57 51 155 64 52 156 26 52 157 27 52 158 65 53 159 59 53 160 58 53 161 64 54 162 27 54 163 28 54 164 65 55 165 60 55 166 59 55 167 64 56 168 28 56 169 29 56 170 65 57 171 61 57 172 60 57 173 64 58 174 29 58 175 30 58 176 65 59 177 62 59 178 61 59 179 64 60 180 30 60 181 31 60 182 65 61 183 63 61 184 62 61 185 31 62 186 0 62 187 64 62 188 65 63 189 32 63 190 63 63 191 0 64 192 32 64 193 33 64 194 33 64 195 1 64 196 0 64 197 1 65 198 33 65 199 34 65 200 34 65 201 2 65 202 1 65 203 2 66 204 34 66 205 35 66 206 35 66 207 3 66 208 2 66 209 3 67 210 35 67 211 36 67 212 36 67 213 4 67 214 3 67 215 4 68 216 36 68 217 37 68 218 37 68 219 5 68 220 4 68 221 5 69 222 37 69 223 38 69 224 38 69 225 6 69 226 5 69 227 6 70 228 38 70 229 39 70 230 39 70 231 7 70 232 6 70 233 7 71 234 39 71 235 40 71 236 40 71 237 8 71 238 7 71 239 8 72 240 40 72 241 41 72 242 41 72 243 9 72 244 8 72 245 9 73 246 41 73 247 42 73 248 42 73 249 10 73 250 9 73 251 10 74 252 42 74 253 43 74 254 43 74 255 11 74 256 10 74 257 11 75 258 43 75 259 44 75 260 44 75 261 12 75 262 11 75 263 12 76 264 44 76 265 45 76 266 45 76 267 13 76 268 12 76 269 13 77 270 45 77 271 46 77 272 46 77 273 14 77 274 13 77 275 14 78 276 46 78 277 47 78 278 47 78 279 15 78 280 14 78 281 15 79 282 47 79 283 48 79 284 48 79 285 16 79 286 15 79 287 16 80 288 48 80 289 49 80 290 49 80 291 17 80 292 16 80 293 17 81 294 49 81 295 50 81 296 50 81 297 18 81 298 17 81 299 18 82 300 50 82 301 51 82 302 51 82 303 19 82 304 18 82 305 19 83 306 51 83 307 52 83 308 52 83 309 20 83 310 19 83 311 20 84 312 52 84 313 53 84 314 53 84 315 21 84 316 20 84 317 21 85 318 53 85 319 54 85 320 54 85 321 22 85 322 21 85 323 22 86 324 54 86 325 55 86 326 55 86 327 23 86 328 22 86 329 23 87 330 55 87 331 56 87 332 56 87 333 24 87 334 23 87 335 24 88 336 56 88 337 57 88 338 57 88 339 25 88 340 24 88 341 25 89 342 57 89 343 58 89 344 58 89 345 26 89 346 25 89 347 26 90 348 58 90 349 59 90 350 59 90 351 27 90 352 26 90 353 27 91 354 59 91 355 60 91 356 60 91 357 28 91 358 27 91 359 28 92 360 60 92 361 61 92 362 61 92 363 29 92 364 28 92 365 29 93 366 61 93 367 62 93 368 62 93 369 30 93 370 29 93 371 30 94 372 62 94 373 63 94 374 63 94 375 31 94 376 30 94 377 32 95 378 0 95 379 31 95 380 31 95 381 63 95 382 32 95 383</p>
				</triangles>
			</mesh>
		</geometry>
	</library_geometries>
	<library_visual_scenes>
		<visual_scene id="Scene" name="Scene">
			<node layer="L1" id="Lamp" name="Lamp">
				<translate sid="translate">-0.29478 -1.99835 2.70248</translate>
				<rotate sid="rotateZ">0 0 1 0.00000</rotate>
				<rotate sid="rotateY">0 1 0 -0.00000</rotate>
				<rotate sid="rotateX">1 0 0 0.00000</rotate>
				<scale sid="scale">1.00000 1.00000 1.00000</scale>
				<instance_light url="#Lamp_001"/>
			</node>
			<node layer="L1" id="Cylinder_001" name="Cylinder_001">
				<translate sid="translate">0.00334 -0.00071 0.00118</translate>
				<rotate sid="rotateZ">0 0 1 0.00000</rotate>
				<rotate sid="rotateY">0 1 0 -0.00000</rotate>
				<rotate sid="rotateX">1 0 0 0.00000</rotate>
				<scale sid="scale">1.00000 1.00000 1.00000</scale>
				<instance_geometry url="#Cylinder_001-Geometry">
					<bind_material>
						<technique_common>
							<instance_material symbol="blue_alpha" target="#blue_alpha">
								<bind_vertex_input input_semantic="TEXCOORD" input_set="1" semantic="CHANNEL1"/>
							</instance_material>
						</technique_common>
					</bind_material>
				</instance_geometry>
			</node>
			<node layer="L1" id="flag" name="flag">
				<translate sid="translate">0.22856 0.00372 1.80362</translate>
				<rotate sid="rotateZ">0 0 1 0.00000</rotate>
				<rotate sid="rotateY">0 1 0 -0.00000</rotate>
				<rotate sid="rotateX">1 0 0 0.00000</rotate>
				<scale sid="scale">0.18803 0.18803 0.18803</scale>
				<instance_geometry url="#flag_001">
					<bind_material>
						<technique_common>
							<instance_material symbol="red" target="#red">
								<bind_vertex_input input_semantic="TEXCOORD" input_set="1" semantic="CHANNEL1"/>
							</instance_material>
						</technique_common>
					</bind_material>
				</instance_geometry>
			</node>
			<node layer="L1" id="Cylinder" name="Cylinder">
				<translate sid="translate">0.00580 0.01041 0.99794</translate>
				<rotate sid="rotateZ">0 0 1 0.00000</rotate>
				<rotate sid="rotateY">0 1 0 -0.00000</rotate>
				<rotate sid="rotateX">1 0 0 0.00000</rotate>
				<scale sid="scale">1.00000 1.00000 1.00000</scale>
				<instance_geometry url="#Cylinder-Geometry">
					<bind_material>
						<technique_common>
							<instance_material symbol="white" target="#white">
								<bind_vertex_input input_semantic="TEXCOORD" input_set="1" semantic="CHANNEL1"/>
							</instance_material>
						</technique_common>
					</bind_material>
				</instance_geometry>
			</node>
		</visual_scene>
	</library_visual_scenes>
	<scene>
		<instance_visual_scene url="#Scene"/>
	</scene>
</COLLADA>

 

  • 2
    点赞
  • 7
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值