Add files

This commit is contained in:
HarleA 2020-09-16 10:05:14 +02:00
parent bcfaacd194
commit a8c94b93eb
851 changed files with 74204 additions and 0 deletions

View file

@ -0,0 +1,21 @@
# THIS IS AN AUTOGENERATED FILE, LAST GENERATED USING wstool ON 2017-07-21
- git:
local-name: hector_gazebo
uri: https://github.com/tu-darmstadt-ros-pkg/hector_gazebo.git
version: hydro-devel
- git:
local-name: hector_localization
uri: https://github.com/tu-darmstadt-ros-pkg/hector_localization.git
version: catkin
- git:
local-name: hector_models
uri: https://github.com/tu-darmstadt-ros-pkg/hector_models.git
version: hydro-devel
- git:
local-name: hector_quadrotor
uri: https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor.git
version: hydro-devel
- git:
local-name: hector_slam
uri: https://github.com/tu-darmstadt-ros-pkg/hector_slam.git
version: catkin

View file

@ -0,0 +1,4 @@
hector_gazebo
=============
hector_gazebo provides packages related to the simulation of robots using gazebo (gazebo plugins, world files etc.).

View file

@ -0,0 +1,30 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package hector_gazebo
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
0.3.6 (2015-03-21)
------------------
0.3.5 (2015-02-23)
------------------
0.3.4 (2014-09-01)
------------------
* Removed package gazebo_rtt_plugin
This package is obsolete. Use the rtt_gazebo stack instead.
* Contributors: Johannes Meyer
0.3.3 (2014-05-27)
------------------
0.3.2 (2014-03-30)
------------------
* Made hector_gazebo and hector_sensors_gazebo true metapackages
* Contributors: Johannes Meyer
0.3.1 (2013-09-23)
------------------
0.3.0 (2013-09-02)
------------------
* Catkinization of stack hector_gazebo

View file

@ -0,0 +1,4 @@
cmake_minimum_required(VERSION 2.8.3)
project(hector_gazebo)
find_package(catkin REQUIRED)
catkin_metapackage()

View file

@ -0,0 +1,27 @@
<package>
<name>hector_gazebo</name>
<version>0.3.6</version>
<description>hector_gazebo provides packages related to to simulation of robots using gazebo (gazebo plugins, world files etc.)</description>
<maintainer email="meyer@fsr.tu-darmstadt.de">Johannes Meyer</maintainer>
<license>BSD</license>
<url type="website">http://ros.org/wiki/hector_gazebo</url>
<!-- <url type="bugtracker"></url> -->
<author email="kohlbrecher@sim.tu-darmstadt.de">Stefan Kohlbrecher</author>
<author email="meyer@fsr.tu-darmstadt.de">Johannes Meyer</author>
<!-- Dependencies which this package needs to build itself. -->
<buildtool_depend>catkin</buildtool_depend>
<!-- Dependencies needed after this package is compiled. -->
<run_depend>hector_gazebo_thermal_camera</run_depend>
<run_depend>hector_gazebo_worlds</run_depend>
<run_depend>hector_gazebo_plugins</run_depend>
<export>
<metapackage/>
</export>
</package>

View file

@ -0,0 +1,76 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package hector_gazebo_plugins
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
0.3.6 (2015-03-21)
------------------
* allow negative offsets in SensorModel dynamic_reconfigure config
* fixed sporadic NaN values in gazebo_ros_imu's angular_velocity output (fix #20)
* reintroduced orientation bias due to accelerometer and yaw sensor drift
This orientation bias was removed in 74b21b7, but there is no need for this.
The IMU can have a mounting offset and a bias error. To remove the bias error, set the accelerationDrift and yawDrift parameters to 0.
* interpret parameters xyzOffset and rpyOffset as pure mounting offsets and not as induced by accelerometer bias (fix #18)
Obviously the SDF conversion assumes that all sensor plugins interpret the `<xyzOffset>` and `<rpyOffset>` parameters in the same way as an
additional sensor link which is connected with a static joint to the real parent frame. I was not aware that this is a requirement.
hector_gazebo_ros_imu interpreted the roll and pitch part of `<rpyOffset>` as an orientation offset caused by a (small) accelerometer bias.
This patch completely removes the bias error on the orientation output in the Imu message and the orientation quaternion in the bias message
is set to zero.
* Contributors: Johannes Meyer
0.3.5 (2015-02-23)
------------------
* fixed simulated IMU calibration
* fill position_covariance in sensor_msgs/NavSatFix message from position error model in gazebo_ros_gps (fix #17)
* added dynamic_reconfigure servers to gps, magneto and sonar plugins
The GPS plugin allows to configure the status and server flags in the output message,
additionally to the error characteristics. This allows to simulate GPS dropouts.
* added dynamic_reconfigure server for IMU sensor model parameters
* fixed invocation of sensor model in gazebo_ros_imu and gazebo_ros_sonar to also respect the scale error
* calculate angular rate from quaternion difference directly
This seems to be numerically more stable and removes the jitter in the angular rate signal.
* added initial bias
* added bias publisher to gazebo_ros_imu
...to compare hector_pose_estimation estimates with ground truth.
Also renamed heading to yaw in gazebo_ros_imu and updated pseudo AHRS orientation calculation.
* added scale error to the sensor model and removed linearization in drift update
The scale error is assumed to be constant and its value is loaded from the `scaleError` plugin parameter.
The default scale error is 1.0 (no scale error).
The value returned by the model is `(real_value * scale_error) + offset + drift + noise`.
* fixed wrong calculation of reference earth magnetic field vector if declination!=0
* Contributors: Johannes Meyer
0.3.4 (2014-09-01)
------------------
* replaced old copied license header in servo_plugin.cpp
* simplified attitude error calculation in gazebo_ros_imu (fixes #12)
* fixed calculation of vector-valued sensor errors and sensor error model resetting with non-zero initial drift
* linking against catkin_libraries
* Contributors: Johannes Meyer, Markus Achtelik
0.3.3 (2014-05-27)
------------------
0.3.2 (2014-03-30)
------------------
* diffdrive_plugin_multi_wheel: Fix wrong whell rotation calculation (Was only half speed of desired)
* diffdrive_plugin_multi_wheel: Optionally do not publish odometry via tf or as msg
* Fixed boost 1.53 issues
Replaced boost::shared_dynamic_cast with boost::dynamic_pointer_cast
* Add servo plugin (used for vision box currently)
* Add catkin_LIBRARIES to linking for multiwheel plugin
* Some fixes to make diffdrive_plugin_multi_wheel work properly
* Work in progress of a diffdrive plugin supporting multiple wheels per side
* used updated API to get rid of warnings
* added topicName parameter back to gazebo_ros_magnetic
* hector_gazebo: deleted deprecated export sections from package.xml files
* abort with a fatal error if ROS is not yet initialized + minor code cleanup
* Contributors: Christopher Hrabia, Johannes Meyer, Richard Williams, Stefan Kohlbrecher, richardw347
0.3.1 (2013-09-23)
------------------
* fixed a bug in UpdateTimer class when updateRate and updatePeriod parameters are unset
* removed warnings due to deprecated sdf API calls
0.3.0 (2013-09-02)
------------------
* Catkinization of stack hector_gazebo

View file

@ -0,0 +1,122 @@
cmake_minimum_required(VERSION 2.8.3)
project(hector_gazebo_plugins)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp std_msgs std_srvs geometry_msgs nav_msgs tf dynamic_reconfigure)
include_directories(include ${catkin_INCLUDE_DIRS})
## Find gazebo
find_package(gazebo REQUIRED)
include_directories(${GAZEBO_INCLUDE_DIRS})
link_directories(${GAZEBO_LIBRARY_DIRS})
## Find Boost
find_package(Boost REQUIRED COMPONENTS thread)
include_directories(${Boost_INCLUDE_DIRS})
#######################################
## Declare ROS messages and services ##
#######################################
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# )
## Generate services in the 'srv' folder
add_service_files(
FILES
SetBias.srv
)
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES geometry_msgs
)
#add dynamic reconfigure api
generate_dynamic_reconfigure_options(
cfg/SensorModel.cfg
cfg/GNSS.cfg
)
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
DEPENDS gazebo
CATKIN_DEPENDS roscpp std_msgs geometry_msgs nav_msgs tf
INCLUDE_DIRS include
LIBRARIES
)
###########
## Build ##
###########
add_library(diffdrive_plugin_6w src/diffdrive_plugin_6w.cpp)
target_link_libraries(diffdrive_plugin_6w ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_library(diffdrive_plugin_multi_wheel src/diffdrive_plugin_multi_wheel.cpp)
target_link_libraries(diffdrive_plugin_multi_wheel ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_library(gazebo_ros_force_based_move src/gazebo_ros_force_based_move.cpp)
target_link_libraries(gazebo_ros_force_based_move ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_library(hector_gazebo_reset_plugin src/reset_plugin.cpp)
target_link_libraries(hector_gazebo_reset_plugin ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_library(hector_gazebo_ros_imu src/gazebo_ros_imu.cpp)
target_link_libraries(hector_gazebo_ros_imu ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(hector_gazebo_ros_imu ${PROJECT_NAME}_generate_messages_cpp ${PROJECT_NAME}_gencfg)
add_library(hector_gazebo_ros_magnetic src/gazebo_ros_magnetic.cpp)
target_link_libraries(hector_gazebo_ros_magnetic ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(hector_gazebo_ros_magnetic ${PROJECT_NAME}_gencfg)
add_library(hector_gazebo_ros_gps src/gazebo_ros_gps.cpp)
target_link_libraries(hector_gazebo_ros_gps ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(hector_gazebo_ros_gps ${PROJECT_NAME}_gencfg)
add_library(hector_gazebo_ros_sonar src/gazebo_ros_sonar.cpp)
target_link_libraries(hector_gazebo_ros_sonar ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(hector_gazebo_ros_sonar ${PROJECT_NAME}_gencfg)
add_library(hector_servo_plugin src/servo_plugin.cpp)
target_link_libraries(hector_servo_plugin ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h"
PATTERN ".svn" EXCLUDE
)
install(TARGETS
diffdrive_plugin_6w
diffdrive_plugin_multi_wheel
gazebo_ros_force_based_move
hector_gazebo_reset_plugin
hector_gazebo_ros_imu
hector_gazebo_ros_magnetic
hector_gazebo_ros_gps
hector_gazebo_ros_sonar
hector_servo_plugin
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

View file

@ -0,0 +1,17 @@
#!/usr/bin/env python
PACKAGE = "hector_gazebo_plugins"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("STATUS_FIX", bool_t, 1, "unaugmented fix", True)
gen.add("STATUS_SBAS_FIX", bool_t, 1, "fix with satellite-based augmentation", False)
gen.add("STATUS_GBAS_FIX", bool_t, 1, "with ground-based augmentation", False)
gen.add("SERVICE_GPS", bool_t, 1, "GPS service", True)
gen.add("SERVICE_GLONASS", bool_t, 1, "GLONASS service", True)
gen.add("SERVICE_COMPASS", bool_t, 1, "COMPASS service", True)
gen.add("SERVICE_GALILEO", bool_t, 1, "GALILEO service", True)
exit(gen.generate(PACKAGE, "hector_gazebo_plugins", "GNSS"))

View file

@ -0,0 +1,14 @@
#!/usr/bin/env python
PACKAGE = "hector_gazebo_plugins"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("gaussian_noise", double_t, 1, "Standard deviation of the additive white Gaussian noise", 0.0, 0.0, 10.0)
gen.add("offset", double_t, 1, "Zero-offset of the published sensor signal", 0.0, -10.0, 10.0)
gen.add("drift", double_t, 1, "Standard deviation of the sensor drift", 0.0, 0.0, 10.0)
gen.add("drift_frequency", double_t, 1, "Reciprocal of the time constant of the first-order drift model in Hz", 0.0, 0.0, 1.0)
gen.add("scale_error", double_t, 1, "Scale error", 1.0, 0.0, 2.0)
exit(gen.generate(PACKAGE, "hector_gazebo_plugins", "SensorModel"))

View file

@ -0,0 +1,116 @@
/*
* Gazebo - Outdoor Multi-Robot Simulator
* Copyright (C) 2003
* Nate Koenig & Andrew Howard
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/
/*
* Desc: ROS interface to a Position2d controller for a Differential drive.
* Author: Daniel Hewlett (adapted from Nathan Koenig)
*/
#ifndef DIFFDRIVE_PLUGIN_HH
#define DIFFDRIVE_PLUGIN_HH
#include <map>
#include <gazebo/common/Plugin.hh>
#include <gazebo/common/Time.hh>
// ROS
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/Twist.h>
#include <nav_msgs/Odometry.h>
// Custom Callback Queue
#include <ros/callback_queue.h>
#include <ros/advertise_options.h>
// Boost
#include <boost/thread.hpp>
#include <boost/bind.hpp>
namespace gazebo
{
class DiffDrivePlugin6W : public ModelPlugin
{
public:
DiffDrivePlugin6W();
virtual ~DiffDrivePlugin6W();
protected:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
virtual void Reset();
virtual void Update();
private:
void publish_odometry();
void GetPositionCmd();
physics::LinkPtr link;
physics::WorldPtr world;
physics::JointPtr joints[6];
float wheelSep;
float wheelDiam;
float torque;
float wheelSpeed[2];
// Simulation time of the last update
common::Time prevUpdateTime;
bool enableMotors;
float odomPose[3];
float odomVel[3];
// ROS STUFF
ros::NodeHandle* rosnode_;
ros::Publisher pub_;
ros::Subscriber sub_;
tf::TransformBroadcaster *transform_broadcaster_;
nav_msgs::Odometry odom_;
std::string tf_prefix_;
boost::mutex lock;
std::string namespace_;
std::string topic_;
std::string link_name_;
// Custom Callback Queue
ros::CallbackQueue queue_;
boost::thread callback_queue_thread_;
void QueueThread();
// DiffDrive stuff
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
float x_;
float rot_;
bool alive_;
// Pointer to the update event connection
event::ConnectionPtr updateConnection;
};
}
#endif

View file

@ -0,0 +1,172 @@
/*
* Copyright (c) 2010, Daniel Hewlett, Antons Rebguns
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the <organization> nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
**/
/*
* \file gazebo_ros_diff_drive.h
*
* \brief A differential drive plugin for gazebo. Based on the diffdrive plugin
* developed for the erratic robot (see copyright notice above). The original
* plugin can be found in the ROS package gazebo_erratic_plugins.
*
* \author Piyush Khandelwal (piyushk@gmail.com)
*
* $ Id: 06/21/2013 11:23:40 AM piyushk $
*/
/**
* A diff drive plugin supporting multiple wheels per vehicle side. Based on
* existing plugins as stated above this notice.
*/
/*
Copyright (c) 2014, Stefan Kohlbrecher
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of the <organization> nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef DIFFDRIVE_PLUGIN_HH
#define DIFFDRIVE_PLUGIN_HH
#include <map>
// Gazebo
#include <gazebo/common/common.hh>
#include <gazebo/physics/physics.hh>
// ROS
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/Twist.h>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/OccupancyGrid.h>
// Custom Callback Queue
#include <ros/callback_queue.h>
#include <ros/advertise_options.h>
// Boost
#include <boost/thread.hpp>
#include <boost/bind.hpp>
namespace gazebo {
class Joint;
class Entity;
class GazeboRosDiffDriveMultiWheel : public ModelPlugin {
public:
GazeboRosDiffDriveMultiWheel();
~GazeboRosDiffDriveMultiWheel();
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
protected:
virtual void UpdateChild();
virtual void FiniChild();
private:
void publishOdometry(double step_time);
void getWheelVelocities();
physics::WorldPtr world;
physics::ModelPtr parent;
event::ConnectionPtr update_connection_;
std::vector<std::string> joint_names_[2];
double wheel_separation_;
double wheel_diameter_;
double torque;
double wheel_speed_[2];
std::vector<physics::JointPtr> joints_[2];
// ROS STUFF
ros::NodeHandle* rosnode_;
ros::Publisher odometry_publisher_;
ros::Subscriber cmd_vel_subscriber_;
tf::TransformBroadcaster *transform_broadcaster_;
nav_msgs::Odometry odom_;
std::string tf_prefix_;
boost::mutex lock;
std::string robot_namespace_;
std::string command_topic_;
std::string odometry_topic_;
std::string odometry_frame_;
std::string robot_base_frame_;
// Custom Callback Queue
ros::CallbackQueue queue_;
boost::thread callback_queue_thread_;
void QueueThread();
// DiffDrive stuff
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
double x_;
double rot_;
bool alive_;
// Update Rate
double update_rate_;
double update_period_;
common::Time last_update_time_;
bool publish_odometry_tf_;
bool publish_odometry_msg_;
};
}
#endif

View file

@ -0,0 +1,106 @@
/*
* Copyright 2015 Stefan Kohlbrecher, TU Darmstadt
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
/*
* Desc: Simple model controller that uses a twist message to exert
* forces on a robot, resulting in motion. Based on the
* planar_move plugin by Piyush Khandelwal.
* Author: Stefan Kohlbrecher
* Date: 06 August 2015
*/
#ifndef GAZEBO_ROS_FORCE_BASED_MOVE_HH
#define GAZEBO_ROS_FORCE_BASED_MOVE_HH
#include <boost/bind.hpp>
#include <boost/thread.hpp>
#include <map>
#include <gazebo/common/common.hh>
#include <gazebo/physics/physics.hh>
#include <sdf/sdf.hh>
#include <geometry_msgs/Twist.h>
#include <nav_msgs/OccupancyGrid.h>
#include <nav_msgs/Odometry.h>
#include <ros/advertise_options.h>
#include <ros/callback_queue.h>
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
namespace gazebo {
class GazeboRosForceBasedMove : public ModelPlugin {
public:
GazeboRosForceBasedMove();
~GazeboRosForceBasedMove();
void Load(physics::ModelPtr parent, sdf::ElementPtr sdf);
protected:
virtual void UpdateChild();
virtual void FiniChild();
private:
void publishOdometry(double step_time);
physics::ModelPtr parent_;
event::ConnectionPtr update_connection_;
/// \brief A pointer to the Link, where force is applied
physics::LinkPtr link_;
/// \brief The Link this plugin is attached to, and will exert forces on.
private: std::string link_name_;
boost::shared_ptr<ros::NodeHandle> rosnode_;
ros::Publisher odometry_pub_;
ros::Subscriber vel_sub_;
boost::shared_ptr<tf::TransformBroadcaster> transform_broadcaster_;
nav_msgs::Odometry odom_;
std::string tf_prefix_;
boost::mutex lock;
std::string robot_namespace_;
std::string command_topic_;
std::string odometry_topic_;
std::string odometry_frame_;
std::string robot_base_frame_;
double odometry_rate_;
// Custom Callback Queue
ros::CallbackQueue queue_;
boost::thread callback_queue_thread_;
void QueueThread();
// command velocity callback
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
double x_;
double y_;
double rot_;
bool alive_;
common::Time last_odom_publish_time_;
math::Pose last_odom_pose_;
};
}
#endif /* end of include guard: GAZEBO_ROS_PLANAR_MOVE_HH */

View file

@ -0,0 +1,100 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_GPS_H
#define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_GPS_H
#include <gazebo/common/Plugin.hh>
#include <ros/ros.h>
#include <sensor_msgs/NavSatFix.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <hector_gazebo_plugins/sensor_model.h>
#include <hector_gazebo_plugins/update_timer.h>
#include <dynamic_reconfigure/server.h>
#include <hector_gazebo_plugins/GNSSConfig.h>
namespace gazebo
{
class GazeboRosGps : public ModelPlugin
{
public:
GazeboRosGps();
virtual ~GazeboRosGps();
protected:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
virtual void Reset();
virtual void Update();
typedef hector_gazebo_plugins::GNSSConfig GNSSConfig;
void dynamicReconfigureCallback(GNSSConfig &config, uint32_t level);
private:
/// \brief The parent World
physics::WorldPtr world;
/// \brief The link referred to by this plugin
physics::LinkPtr link;
ros::NodeHandle* node_handle_;
ros::Publisher fix_publisher_;
ros::Publisher velocity_publisher_;
sensor_msgs::NavSatFix fix_;
geometry_msgs::Vector3Stamped velocity_;
std::string namespace_;
std::string link_name_;
std::string frame_id_;
std::string fix_topic_;
std::string velocity_topic_;
double reference_latitude_;
double reference_longitude_;
double reference_heading_;
double reference_altitude_;
double radius_north_;
double radius_east_;
SensorModel3 position_error_model_;
SensorModel3 velocity_error_model_;
UpdateTimer updateTimer;
event::ConnectionPtr updateConnection;
boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > dynamic_reconfigure_server_position_, dynamic_reconfigure_server_velocity_;
boost::shared_ptr<dynamic_reconfigure::Server<GNSSConfig> > dynamic_reconfigure_server_status_;
};
} // namespace gazebo
#endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_GPS_H

View file

@ -0,0 +1,141 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H
#define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H
// #define USE_CBQ
#ifdef USE_CBQ
#include <ros/callback_queue.h>
#include <ros/advertise_options.h>
#endif
#include <gazebo/common/Plugin.hh>
#include <ros/ros.h>
#include <boost/thread/mutex.hpp>
#include <sensor_msgs/Imu.h>
#include <std_srvs/Empty.h>
#include <hector_gazebo_plugins/SetBias.h>
#include <hector_gazebo_plugins/sensor_model.h>
#include <hector_gazebo_plugins/update_timer.h>
#include <dynamic_reconfigure/server.h>
namespace gazebo
{
class GazeboRosIMU : public ModelPlugin
{
public:
/// \brief Constructor
GazeboRosIMU();
/// \brief Destructor
virtual ~GazeboRosIMU();
protected:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
virtual void Reset();
virtual void Update();
private:
/// \brief The parent World
physics::WorldPtr world;
/// \brief The link referred to by this plugin
physics::LinkPtr link;
/// \brief pointer to ros node
ros::NodeHandle* node_handle_;
ros::Publisher pub_;
ros::Publisher bias_pub_;
/// \brief ros message
sensor_msgs::Imu imuMsg;
sensor_msgs::Imu biasMsg;
/// \brief store link name
std::string link_name_;
/// \brief frame id
std::string frame_id_;
/// \brief topic name
std::string topic_;
std::string bias_topic_;
/// \brief allow specifying constant xyz and rpy offsets
math::Pose offset_;
/// \brief Sensor models
SensorModel3 accelModel;
SensorModel3 rateModel;
SensorModel yawModel;
/// \brief A mutex to lock access to fields that are used in message callbacks
boost::mutex lock;
/// \brief save current body/physics state
math::Quaternion orientation;
math::Vector3 velocity;
math::Vector3 accel;
math::Vector3 rate;
math::Vector3 gravity;
/// \brief Gaussian noise generator
double GaussianKernel(double mu,double sigma);
/// \brief for setting ROS name space
std::string namespace_;
/// \brief call back when using service
bool ServiceCallback(std_srvs::Empty::Request &req,
std_srvs::Empty::Response &res);
ros::ServiceServer srv_;
std::string serviceName;
/// \brief Bias service callbacks
bool SetAccelBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res);
bool SetRateBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res);
ros::ServiceServer accelBiasService;
ros::ServiceServer rateBiasService;
#ifdef USE_CBQ
ros::CallbackQueue callback_queue_;
void CallbackQueueThread();
boost::thread callback_queue_thread_;
#endif
UpdateTimer updateTimer;
event::ConnectionPtr updateConnection;
boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > dynamic_reconfigure_server_accel_, dynamic_reconfigure_server_rate_, dynamic_reconfigure_server_yaw_;
};
}
#endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H

View file

@ -0,0 +1,88 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_MAGNETIC_H
#define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_MAGNETIC_H
#include <gazebo/common/Plugin.hh>
#include <ros/ros.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <hector_gazebo_plugins/sensor_model.h>
#include <hector_gazebo_plugins/update_timer.h>
#include <dynamic_reconfigure/server.h>
namespace gazebo
{
class GazeboRosMagnetic : public ModelPlugin
{
public:
GazeboRosMagnetic();
virtual ~GazeboRosMagnetic();
protected:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
virtual void Reset();
virtual void Update();
private:
/// \brief The parent World
physics::WorldPtr world;
/// \brief The link referred to by this plugin
physics::LinkPtr link;
ros::NodeHandle* node_handle_;
ros::Publisher publisher_;
geometry_msgs::Vector3Stamped magnetic_field_;
gazebo::math::Vector3 magnetic_field_world_;
std::string namespace_;
std::string topic_;
std::string link_name_;
std::string frame_id_;
double magnitude_;
double reference_heading_;
double declination_;
double inclination_;
SensorModel3 sensor_model_;
UpdateTimer updateTimer;
event::ConnectionPtr updateConnection;
boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > dynamic_reconfigure_server_;
};
} // namespace gazebo
#endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_MAGNETIC_H

View file

@ -0,0 +1,82 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_SONAR_H
#define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_SONAR_H
#include <gazebo/common/Plugin.hh>
#include <ros/callback_queue.h>
#include <ros/ros.h>
#include <sensor_msgs/Range.h>
#include <hector_gazebo_plugins/sensor_model.h>
#include <hector_gazebo_plugins/update_timer.h>
#include <dynamic_reconfigure/server.h>
namespace gazebo
{
class GazeboRosSonar : public SensorPlugin
{
public:
GazeboRosSonar();
virtual ~GazeboRosSonar();
protected:
virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
virtual void Reset();
virtual void Update();
private:
/// \brief The parent World
physics::WorldPtr world;
sensors::RaySensorPtr sensor_;
ros::NodeHandle* node_handle_;
ros::Publisher publisher_;
sensor_msgs::Range range_;
std::string namespace_;
std::string topic_;
std::string frame_id_;
SensorModel sensor_model_;
UpdateTimer updateTimer;
event::ConnectionPtr updateConnection;
boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > dynamic_reconfigure_server_;
};
} // namespace gazebo
#endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_SONAR_H

View file

@ -0,0 +1,55 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#ifndef HECTOR_GAZEBO_PLUGINS_RESET_PLUGIN_H
#define HECTOR_GAZEBO_PLUGINS_RESET_PLUGIN_H
#include <gazebo/common/Plugin.hh>
#include <ros/ros.h>
namespace gazebo
{
class GazeboResetPlugin : public ModelPlugin
{
public:
GazeboResetPlugin();
virtual ~GazeboResetPlugin();
protected:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
virtual void Reset();
private:
ros::NodeHandle* node_handle_;
ros::Publisher publisher_;
};
} // namespace gazebo
#endif // HECTOR_GAZEBO_PLUGINS_RESET_PLUGIN_H

View file

@ -0,0 +1,236 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#ifndef HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H
#define HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H
#include <sdf/sdf.hh>
#include <gazebo/math/Vector3.hh>
#include <hector_gazebo_plugins/SensorModelConfig.h>
#include <numeric>
namespace gazebo {
using hector_gazebo_plugins::SensorModelConfig;
template <typename T>
class SensorModel_ {
public:
SensorModel_();
virtual ~SensorModel_();
virtual void Load(sdf::ElementPtr _sdf, const std::string& prefix = std::string());
virtual T operator()(const T& value) const { return value * scale_error + current_error_; }
virtual T operator()(const T& value, double dt) { return value * scale_error + update(dt); }
virtual T update(double dt);
virtual void reset();
virtual void reset(const T& value);
virtual const T& getCurrentError() const { return current_error_; }
virtual T getCurrentBias() const { return current_drift_ + offset; }
virtual const T& getCurrentDrift() const { return current_drift_; }
virtual const T& getScaleError() const { return scale_error; }
virtual void setCurrentDrift(const T& new_drift) { current_drift_ = new_drift; }
virtual void dynamicReconfigureCallback(SensorModelConfig &config, uint32_t level);
private:
virtual bool LoadImpl(sdf::ElementPtr _element, T& _value);
public:
T offset;
T drift;
T drift_frequency;
T gaussian_noise;
T scale_error;
private:
T current_drift_;
T current_error_;
};
template <typename T>
SensorModel_<T>::SensorModel_()
: offset()
, drift()
, drift_frequency()
, gaussian_noise()
{
drift_frequency = 1.0/3600.0; // time constant 1h
scale_error = 1.0;
reset();
}
template <typename T>
SensorModel_<T>::~SensorModel_()
{
}
template <typename T>
void SensorModel_<T>::Load(sdf::ElementPtr _sdf, const std::string& prefix)
{
std::string _offset, _drift, _drift_frequency, _gaussian_noise, _scale_error;
if (prefix.empty()) {
_offset = "offset";
_drift = "drift";
_drift_frequency = "driftFrequency";
_gaussian_noise = "gaussianNoise";
_scale_error = "scaleError";
} else {
_offset = prefix + "Offset";
_drift = prefix + "Drift";
_drift_frequency = prefix + "DriftFrequency";
_gaussian_noise = prefix + "GaussianNoise";
_scale_error = prefix + "ScaleError";
}
if (_sdf->HasElement(_offset)) LoadImpl(_sdf->GetElement(_offset), offset);
if (_sdf->HasElement(_drift)) LoadImpl(_sdf->GetElement(_drift), drift);
if (_sdf->HasElement(_drift_frequency)) LoadImpl(_sdf->GetElement(_drift_frequency), drift_frequency);
if (_sdf->HasElement(_gaussian_noise)) LoadImpl(_sdf->GetElement(_gaussian_noise), gaussian_noise);
if (_sdf->HasElement(_scale_error)) LoadImpl(_sdf->GetElement(_scale_error), scale_error);
reset();
}
template <typename T>
bool SensorModel_<T>::LoadImpl(sdf::ElementPtr _element, T& _value) {
if (!_element->GetValue()) return false;
return _element->GetValue()->Get(_value);
}
namespace {
template <typename T>
static inline T SensorModelGaussianKernel(T mu, T sigma)
{
// using Box-Muller transform to generate two independent standard normally distributed normal variables
// see wikipedia
T U = (T)rand()/(T)RAND_MAX; // normalized uniform random variable
T V = (T)rand()/(T)RAND_MAX; // normalized uniform random variable
T X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V);
X = sigma * X + mu;
return X;
}
template <typename T>
static inline T SensorModelInternalUpdate(T& current_drift, T drift, T drift_frequency, T offset, T gaussian_noise, double dt)
{
// current_drift = current_drift - dt * (current_drift * drift_frequency + SensorModelGaussianKernel(T(), sqrt(2*drift_frequency)*drift));
current_drift = exp(-dt * drift_frequency) * current_drift + dt * SensorModelGaussianKernel(T(), sqrt(2*drift_frequency)*drift);
return offset + current_drift + SensorModelGaussianKernel(T(), gaussian_noise);
}
}
template <typename T>
T SensorModel_<T>::update(double dt)
{
for(std::size_t i = 0; i < current_error_.size(); ++i) current_error_[i] = SensorModelInternalUpdate(current_drift_[i], drift[i], drift_frequency[i], offset[i], gaussian_noise[i], dt);
return current_error_;
}
template <>
double SensorModel_<double>::update(double dt)
{
current_error_ = SensorModelInternalUpdate(current_drift_, drift, drift_frequency, offset, gaussian_noise, dt);
return current_error_;
}
template <>
math::Vector3 SensorModel_<math::Vector3>::update(double dt)
{
current_error_.x = SensorModelInternalUpdate(current_drift_.x, drift.x, drift_frequency.x, offset.x, gaussian_noise.x, dt);
current_error_.y = SensorModelInternalUpdate(current_drift_.y, drift.y, drift_frequency.y, offset.y, gaussian_noise.y, dt);
current_error_.z = SensorModelInternalUpdate(current_drift_.z, drift.z, drift_frequency.z, offset.z, gaussian_noise.z, dt);
return current_error_;
}
template <typename T>
void SensorModel_<T>::reset()
{
for(std::size_t i = 0; i < current_drift_.size(); ++i) current_drift_[i] = SensorModelGaussianKernel(T::value_type(), drift[i]);
current_error_ = T();
}
template <>
void SensorModel_<double>::reset()
{
current_drift_ = SensorModelGaussianKernel(0.0, drift);
current_error_ = 0.0;
}
template <>
void SensorModel_<math::Vector3>::reset()
{
current_drift_.x = SensorModelGaussianKernel(0.0, drift.x);
current_drift_.y = SensorModelGaussianKernel(0.0, drift.y);
current_drift_.z = SensorModelGaussianKernel(0.0, drift.z);
current_error_ = math::Vector3();
}
template <typename T>
void SensorModel_<T>::reset(const T& value)
{
current_drift_ = value;
current_error_ = T();
}
namespace helpers {
template <typename T> struct scalar_value { static double toDouble(const T &orig) { return orig; } };
template <typename T> struct scalar_value<std::vector<T> > { static double toDouble(const std::vector<T> &orig) { return (double) std::accumulate(orig.begin(), orig.end()) / orig.size(); } };
template <> struct scalar_value<math::Vector3> { static double toDouble(const math::Vector3 &orig) { return (orig.x + orig.y + orig.z) / 3; } };
}
template <typename T>
void SensorModel_<T>::dynamicReconfigureCallback(SensorModelConfig &config, uint32_t level)
{
if (level == 1) {
gaussian_noise = config.gaussian_noise;
offset = config.offset;
drift = config.drift;
drift_frequency = config.drift_frequency;
scale_error = config.scale_error;
} else {
config.gaussian_noise = helpers::scalar_value<T>::toDouble(gaussian_noise);
config.offset = helpers::scalar_value<T>::toDouble(offset);
config.drift = helpers::scalar_value<T>::toDouble(drift);
config.drift_frequency = helpers::scalar_value<T>::toDouble(drift_frequency);
config.scale_error = helpers::scalar_value<T>::toDouble(scale_error);
}
}
typedef SensorModel_<double> SensorModel;
typedef SensorModel_<math::Vector3> SensorModel3;
}
#endif // HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H

View file

@ -0,0 +1,117 @@
/*
* Gazebo - Outdoor Multi-Robot Simulator
* Copyright (C) 2003
* Nate Koenig & Andrew Howard
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/
#ifndef SERVO_PLUGIN_H
#define SERVO_PLUGIN_H
#include <gazebo/common/Plugin.hh>
#include <gazebo/common/Time.hh>
#include <gazebo/math/Quaternion.hh>
// ROS
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/QuaternionStamped.h>
#include <sensor_msgs/JointState.h>
// Boost
#include <boost/thread.hpp>
#include <boost/bind.hpp>
namespace gazebo
{
class ServoPlugin : public ModelPlugin
{
public:
ServoPlugin();
virtual ~ServoPlugin();
protected:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
virtual void Init();
virtual void Reset();
virtual void Update();
private:
void CalculateVelocities();
void publish_joint_states();
private:
/// \brief The parent World
physics::WorldPtr world;
// Simulation time of the last update
common::Time prevUpdateTime;
bool enableMotors;
struct Servo {
std::string name;
math::Vector3 axis;
physics::JointPtr joint;
float velocity;
Servo() : velocity() {}
} servo[3];
unsigned int countOfServos;
unsigned int orderOfAxes[3];
unsigned int rotationConv;
sensor_msgs::JointState joint_state;
// parameters
std::string robotNamespace;
std::string topicName;
std::string jointStateName;
common::Time controlPeriod;
float proportionalControllerGain;
float derivativeControllerGain;
double maximumVelocity;
float maximumTorque;
// ROS STUFF
ros::NodeHandle* rosnode_;
ros::Publisher jointStatePub_;
ros::Subscriber sub_;
tf::TransformListener* transform_listener_;
// Custom Callback Queue
ros::CallbackQueue queue_;
// boost::thread* callback_queue_thread_;
// void QueueThread();
// DiffDrive stuff
void cmdCallback(const geometry_msgs::QuaternionStamped::ConstPtr& cmd_msg);
boost::mutex mutex;
geometry_msgs::QuaternionStamped::ConstPtr current_cmd;
math::Quaternion rotation_;
// Pointer to the update event connection
event::ConnectionPtr updateConnection;
};
}
#endif

View file

@ -0,0 +1,168 @@
//=================================================================================================
// Copyright (c) 2013, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#ifndef HECTOR_GAZEBO_PLUGINS_UPDATE_TIMER_H
#define HECTOR_GAZEBO_PLUGINS_UPDATE_TIMER_H
#include <sdf/sdf.hh>
#include <gazebo/physics/World.hh>
#include <gazebo/physics/PhysicsEngine.hh>
#include <gazebo/common/Event.hh>
#include <gazebo/common/Events.hh>
namespace gazebo {
class UpdateTimer {
public:
UpdateTimer()
: connection_count_(0)
{
}
virtual ~UpdateTimer()
{
}
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf, const std::string& _prefix = "update")
{
this->world_ = _world;
if (_sdf->HasElement(_prefix + "Rate")) {
double update_rate = 0.0;
_sdf->GetElement(_prefix + "Rate")->GetValue()->Get(update_rate);
update_period_ = update_rate > 0.0 ? 1.0/update_rate : 0.0;
}
if (_sdf->HasElement(_prefix + "Period")) {
_sdf->GetElement(_prefix + "Period")->GetValue()->Get(update_period_);
}
if (_sdf->HasElement(_prefix + "Offset")) {
_sdf->GetElement(_prefix + "Offset")->GetValue()->Get(update_offset_);
}
}
virtual event::ConnectionPtr Connect(const boost::function<void()> &_subscriber, bool connectToWorldUpdateBegin = true)
{
if (connectToWorldUpdateBegin && !update_connection_) {
update_connection_ = event::Events::ConnectWorldUpdateBegin(
boost::bind(&UpdateTimer::Update, this));
}
connection_count_++;
return update_event_.Connect(_subscriber);
}
virtual void Disconnect(event::ConnectionPtr const& _c = event::ConnectionPtr())
{
if (_c) update_event_.Disconnect(_c);
if (update_connection_ && (!_c || --connection_count_ == 0)) {
event::Events::DisconnectWorldUpdateBegin(update_connection_);
update_connection_.reset();
}
}
common::Time const& getUpdatePeriod() const {
return update_period_;
}
void setUpdatePeriod(common::Time const& period) {
update_period_ = period;
}
double getUpdateRate() const {
double period = update_period_.Double();
return (period > 0.0) ? (1.0 / period) : 0.0;
}
void setUpdateRate(double rate) {
update_period_ = (rate > 0.0) ? (1.0 / rate) : 0.0;
}
common::Time const& getLastUpdate() const {
return last_update_;
}
common::Time getTimeSinceLastUpdate() const {
if (last_update_ == common::Time()) return common::Time();
return world_->GetSimTime() - last_update_;
}
virtual bool checkUpdate() const
{
double period = update_period_.Double();
double step = world_->GetPhysicsEngine()->GetMaxStepSize();
if (period == 0) return true;
double fraction = fmod((world_->GetSimTime() - update_offset_).Double() + (step / 2.0), period);
return (fraction >= 0.0) && (fraction < step);
}
virtual bool update()
{
if (!checkUpdate()) return false;
last_update_ = world_->GetSimTime();
return true;
}
virtual bool update(double& dt)
{
dt = getTimeSinceLastUpdate().Double();
return update();
}
virtual void Reset()
{
last_update_ = common::Time();
}
protected:
virtual bool Update()
{
if (!checkUpdate()) {
return false;
}
update_event_();
last_update_ = world_->GetSimTime();
return true;
}
private:
physics::WorldPtr world_;
common::Time update_period_;
common::Time update_offset_;
common::Time last_update_;
event::EventT<void()> update_event_;
unsigned int connection_count_;
event::ConnectionPtr update_connection_;
};
} // namespace gazebo
#endif // HECTOR_GAZEBO_PLUGINS_UPDATE_TIMER_H

View file

@ -0,0 +1,41 @@
<package>
<name>hector_gazebo_plugins</name>
<version>0.3.6</version>
<description>hector_gazebo_plugins provides gazebo plugins from Team Hector.
Currently it contains a 6wd differential drive plugin, an IMU sensor plugin,
an earth magnetic field sensor plugin, a GPS sensor plugin and a
sonar ranger plugin.</description>
<maintainer email="meyer@fsr.tu-darmstadt.de">Johannes Meyer</maintainer>
<license>BSD</license>
<url type="website">http://ros.org/wiki/hector_gazebo_plugins</url>
<!-- <url type="bugtracker"></url> -->
<author email="kohlbrecher@sim.tu-darmstadt.de">Stefan Kohlbrecher</author>
<author email="meyer@fsr.tu-darmstadt.de">Johannes Meyer</author>
<!-- Dependencies which this package needs to build itself. -->
<buildtool_depend>catkin</buildtool_depend>
<!-- Dependencies needed to compile this package. -->
<build_depend>roscpp</build_depend>
<build_depend>gazebo</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<!-- Dependencies needed after this package is compiled. -->
<run_depend>roscpp</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
</package>

View file

@ -0,0 +1,335 @@
//=================================================================================================
// Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Simulation, Systems Optimization and Robotics
// group, TU Darmstadt nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
/**
* Based on diffdrive_plugin by Nathan Koenig, Andrew Howard and Daniel Hewlett
*/
#include <algorithm>
#include <assert.h>
#include <hector_gazebo_plugins/diffdrive_plugin_6w.h>
#include <gazebo/common/Events.hh>
#include <gazebo/physics/physics.hh>
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/Twist.h>
#include <nav_msgs/Odometry.h>
#include <boost/bind.hpp>
namespace gazebo {
enum
{
FRONT_LEFT,
FRONT_RIGHT,
MID_LEFT,
MID_RIGHT,
REAR_LEFT,
REAR_RIGHT,
NUM_WHEELS
};
// Constructor
DiffDrivePlugin6W::DiffDrivePlugin6W()
{
}
// Destructor
DiffDrivePlugin6W::~DiffDrivePlugin6W()
{
event::Events::DisconnectWorldUpdateBegin(updateConnection);
delete transform_broadcaster_;
rosnode_->shutdown();
callback_queue_thread_.join();
delete rosnode_;
}
// Load the controller
void DiffDrivePlugin6W::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
world = _model->GetWorld();
// default parameters
namespace_.clear();
topic_ = "cmd_vel";
wheelSep = 0.34;
wheelDiam = 0.15;
torque = 10.0;
// load parameters
if (_sdf->HasElement("robotNamespace"))
namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
if (_sdf->HasElement("topicName"))
topic_ = _sdf->GetElement("topicName")->GetValue()->GetAsString();
if (_sdf->HasElement("bodyName"))
{
link_name_ = _sdf->GetElement("bodyName")->GetValue()->GetAsString();
link = _model->GetLink(link_name_);
} else {
link = _model->GetLink();
link_name_ = link->GetName();
}
// assert that the body by link_name_ exists
if (!link)
{
ROS_FATAL("DiffDrivePlugin6W plugin error: bodyName: %s does not exist\n", link_name_.c_str());
return;
}
if (_sdf->HasElement("frontLeftJoint")) joints[FRONT_LEFT] = _model->GetJoint(_sdf->GetElement("frontLeftJoint")->GetValue()->GetAsString());
if (_sdf->HasElement("frontRightJoint")) joints[FRONT_RIGHT] = _model->GetJoint(_sdf->GetElement("frontRightJoint")->GetValue()->GetAsString());
if (_sdf->HasElement("midLeftJoint")) joints[MID_LEFT] = _model->GetJoint(_sdf->GetElement("midLeftJoint")->GetValue()->GetAsString());
if (_sdf->HasElement("midRightJoint")) joints[MID_RIGHT] = _model->GetJoint(_sdf->GetElement("midRightJoint")->GetValue()->GetAsString());
if (_sdf->HasElement("rearLeftJoint")) joints[REAR_LEFT] = _model->GetJoint(_sdf->GetElement("rearLeftJoint")->GetValue()->GetAsString());
if (_sdf->HasElement("rearRightJoint")) joints[REAR_RIGHT] = _model->GetJoint(_sdf->GetElement("rearRightJoint")->GetValue()->GetAsString());
if (!joints[FRONT_LEFT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get front left joint");
if (!joints[FRONT_RIGHT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get front right joint");
if (!joints[MID_LEFT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get mid left joint");
if (!joints[MID_RIGHT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get mid right joint");
if (!joints[REAR_LEFT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get rear left joint");
if (!joints[REAR_RIGHT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get rear right joint");
if (_sdf->HasElement("wheelSeparation"))
_sdf->GetElement("wheelSeparation")->GetValue()->Get(wheelSep);
if (_sdf->HasElement("wheelDiameter"))
_sdf->GetElement("wheelDiameter")->GetValue()->Get(wheelDiam);
if (_sdf->HasElement("torque"))
_sdf->GetElement("torque")->GetValue()->Get(torque);
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
rosnode_ = new ros::NodeHandle(namespace_);
tf_prefix_ = tf::getPrefixParam(*rosnode_);
transform_broadcaster_ = new tf::TransformBroadcaster();
// ROS: Subscribe to the velocity command topic (usually "cmd_vel")
ros::SubscribeOptions so =
ros::SubscribeOptions::create<geometry_msgs::Twist>(topic_, 1,
boost::bind(&DiffDrivePlugin6W::cmdVelCallback, this, _1),
ros::VoidPtr(), &queue_);
sub_ = rosnode_->subscribe(so);
pub_ = rosnode_->advertise<nav_msgs::Odometry>("odom", 1);
callback_queue_thread_ = boost::thread(boost::bind(&DiffDrivePlugin6W::QueueThread, this));
Reset();
// New Mechanism for Updating every World Cycle
// Listen to the update event. This event is broadcast every
// simulation iteration.
updateConnection = event::Events::ConnectWorldUpdateBegin(
boost::bind(&DiffDrivePlugin6W::Update, this));
}
// Initialize the controller
void DiffDrivePlugin6W::Reset()
{
enableMotors = true;
for (size_t i = 0; i < 2; ++i){
wheelSpeed[i] = 0;
}
prevUpdateTime = world->GetSimTime();
x_ = 0;
rot_ = 0;
alive_ = true;
// Reset odometric pose
odomPose[0] = 0.0;
odomPose[1] = 0.0;
odomPose[2] = 0.0;
odomVel[0] = 0.0;
odomVel[1] = 0.0;
odomVel[2] = 0.0;
}
// Update the controller
void DiffDrivePlugin6W::Update()
{
// TODO: Step should be in a parameter of this function
double d1, d2;
double dr, da;
common::Time stepTime;
GetPositionCmd();
//stepTime = World::Instance()->GetPhysicsEngine()->GetStepTime();
stepTime = world->GetSimTime() - prevUpdateTime;
prevUpdateTime = world->GetSimTime();
// Distance travelled by front wheels
d1 = stepTime.Double() * wheelDiam / 2 * joints[MID_LEFT]->GetVelocity(0);
d2 = stepTime.Double() * wheelDiam / 2 * joints[MID_RIGHT]->GetVelocity(0);
dr = (d1 + d2) / 2;
da = (d1 - d2) / wheelSep;
// Compute odometric pose
odomPose[0] += dr * cos(odomPose[2]);
odomPose[1] += dr * sin(odomPose[2]);
odomPose[2] += da;
// Compute odometric instantaneous velocity
odomVel[0] = dr / stepTime.Double();
odomVel[1] = 0.0;
odomVel[2] = da / stepTime.Double();
if (enableMotors)
{
joints[FRONT_LEFT]->SetVelocity(0, wheelSpeed[0] / (wheelDiam / 2.0));
joints[MID_LEFT]->SetVelocity(0, wheelSpeed[0] / (wheelDiam / 2.0));
joints[REAR_LEFT]->SetVelocity(0, wheelSpeed[0] / (wheelDiam / 2.0));
joints[FRONT_RIGHT]->SetVelocity(0, wheelSpeed[1] / (wheelDiam / 2.0));
joints[MID_RIGHT]->SetVelocity(0, wheelSpeed[1] / (wheelDiam / 2.0));
joints[REAR_RIGHT]->SetVelocity(0, wheelSpeed[1] / (wheelDiam / 2.0));
joints[FRONT_LEFT]->SetMaxForce(0, torque);
joints[MID_LEFT]->SetMaxForce(0, torque);
joints[REAR_LEFT]->SetMaxForce(0, torque);
joints[FRONT_RIGHT]->SetMaxForce(0, torque);
joints[MID_RIGHT]->SetMaxForce(0, torque);
joints[REAR_RIGHT]->SetMaxForce(0, torque);
}
//publish_odometry();
}
// NEW: Now uses the target velocities from the ROS message, not the Iface
void DiffDrivePlugin6W::GetPositionCmd()
{
lock.lock();
double vr, va;
vr = x_; //myIface->data->cmdVelocity.pos.x;
va = -rot_; //myIface->data->cmdVelocity.yaw;
//std::cout << "X: [" << x_ << "] ROT: [" << rot_ << "]" << std::endl;
// Changed motors to be always on, which is probably what we want anyway
enableMotors = true; //myIface->data->cmdEnableMotors > 0;
//std::cout << enableMotors << std::endl;
wheelSpeed[0] = vr + va * wheelSep / 2;
wheelSpeed[1] = vr - va * wheelSep / 2;
lock.unlock();
}
// NEW: Store the velocities from the ROS message
void DiffDrivePlugin6W::cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg)
{
//std::cout << "BEGIN CALLBACK\n";
lock.lock();
x_ = cmd_msg->linear.x;
rot_ = cmd_msg->angular.z;
lock.unlock();
//std::cout << "END CALLBACK\n";
}
// NEW: custom callback queue thread
void DiffDrivePlugin6W::QueueThread()
{
static const double timeout = 0.01;
while (alive_ && rosnode_->ok())
{
// std::cout << "CALLING STUFF\n";
queue_.callAvailable(ros::WallDuration(timeout));
}
}
// NEW: Update this to publish odometry topic
void DiffDrivePlugin6W::publish_odometry()
{
// get current time
ros::Time current_time_((world->GetSimTime()).sec, (world->GetSimTime()).nsec);
// getting data for base_footprint to odom transform
math::Pose pose = link->GetWorldPose();
math::Vector3 velocity = link->GetWorldLinearVel();
math::Vector3 angular_velocity = link->GetWorldAngularVel();
tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
tf::Transform base_footprint_to_odom(qt, vt);
transform_broadcaster_->sendTransform(tf::StampedTransform(base_footprint_to_odom,
current_time_,
"odom",
"base_footprint"));
// publish odom topic
odom_.pose.pose.position.x = pose.pos.x;
odom_.pose.pose.position.y = pose.pos.y;
odom_.pose.pose.orientation.x = pose.rot.x;
odom_.pose.pose.orientation.y = pose.rot.y;
odom_.pose.pose.orientation.z = pose.rot.z;
odom_.pose.pose.orientation.w = pose.rot.w;
odom_.twist.twist.linear.x = velocity.x;
odom_.twist.twist.linear.y = velocity.y;
odom_.twist.twist.angular.z = angular_velocity.z;
odom_.header.frame_id = tf::resolve(tf_prefix_, "odom");
odom_.child_frame_id = "base_footprint";
odom_.header.stamp = current_time_;
pub_.publish(odom_);
}
GZ_REGISTER_MODEL_PLUGIN(DiffDrivePlugin6W)
} // namespace gazebo

View file

@ -0,0 +1,408 @@
/*
Copyright (c) 2010, Daniel Hewlett, Antons Rebguns
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of the <organization> nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*
* \file gazebo_ros_diff_drive.cpp
*
* \brief A differential drive plugin for gazebo. Based on the diffdrive plugin
* developed for the erratic robot (see copyright notice above). The original
* plugin can be found in the ROS package gazebo_erratic_plugins.
*
* \author Piyush Khandelwal (piyushk@gmail.com)
*
* $ Id: 06/21/2013 11:23:40 AM piyushk $
*/
/**
* A diff drive plugin supporting multiple wheels per vehicle side. Based on
* existing plugins as stated above this notice.
*/
/*
Copyright (c) 2014, Stefan Kohlbrecher
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of the <organization> nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include <algorithm>
#include <assert.h>
#include <hector_gazebo_plugins/diffdrive_plugin_multi_wheel.h>
#include <gazebo/math/gzmath.hh>
#include <sdf/sdf.hh>
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/Twist.h>
#include <nav_msgs/GetMap.h>
#include <nav_msgs/Odometry.h>
#include <boost/bind.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/algorithm/string/split.hpp>
#include <boost/algorithm/string/classification.hpp>
namespace gazebo {
enum {
RIGHT,
LEFT,
};
GazeboRosDiffDriveMultiWheel::GazeboRosDiffDriveMultiWheel() {}
// Destructor
GazeboRosDiffDriveMultiWheel::~GazeboRosDiffDriveMultiWheel() {
delete rosnode_;
delete transform_broadcaster_;
}
// Load the controller
void GazeboRosDiffDriveMultiWheel::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
this->parent = _parent;
this->world = _parent->GetWorld();
this->robot_namespace_ = "";
if (!_sdf->HasElement("robotNamespace")) {
ROS_INFO("GazeboRosDiffDriveMultiWheel Plugin missing <robotNamespace>, defaults to \"%s\"",
this->robot_namespace_.c_str());
} else {
this->robot_namespace_ =
_sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
}
//this->left_joint_names_ = "left_joint";
if (!_sdf->HasElement("leftJoints")) {
gzthrow("Have to specify space separated left side joint names via <leftJoints> tag!");
} else {
std::string joint_string = _sdf->GetElement("leftJoints")->Get<std::string>();
boost::split( joint_names_[LEFT], joint_string, boost::is_any_of(" ") );
}
//this->right_joint_names_ = "right_joint";
if (!_sdf->HasElement("rightJoints")) {
gzthrow("Have to specify space separated right side joint names via <rightJoints> tag!");
} else {
std::string joint_string = _sdf->GetElement("rightJoints")->Get<std::string>();
boost::split( joint_names_[RIGHT], joint_string, boost::is_any_of(" ") );
}
this->wheel_separation_ = 0.34;
if (!_sdf->HasElement("wheelSeparation")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <wheelSeparation>, defaults to %f",
this->robot_namespace_.c_str(), this->wheel_separation_);
} else {
this->wheel_separation_ =
_sdf->GetElement("wheelSeparation")->Get<double>();
}
this->wheel_diameter_ = 0.15;
if (!_sdf->HasElement("wheelDiameter")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <wheelDiameter>, defaults to %f",
this->robot_namespace_.c_str(), this->wheel_diameter_);
} else {
this->wheel_diameter_ = _sdf->GetElement("wheelDiameter")->Get<double>();
}
this->torque = 5.0;
if (!_sdf->HasElement("torque")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <torque>, defaults to %f",
this->robot_namespace_.c_str(), this->torque);
} else {
this->torque = _sdf->GetElement("torque")->Get<double>();
}
this->command_topic_ = "cmd_vel";
if (!_sdf->HasElement("commandTopic")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <commandTopic>, defaults to \"%s\"",
this->robot_namespace_.c_str(), this->command_topic_.c_str());
} else {
this->command_topic_ = _sdf->GetElement("commandTopic")->Get<std::string>();
}
this->odometry_topic_ = "odom";
if (!_sdf->HasElement("odometryTopic")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <odometryTopic>, defaults to \"%s\"",
this->robot_namespace_.c_str(), this->odometry_topic_.c_str());
} else {
this->odometry_topic_ = _sdf->GetElement("odometryTopic")->Get<std::string>();
}
this->odometry_frame_ = "odom";
if (!_sdf->HasElement("odometryFrame")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <odometryFrame>, defaults to \"%s\"",
this->robot_namespace_.c_str(), this->odometry_frame_.c_str());
} else {
this->odometry_frame_ = _sdf->GetElement("odometryFrame")->Get<std::string>();
}
this->robot_base_frame_ = "base_footprint";
if (!_sdf->HasElement("robotBaseFrame")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <robotBaseFrame>, defaults to \"%s\"",
this->robot_namespace_.c_str(), this->robot_base_frame_.c_str());
} else {
this->robot_base_frame_ = _sdf->GetElement("robotBaseFrame")->Get<std::string>();
}
this->update_rate_ = 100.0;
if (!_sdf->HasElement("updateRate")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <updateRate>, defaults to %f",
this->robot_namespace_.c_str(), this->update_rate_);
} else {
this->update_rate_ = _sdf->GetElement("updateRate")->Get<double>();
}
this->publish_odometry_tf_ = true;
if (!_sdf->HasElement("publishOdometryTf")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <publishOdometryTf>, defaults to %s",
this->robot_namespace_.c_str(), this->publish_odometry_tf_ ? "true" : "false");
} else {
this->publish_odometry_tf_ = _sdf->GetElement("publishOdometryTf")->Get<bool>();
}
this->publish_odometry_msg_ = true;
if (!_sdf->HasElement("publishOdometryMsg")) {
ROS_WARN("GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <publishOdometryMsg>, defaults to %s",
this->robot_namespace_.c_str(), this->publish_odometry_msg_ ? "true" : "false");
} else {
this->publish_odometry_msg_ = _sdf->GetElement("publishOdometryMsg")->Get<bool>();
}
// Initialize update rate stuff
if (this->update_rate_ > 0.0) {
this->update_period_ = 1.0 / this->update_rate_;
} else {
this->update_period_ = 0.0;
}
last_update_time_ = this->world->GetSimTime();
// Initialize velocity stuff
wheel_speed_[RIGHT] = 0;
wheel_speed_[LEFT] = 0;
x_ = 0;
rot_ = 0;
alive_ = true;
for (size_t side = 0; side < 2; ++side){
for (size_t i = 0; i < joint_names_[side].size(); ++i){
joints_[side].push_back(this->parent->GetJoint(joint_names_[side][i]));
if (!joints_[side][i]){
char error[200];
snprintf(error, 200,
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) couldn't get hinge joint named \"%s\"",
this->robot_namespace_.c_str(), joint_names_[side][i].c_str());
gzthrow(error);
}
joints_[side][i]->SetMaxForce(0, torque);
}
}
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
rosnode_ = new ros::NodeHandle(this->robot_namespace_);
ROS_INFO("Starting GazeboRosDiffDriveMultiWheel Plugin (ns = %s)!", this->robot_namespace_.c_str());
tf_prefix_ = tf::getPrefixParam(*rosnode_);
transform_broadcaster_ = new tf::TransformBroadcaster();
// ROS: Subscribe to the velocity command topic (usually "cmd_vel")
ros::SubscribeOptions so =
ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
boost::bind(&GazeboRosDiffDriveMultiWheel::cmdVelCallback, this, _1),
ros::VoidPtr(), &queue_);
cmd_vel_subscriber_ = rosnode_->subscribe(so);
odometry_publisher_ = rosnode_->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
// start custom queue for diff drive
this->callback_queue_thread_ =
boost::thread(boost::bind(&GazeboRosDiffDriveMultiWheel::QueueThread, this));
// listen to the update event (broadcast every simulation iteration)
this->update_connection_ =
event::Events::ConnectWorldUpdateBegin(
boost::bind(&GazeboRosDiffDriveMultiWheel::UpdateChild, this));
}
// Update the controller
void GazeboRosDiffDriveMultiWheel::UpdateChild() {
common::Time current_time = this->world->GetSimTime();
double seconds_since_last_update =
(current_time - last_update_time_).Double();
if (seconds_since_last_update > update_period_) {
if (this->publish_odometry_tf_ || this->publish_odometry_msg_){
publishOdometry(seconds_since_last_update);
}
// Update robot in case new velocities have been requested
getWheelVelocities();
//joints[LEFT]->SetVelocity(0, wheel_speed_[LEFT] / wheel_diameter_);
//joints[RIGHT]->SetVelocity(0, wheel_speed_[RIGHT] / wheel_diameter_);
for (size_t side = 0; side < 2; ++side){
for (size_t i = 0; i < joints_[side].size(); ++i){
joints_[side][i]->SetVelocity(0, wheel_speed_[side] / (0.5 * wheel_diameter_));
}
}
last_update_time_+= common::Time(update_period_);
}
}
// Finalize the controller
void GazeboRosDiffDriveMultiWheel::FiniChild() {
alive_ = false;
queue_.clear();
queue_.disable();
rosnode_->shutdown();
callback_queue_thread_.join();
}
void GazeboRosDiffDriveMultiWheel::getWheelVelocities() {
boost::mutex::scoped_lock scoped_lock(lock);
double vr = x_;
double va = rot_;
wheel_speed_[LEFT] = vr - va * wheel_separation_ / 2.0;
wheel_speed_[RIGHT] = vr + va * wheel_separation_ / 2.0;
}
void GazeboRosDiffDriveMultiWheel::cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& cmd_msg) {
boost::mutex::scoped_lock scoped_lock(lock);
x_ = cmd_msg->linear.x;
rot_ = cmd_msg->angular.z;
}
void GazeboRosDiffDriveMultiWheel::QueueThread() {
static const double timeout = 0.01;
while (alive_ && rosnode_->ok()) {
queue_.callAvailable(ros::WallDuration(timeout));
}
}
void GazeboRosDiffDriveMultiWheel::publishOdometry(double step_time) {
ros::Time current_time = ros::Time::now();
std::string odom_frame =
tf::resolve(tf_prefix_, odometry_frame_);
std::string base_footprint_frame =
tf::resolve(tf_prefix_, robot_base_frame_);
// getting data for base_footprint to odom transform
math::Pose pose = this->parent->GetWorldPose();
tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
tf::Transform base_footprint_to_odom(qt, vt);
if (this->publish_odometry_tf_){
transform_broadcaster_->sendTransform(
tf::StampedTransform(base_footprint_to_odom, current_time,
odom_frame, base_footprint_frame));
}
// publish odom topic
odom_.pose.pose.position.x = pose.pos.x;
odom_.pose.pose.position.y = pose.pos.y;
odom_.pose.pose.orientation.x = pose.rot.x;
odom_.pose.pose.orientation.y = pose.rot.y;
odom_.pose.pose.orientation.z = pose.rot.z;
odom_.pose.pose.orientation.w = pose.rot.w;
odom_.pose.covariance[0] = 0.00001;
odom_.pose.covariance[7] = 0.00001;
odom_.pose.covariance[14] = 1000000000000.0;
odom_.pose.covariance[21] = 1000000000000.0;
odom_.pose.covariance[28] = 1000000000000.0;
odom_.pose.covariance[35] = 0.001;
// get velocity in /odom frame
math::Vector3 linear;
linear = this->parent->GetWorldLinearVel();
odom_.twist.twist.angular.z = this->parent->GetWorldAngularVel().z;
// convert velocity to child_frame_id (aka base_footprint)
float yaw = pose.rot.GetYaw();
odom_.twist.twist.linear.x = cosf(yaw) * linear.x + sinf(yaw) * linear.y;
odom_.twist.twist.linear.y = cosf(yaw) * linear.y - sinf(yaw) * linear.x;
odom_.header.stamp = current_time;
odom_.header.frame_id = odom_frame;
odom_.child_frame_id = base_footprint_frame;
if (this->publish_odometry_msg_){
odometry_publisher_.publish(odom_);
}
}
GZ_REGISTER_MODEL_PLUGIN(GazeboRosDiffDriveMultiWheel)
}

View file

@ -0,0 +1,296 @@
/*
* Copyright 2015 Stefan Kohlbrecher, TU Darmstadt
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
/*
* Desc: Simple model controller that uses a twist message to exert
* forces on a robot, resulting in motion. Based on the
* planar_move plugin by Piyush Khandelwal.
* Author: Stefan Kohlbrecher
* Date: 06 August 2015
*/
#include <hector_gazebo_plugins/gazebo_ros_force_based_move.h>
namespace gazebo
{
GazeboRosForceBasedMove::GazeboRosForceBasedMove() {}
GazeboRosForceBasedMove::~GazeboRosForceBasedMove() {}
// Load the controller
void GazeboRosForceBasedMove::Load(physics::ModelPtr parent,
sdf::ElementPtr sdf)
{
parent_ = parent;
/* Parse parameters */
robot_namespace_ = "";
if (!sdf->HasElement("robotNamespace"))
{
ROS_INFO("PlanarMovePlugin missing <robotNamespace>, "
"defaults to \"%s\"", robot_namespace_.c_str());
}
else
{
robot_namespace_ =
sdf->GetElement("robotNamespace")->Get<std::string>();
}
command_topic_ = "cmd_vel";
if (!sdf->HasElement("commandTopic"))
{
ROS_WARN("PlanarMovePlugin (ns = %s) missing <commandTopic>, "
"defaults to \"%s\"",
robot_namespace_.c_str(), command_topic_.c_str());
}
else
{
command_topic_ = sdf->GetElement("commandTopic")->Get<std::string>();
}
odometry_topic_ = "odom";
if (!sdf->HasElement("odometryTopic"))
{
ROS_WARN("PlanarMovePlugin (ns = %s) missing <odometryTopic>, "
"defaults to \"%s\"",
robot_namespace_.c_str(), odometry_topic_.c_str());
}
else
{
odometry_topic_ = sdf->GetElement("odometryTopic")->Get<std::string>();
}
odometry_frame_ = "odom";
if (!sdf->HasElement("odometryFrame"))
{
ROS_WARN("PlanarMovePlugin (ns = %s) missing <odometryFrame>, "
"defaults to \"%s\"",
robot_namespace_.c_str(), odometry_frame_.c_str());
}
else
{
odometry_frame_ = sdf->GetElement("odometryFrame")->Get<std::string>();
}
robot_base_frame_ = "base_footprint";
if (!sdf->HasElement("robotBaseFrame"))
{
ROS_WARN("PlanarMovePlugin (ns = %s) missing <robotBaseFrame>, "
"defaults to \"%s\"",
robot_namespace_.c_str(), robot_base_frame_.c_str());
}
else
{
robot_base_frame_ = sdf->GetElement("robotBaseFrame")->Get<std::string>();
}
ROS_INFO_STREAM("robotBaseFrame for force based move plugin: " << robot_base_frame_ << "\n");
this->link_ = parent->GetLink(robot_base_frame_);
odometry_rate_ = 20.0;
if (!sdf->HasElement("odometryRate"))
{
ROS_WARN("PlanarMovePlugin (ns = %s) missing <odometryRate>, "
"defaults to %f",
robot_namespace_.c_str(), odometry_rate_);
}
else
{
odometry_rate_ = sdf->GetElement("odometryRate")->Get<double>();
}
last_odom_publish_time_ = parent_->GetWorld()->GetSimTime();
last_odom_pose_ = parent_->GetWorldPose();
x_ = 0;
y_ = 0;
rot_ = 0;
alive_ = true;
// Ensure that ROS has been initialized and subscribe to cmd_vel
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("PlanarMovePlugin (ns = " << robot_namespace_
<< "). A ROS node for Gazebo has not been initialized, "
<< "unable to load plugin. Load the Gazebo system plugin "
<< "'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
rosnode_.reset(new ros::NodeHandle(robot_namespace_));
ROS_DEBUG("OCPlugin (%s) has started!",
robot_namespace_.c_str());
tf_prefix_ = tf::getPrefixParam(*rosnode_);
transform_broadcaster_.reset(new tf::TransformBroadcaster());
// subscribe to the odometry topic
ros::SubscribeOptions so =
ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
boost::bind(&GazeboRosForceBasedMove::cmdVelCallback, this, _1),
ros::VoidPtr(), &queue_);
vel_sub_ = rosnode_->subscribe(so);
odometry_pub_ = rosnode_->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
// start custom queue for diff drive
callback_queue_thread_ =
boost::thread(boost::bind(&GazeboRosForceBasedMove::QueueThread, this));
// listen to the update event (broadcast every simulation iteration)
update_connection_ =
event::Events::ConnectWorldUpdateBegin(
boost::bind(&GazeboRosForceBasedMove::UpdateChild, this));
}
// Update the controller
void GazeboRosForceBasedMove::UpdateChild()
{
boost::mutex::scoped_lock scoped_lock(lock);
math::Pose pose = parent_->GetWorldPose();
math::Vector3 angular_vel = parent_->GetWorldAngularVel();
double error = angular_vel.z - rot_;
link_->AddTorque(math::Vector3(0.0, 0.0, -error * 100.0));
float yaw = pose.rot.GetYaw();
math::Vector3 linear_vel = parent_->GetRelativeLinearVel();
link_->AddRelativeForce(math::Vector3((x_ - linear_vel.x)* 10000,
(y_ - linear_vel.y)* 10000,
0.0));
//parent_->PlaceOnNearestEntityBelow();
//parent_->SetLinearVel(math::Vector3(
// x_ * cosf(yaw) - y_ * sinf(yaw),
// y_ * cosf(yaw) + x_ * sinf(yaw),
// 0));
//parent_->SetAngularVel(math::Vector3(0, 0, rot_));
if (odometry_rate_ > 0.0) {
common::Time current_time = parent_->GetWorld()->GetSimTime();
double seconds_since_last_update =
(current_time - last_odom_publish_time_).Double();
if (seconds_since_last_update > (1.0 / odometry_rate_)) {
publishOdometry(seconds_since_last_update);
last_odom_publish_time_ = current_time;
}
}
}
// Finalize the controller
void GazeboRosForceBasedMove::FiniChild() {
alive_ = false;
queue_.clear();
queue_.disable();
rosnode_->shutdown();
callback_queue_thread_.join();
}
void GazeboRosForceBasedMove::cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& cmd_msg)
{
boost::mutex::scoped_lock scoped_lock(lock);
x_ = cmd_msg->linear.x;
y_ = cmd_msg->linear.y;
rot_ = cmd_msg->angular.z;
}
void GazeboRosForceBasedMove::QueueThread()
{
static const double timeout = 0.01;
while (alive_ && rosnode_->ok())
{
queue_.callAvailable(ros::WallDuration(timeout));
}
}
void GazeboRosForceBasedMove::publishOdometry(double step_time)
{
ros::Time current_time = ros::Time::now();
std::string odom_frame = tf::resolve(tf_prefix_, odometry_frame_);
std::string base_footprint_frame =
tf::resolve(tf_prefix_, robot_base_frame_);
// getting data for base_footprint to odom transform
math::Pose pose = this->parent_->GetWorldPose();
tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
tf::Transform base_footprint_to_odom(qt, vt);
transform_broadcaster_->sendTransform(
tf::StampedTransform(base_footprint_to_odom, current_time, odom_frame,
base_footprint_frame));
// publish odom topic
odom_.pose.pose.position.x = pose.pos.x;
odom_.pose.pose.position.y = pose.pos.y;
odom_.pose.pose.orientation.x = pose.rot.x;
odom_.pose.pose.orientation.y = pose.rot.y;
odom_.pose.pose.orientation.z = pose.rot.z;
odom_.pose.pose.orientation.w = pose.rot.w;
odom_.pose.covariance[0] = 0.00001;
odom_.pose.covariance[7] = 0.00001;
odom_.pose.covariance[14] = 1000000000000.0;
odom_.pose.covariance[21] = 1000000000000.0;
odom_.pose.covariance[28] = 1000000000000.0;
odom_.pose.covariance[35] = 0.001;
// get velocity in /odom frame
math::Vector3 linear;
linear.x = (pose.pos.x - last_odom_pose_.pos.x) / step_time;
linear.y = (pose.pos.y - last_odom_pose_.pos.y) / step_time;
if (rot_ > M_PI / step_time)
{
// we cannot calculate the angular velocity correctly
odom_.twist.twist.angular.z = rot_;
}
else
{
float last_yaw = last_odom_pose_.rot.GetYaw();
float current_yaw = pose.rot.GetYaw();
while (current_yaw < last_yaw - M_PI) current_yaw += 2 * M_PI;
while (current_yaw > last_yaw + M_PI) current_yaw -= 2 * M_PI;
float angular_diff = current_yaw - last_yaw;
odom_.twist.twist.angular.z = angular_diff / step_time;
}
last_odom_pose_ = pose;
// convert velocity to child_frame_id (aka base_footprint)
float yaw = pose.rot.GetYaw();
odom_.twist.twist.linear.x = cosf(yaw) * linear.x + sinf(yaw) * linear.y;
odom_.twist.twist.linear.y = cosf(yaw) * linear.y - sinf(yaw) * linear.x;
odom_.header.stamp = current_time;
odom_.header.frame_id = odom_frame;
odom_.child_frame_id = base_footprint_frame;
odometry_pub_.publish(odom_);
}
GZ_REGISTER_MODEL_PLUGIN(GazeboRosForceBasedMove)
}

View file

@ -0,0 +1,243 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include <hector_gazebo_plugins/gazebo_ros_gps.h>
#include <gazebo/physics/physics.hh>
// WGS84 constants
static const double equatorial_radius = 6378137.0;
static const double flattening = 1.0/298.257223563;
static const double excentrity2 = 2*flattening - flattening*flattening;
// default reference position
static const double DEFAULT_REFERENCE_LATITUDE = 49.9;
static const double DEFAULT_REFERENCE_LONGITUDE = 8.9;
static const double DEFAULT_REFERENCE_HEADING = 0.0;
static const double DEFAULT_REFERENCE_ALTITUDE = 0.0;
namespace gazebo {
GazeboRosGps::GazeboRosGps()
{
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
GazeboRosGps::~GazeboRosGps()
{
updateTimer.Disconnect(updateConnection);
dynamic_reconfigure_server_position_.reset();
dynamic_reconfigure_server_velocity_.reset();
dynamic_reconfigure_server_status_.reset();
node_handle_->shutdown();
delete node_handle_;
}
////////////////////////////////////////////////////////////////////////////////
// Load the controller
void GazeboRosGps::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
world = _model->GetWorld();
// load parameters
if (!_sdf->HasElement("robotNamespace"))
namespace_.clear();
else
namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
if (!_sdf->HasElement("bodyName"))
{
link = _model->GetLink();
link_name_ = link->GetName();
}
else {
link_name_ = _sdf->GetElement("bodyName")->GetValue()->GetAsString();
link = _model->GetLink(link_name_);
}
if (!link)
{
ROS_FATAL("GazeboRosGps plugin error: bodyName: %s does not exist\n", link_name_.c_str());
return;
}
// default parameters
frame_id_ = "/world";
fix_topic_ = "fix";
velocity_topic_ = "fix_velocity";
reference_latitude_ = DEFAULT_REFERENCE_LATITUDE;
reference_longitude_ = DEFAULT_REFERENCE_LONGITUDE;
reference_heading_ = DEFAULT_REFERENCE_HEADING * M_PI/180.0;
reference_altitude_ = DEFAULT_REFERENCE_ALTITUDE;
fix_.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
fix_.status.service = sensor_msgs::NavSatStatus::STATUS_FIX;
if (_sdf->HasElement("frameId"))
frame_id_ = _sdf->GetElement("frameId")->GetValue()->GetAsString();
if (_sdf->HasElement("topicName"))
fix_topic_ = _sdf->GetElement("topicName")->GetValue()->GetAsString();
if (_sdf->HasElement("velocityTopicName"))
velocity_topic_ = _sdf->GetElement("velocityTopicName")->GetValue()->GetAsString();
if (_sdf->HasElement("referenceLatitude"))
_sdf->GetElement("referenceLatitude")->GetValue()->Get(reference_latitude_);
if (_sdf->HasElement("referenceLongitude"))
_sdf->GetElement("referenceLongitude")->GetValue()->Get(reference_longitude_);
if (_sdf->HasElement("referenceHeading"))
if (_sdf->GetElement("referenceHeading")->GetValue()->Get(reference_heading_))
reference_heading_ *= M_PI/180.0;
if (_sdf->HasElement("referenceAltitude"))
_sdf->GetElement("referenceAltitude")->GetValue()->Get(reference_altitude_);
if (_sdf->HasElement("status"))
_sdf->GetElement("status")->GetValue()->Get(fix_.status.status);
if (_sdf->HasElement("service"))
_sdf->GetElement("service")->GetValue()->Get(fix_.status.service);
fix_.header.frame_id = frame_id_;
velocity_.header.frame_id = frame_id_;
position_error_model_.Load(_sdf);
velocity_error_model_.Load(_sdf, "velocity");
// calculate earth radii
double temp = 1.0 / (1.0 - excentrity2 * sin(reference_latitude_ * M_PI/180.0) * sin(reference_latitude_ * M_PI/180.0));
double prime_vertical_radius = equatorial_radius * sqrt(temp);
radius_north_ = prime_vertical_radius * (1 - excentrity2) * temp;
radius_east_ = prime_vertical_radius * cos(reference_latitude_ * M_PI/180.0);
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
node_handle_ = new ros::NodeHandle(namespace_);
fix_publisher_ = node_handle_->advertise<sensor_msgs::NavSatFix>(fix_topic_, 10);
velocity_publisher_ = node_handle_->advertise<geometry_msgs::Vector3Stamped>(velocity_topic_, 10);
// setup dynamic_reconfigure servers
dynamic_reconfigure_server_position_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, fix_topic_ + "/position")));
dynamic_reconfigure_server_velocity_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, fix_topic_ + "/velocity")));
dynamic_reconfigure_server_status_.reset(new dynamic_reconfigure::Server<GNSSConfig>(ros::NodeHandle(*node_handle_, fix_topic_ + "/status")));
dynamic_reconfigure_server_position_->setCallback(boost::bind(&SensorModel3::dynamicReconfigureCallback, &position_error_model_, _1, _2));
dynamic_reconfigure_server_velocity_->setCallback(boost::bind(&SensorModel3::dynamicReconfigureCallback, &velocity_error_model_, _1, _2));
dynamic_reconfigure_server_status_->setCallback(boost::bind(&GazeboRosGps::dynamicReconfigureCallback, this, _1, _2));
Reset();
// connect Update function
updateTimer.setUpdateRate(4.0);
updateTimer.Load(world, _sdf);
updateConnection = updateTimer.Connect(boost::bind(&GazeboRosGps::Update, this));
}
void GazeboRosGps::Reset()
{
updateTimer.Reset();
position_error_model_.reset();
velocity_error_model_.reset();
}
void GazeboRosGps::dynamicReconfigureCallback(GazeboRosGps::GNSSConfig &config, uint32_t level)
{
using sensor_msgs::NavSatStatus;
if (level == 1) {
if (!config.STATUS_FIX) {
fix_.status.status = NavSatStatus::STATUS_NO_FIX;
} else {
fix_.status.status = (config.STATUS_SBAS_FIX ? NavSatStatus::STATUS_SBAS_FIX : 0) |
(config.STATUS_GBAS_FIX ? NavSatStatus::STATUS_GBAS_FIX : 0);
}
fix_.status.service = (config.SERVICE_GPS ? NavSatStatus::SERVICE_GPS : 0) |
(config.SERVICE_GLONASS ? NavSatStatus::SERVICE_GLONASS : 0) |
(config.SERVICE_COMPASS ? NavSatStatus::SERVICE_COMPASS : 0) |
(config.SERVICE_GALILEO ? NavSatStatus::SERVICE_GALILEO : 0);
} else {
config.STATUS_FIX = (fix_.status.status != NavSatStatus::STATUS_NO_FIX);
config.STATUS_SBAS_FIX = (fix_.status.status & NavSatStatus::STATUS_SBAS_FIX);
config.STATUS_GBAS_FIX = (fix_.status.status & NavSatStatus::STATUS_GBAS_FIX);
config.SERVICE_GPS = (fix_.status.service & NavSatStatus::SERVICE_GPS);
config.SERVICE_GLONASS = (fix_.status.service & NavSatStatus::SERVICE_GLONASS);
config.SERVICE_COMPASS = (fix_.status.service & NavSatStatus::SERVICE_COMPASS);
config.SERVICE_GALILEO = (fix_.status.service & NavSatStatus::SERVICE_GALILEO);
}
}
////////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosGps::Update()
{
common::Time sim_time = world->GetSimTime();
double dt = updateTimer.getTimeSinceLastUpdate().Double();
math::Pose pose = link->GetWorldPose();
gazebo::math::Vector3 velocity = velocity_error_model_(link->GetWorldLinearVel(), dt);
gazebo::math::Vector3 position = position_error_model_(pose.pos, dt);
// An offset error in the velocity is integrated into the position error for the next timestep.
// Note: Usually GNSS receivers have almost no drift in the velocity signal.
position_error_model_.setCurrentDrift(position_error_model_.getCurrentDrift() + dt * velocity_error_model_.getCurrentDrift());
fix_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec);
velocity_.header.stamp = fix_.header.stamp;
fix_.latitude = reference_latitude_ + ( cos(reference_heading_) * position.x + sin(reference_heading_) * position.y) / radius_north_ * 180.0/M_PI;
fix_.longitude = reference_longitude_ - (-sin(reference_heading_) * position.x + cos(reference_heading_) * position.y) / radius_east_ * 180.0/M_PI;
fix_.altitude = reference_altitude_ + position.z;
velocity_.vector.x = cos(reference_heading_) * velocity.x + sin(reference_heading_) * velocity.y;
velocity_.vector.y = -sin(reference_heading_) * velocity.x + cos(reference_heading_) * velocity.y;
velocity_.vector.z = velocity.z;
fix_.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
fix_.position_covariance[0] = position_error_model_.drift.x*position_error_model_.drift.x + position_error_model_.gaussian_noise.x*position_error_model_.gaussian_noise.x;
fix_.position_covariance[4] = position_error_model_.drift.y*position_error_model_.drift.y + position_error_model_.gaussian_noise.y*position_error_model_.gaussian_noise.y;
fix_.position_covariance[8] = position_error_model_.drift.z*position_error_model_.drift.z + position_error_model_.gaussian_noise.z*position_error_model_.gaussian_noise.z;
fix_publisher_.publish(fix_);
velocity_publisher_.publish(velocity_);
}
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(GazeboRosGps)
} // namespace gazebo

View file

@ -0,0 +1,384 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include <hector_gazebo_plugins/gazebo_ros_imu.h>
#include <gazebo/common/Events.hh>
#include <gazebo/physics/physics.hh>
#include <ros/console.h>
namespace gazebo
{
// #define DEBUG_OUTPUT
#ifdef DEBUG_OUTPUT
#include <geometry_msgs/PoseStamped.h>
static ros::Publisher debugPublisher;
#endif // DEBUG_OUTPUT
////////////////////////////////////////////////////////////////////////////////
// Constructor
GazeboRosIMU::GazeboRosIMU()
{
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
GazeboRosIMU::~GazeboRosIMU()
{
updateTimer.Disconnect(updateConnection);
dynamic_reconfigure_server_accel_.reset();
dynamic_reconfigure_server_rate_.reset();
dynamic_reconfigure_server_yaw_.reset();
node_handle_->shutdown();
#ifdef USE_CBQ
callback_queue_thread_.join();
#endif
delete node_handle_;
}
////////////////////////////////////////////////////////////////////////////////
// Load the controller
void GazeboRosIMU::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
// Get the world name.
world = _model->GetWorld();
// load parameters
if (_sdf->HasElement("robotNamespace"))
namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
else
namespace_.clear();
if (_sdf->HasElement("bodyName"))
{
link_name_ = _sdf->GetElement("bodyName")->GetValue()->GetAsString();
link = _model->GetLink(link_name_);
}
else
{
link = _model->GetLink();
link_name_ = link->GetName();
}
// assert that the body by link_name_ exists
if (!link)
{
ROS_FATAL("GazeboRosIMU plugin error: bodyName: %s does not exist\n", link_name_.c_str());
return;
}
// default parameters
frame_id_ = link_name_;
topic_ = "imu";
if (_sdf->HasElement("frameId"))
frame_id_ = _sdf->GetElement("frameId")->GetValue()->GetAsString();
if (_sdf->HasElement("topicName"))
topic_ = _sdf->GetElement("topicName")->GetValue()->GetAsString();
if (_sdf->HasElement("biasTopicName"))
bias_topic_ = _sdf->GetElement("biasTopicName")->GetValue()->GetAsString();
else
bias_topic_ = (!topic_.empty() ? topic_ + "/bias" : "");
if (_sdf->HasElement("serviceName"))
serviceName = _sdf->GetElement("serviceName")->GetValue()->GetAsString();
else
serviceName = topic_ + "/calibrate";
accelModel.Load(_sdf, "accel");
rateModel.Load(_sdf, "rate");
yawModel.Load(_sdf, "yaw");
// also use old configuration variables from gazebo_ros_imu
if (_sdf->HasElement("gaussianNoise")) {
double gaussianNoise;
if (_sdf->GetElement("gaussianNoise")->GetValue()->Get(gaussianNoise) && gaussianNoise != 0.0) {
accelModel.gaussian_noise = gaussianNoise;
rateModel.gaussian_noise = gaussianNoise;
}
}
if (_sdf->HasElement("xyzOffset")) {
this->offset_.pos = _sdf->Get<math::Vector3>("xyzOffset");
} else {
ROS_INFO("imu plugin missing <xyzOffset>, defaults to 0s");
this->offset_.pos = math::Vector3(0, 0, 0);
}
if (_sdf->HasElement("rpyOffset")) {
this->offset_.rot = _sdf->Get<math::Vector3>("rpyOffset");
} else {
ROS_INFO("imu plugin missing <rpyOffset>, defaults to 0s");
this->offset_.rot = math::Vector3(0, 0, 0);
}
// fill in constant covariance matrix
imuMsg.angular_velocity_covariance[0] = rateModel.gaussian_noise.x*rateModel.gaussian_noise.x;
imuMsg.angular_velocity_covariance[4] = rateModel.gaussian_noise.y*rateModel.gaussian_noise.y;
imuMsg.angular_velocity_covariance[8] = rateModel.gaussian_noise.z*rateModel.gaussian_noise.z;
imuMsg.linear_acceleration_covariance[0] = accelModel.gaussian_noise.x*accelModel.gaussian_noise.x;
imuMsg.linear_acceleration_covariance[4] = accelModel.gaussian_noise.y*accelModel.gaussian_noise.y;
imuMsg.linear_acceleration_covariance[8] = accelModel.gaussian_noise.z*accelModel.gaussian_noise.z;
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package.");
return;
}
node_handle_ = new ros::NodeHandle(namespace_);
// if topic name specified as empty, do not publish (then what is this plugin good for?)
if (!topic_.empty())
pub_ = node_handle_->advertise<sensor_msgs::Imu>(topic_, 10);
if (!bias_topic_.empty())
bias_pub_ = node_handle_->advertise<sensor_msgs::Imu>(bias_topic_, 10);
#ifdef DEBUG_OUTPUT
debugPublisher = rosnode_->advertise<geometry_msgs::PoseStamped>(topic_ + "/pose", 10);
#endif // DEBUG_OUTPUT
// advertise services for calibration and bias setting
if (!serviceName.empty())
srv_ = node_handle_->advertiseService(serviceName, &GazeboRosIMU::ServiceCallback, this);
accelBiasService = node_handle_->advertiseService(topic_ + "/set_accel_bias", &GazeboRosIMU::SetAccelBiasCallback, this);
rateBiasService = node_handle_->advertiseService(topic_ + "/set_rate_bias", &GazeboRosIMU::SetRateBiasCallback, this);
// setup dynamic_reconfigure servers
if (!topic_.empty()) {
dynamic_reconfigure_server_accel_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, topic_ + "/accel")));
dynamic_reconfigure_server_rate_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, topic_ + "/rate")));
dynamic_reconfigure_server_yaw_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, topic_ + "/yaw")));
dynamic_reconfigure_server_accel_->setCallback(boost::bind(&SensorModel3::dynamicReconfigureCallback, &accelModel, _1, _2));
dynamic_reconfigure_server_rate_->setCallback(boost::bind(&SensorModel3::dynamicReconfigureCallback, &rateModel, _1, _2));
dynamic_reconfigure_server_yaw_->setCallback(boost::bind(&SensorModel::dynamicReconfigureCallback, &yawModel, _1, _2));
}
#ifdef USE_CBQ
// start custom queue for imu
callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosIMU::CallbackQueueThread,this ) );
#endif
Reset();
// connect Update function
updateTimer.Load(world, _sdf);
updateConnection = updateTimer.Connect(boost::bind(&GazeboRosIMU::Update, this));
}
void GazeboRosIMU::Reset()
{
updateTimer.Reset();
orientation = math::Quaternion();
velocity = 0.0;
accel = 0.0;
accelModel.reset();
rateModel.reset();
yawModel.reset();
}
////////////////////////////////////////////////////////////////////////////////
// returns true always, imu is always calibrated in sim
bool GazeboRosIMU::ServiceCallback(std_srvs::Empty::Request &req,
std_srvs::Empty::Response &res)
{
boost::mutex::scoped_lock scoped_lock(lock);
rateModel.reset(math::Vector3(0.0, 0.0, 0.0));
return true;
}
bool GazeboRosIMU::SetAccelBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
{
boost::mutex::scoped_lock scoped_lock(lock);
accelModel.reset(math::Vector3(req.bias.x, req.bias.y, req.bias.z));
return true;
}
bool GazeboRosIMU::SetRateBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
{
boost::mutex::scoped_lock scoped_lock(lock);
rateModel.reset(math::Vector3(req.bias.x, req.bias.y, req.bias.z));
return true;
}
////////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosIMU::Update()
{
// Get Time Difference dt
common::Time cur_time = world->GetSimTime();
double dt = updateTimer.getTimeSinceLastUpdate().Double();
boost::mutex::scoped_lock scoped_lock(lock);
// Get Pose/Orientation
math::Pose pose = link->GetWorldPose();
// math::Vector3 pos = pose.pos + this->offset_.pos;
math::Quaternion rot = this->offset_.rot * pose.rot;
rot.Normalize();
// get Gravity
gravity = world->GetPhysicsEngine()->GetGravity();
double gravity_length = gravity.GetLength();
ROS_DEBUG_NAMED("gazebo_ros_imu", "gravity_world = [%g %g %g]", gravity.x, gravity.y, gravity.z);
// get Acceleration and Angular Rates
// the result of GetRelativeLinearAccel() seems to be unreliable (sum of forces added during the current simulation step)?
//accel = myBody->GetRelativeLinearAccel(); // get acceleration in body frame
math::Vector3 temp = link->GetWorldLinearVel(); // get velocity in world frame
if (dt > 0.0) accel = rot.RotateVectorReverse((temp - velocity) / dt - gravity);
velocity = temp;
// calculate angular velocity from delta quaternion
// note: link->GetRelativeAngularVel() sometimes return nan?
// rate = link->GetRelativeAngularVel(); // get angular rate in body frame
math::Quaternion delta = this->orientation.GetInverse() * rot;
this->orientation = rot;
if (dt > 0.0) {
rate = 2.0 * acos(std::max(std::min(delta.w, 1.0), -1.0)) * math::Vector3(delta.x, delta.y, delta.z).Normalize() / dt;
}
// update sensor models
accel = accelModel(accel, dt);
rate = rateModel(rate, dt);
yawModel.update(dt);
ROS_DEBUG_NAMED("gazebo_ros_imu", "Current bias errors: accel = [%g %g %g], rate = [%g %g %g], yaw = %g",
accelModel.getCurrentBias().x, accelModel.getCurrentBias().y, accelModel.getCurrentBias().z,
rateModel.getCurrentBias().x, rateModel.getCurrentBias().y, rateModel.getCurrentBias().z,
yawModel.getCurrentBias());
ROS_DEBUG_NAMED("gazebo_ros_imu", "Scale errors: accel = [%g %g %g], rate = [%g %g %g], yaw = %g",
accelModel.getScaleError().x, accelModel.getScaleError().y, accelModel.getScaleError().z,
rateModel.getScaleError().x, rateModel.getScaleError().y, rateModel.getScaleError().z,
yawModel.getScaleError());
// apply accelerometer and yaw drift error to orientation (pseudo AHRS)
math::Vector3 accelDrift = pose.rot.RotateVector(accelModel.getCurrentBias());
double yawError = yawModel.getCurrentBias();
math::Quaternion orientationError(
math::Quaternion(cos(yawError/2), 0.0, 0.0, sin(yawError/2)) * // yaw error
math::Quaternion(1.0, 0.5 * accelDrift.y / gravity_length, 0.5 * -accelDrift.x / gravity_length, 0.0) // roll and pitch error
);
orientationError.Normalize();
rot = orientationError * rot;
// copy data into pose message
imuMsg.header.frame_id = frame_id_;
imuMsg.header.stamp.sec = cur_time.sec;
imuMsg.header.stamp.nsec = cur_time.nsec;
// orientation quaternion
imuMsg.orientation.x = rot.x;
imuMsg.orientation.y = rot.y;
imuMsg.orientation.z = rot.z;
imuMsg.orientation.w = rot.w;
// pass angular rates
imuMsg.angular_velocity.x = rate.x;
imuMsg.angular_velocity.y = rate.y;
imuMsg.angular_velocity.z = rate.z;
// pass accelerations
imuMsg.linear_acceleration.x = accel.x;
imuMsg.linear_acceleration.y = accel.y;
imuMsg.linear_acceleration.z = accel.z;
// fill in covariance matrix
imuMsg.orientation_covariance[8] = yawModel.gaussian_noise*yawModel.gaussian_noise;
if (gravity_length > 0.0) {
imuMsg.orientation_covariance[0] = accelModel.gaussian_noise.x*accelModel.gaussian_noise.x/(gravity_length*gravity_length);
imuMsg.orientation_covariance[4] = accelModel.gaussian_noise.y*accelModel.gaussian_noise.y/(gravity_length*gravity_length);
} else {
imuMsg.orientation_covariance[0] = -1;
imuMsg.orientation_covariance[4] = -1;
}
// publish to ros
pub_.publish(imuMsg);
ROS_DEBUG_NAMED("gazebo_ros_imu", "Publishing IMU data at t = %f", cur_time.Double());
// publish bias
if (bias_pub_) {
biasMsg.header = imuMsg.header;
biasMsg.orientation.x = orientationError.x;
biasMsg.orientation.y = orientationError.y;
biasMsg.orientation.z = orientationError.z;
biasMsg.orientation.w = orientationError.w;
biasMsg.angular_velocity.x = rateModel.getCurrentBias().x;
biasMsg.angular_velocity.y = rateModel.getCurrentBias().y;
biasMsg.angular_velocity.z = rateModel.getCurrentBias().z;
biasMsg.linear_acceleration.x = accelModel.getCurrentBias().x;
biasMsg.linear_acceleration.y = accelModel.getCurrentBias().y;
biasMsg.linear_acceleration.z = accelModel.getCurrentBias().z;
bias_pub_.publish(biasMsg);
}
// debug output
#ifdef DEBUG_OUTPUT
if (debugPublisher) {
geometry_msgs::PoseStamped debugPose;
debugPose.header = imuMsg.header;
debugPose.header.frame_id = "/map";
debugPose.pose.orientation.w = imuMsg.orientation.w;
debugPose.pose.orientation.x = imuMsg.orientation.x;
debugPose.pose.orientation.y = imuMsg.orientation.y;
debugPose.pose.orientation.z = imuMsg.orientation.z;
math::Pose pose = link->GetWorldPose();
debugPose.pose.position.x = pose.pos.x;
debugPose.pose.position.y = pose.pos.y;
debugPose.pose.position.z = pose.pos.z;
debugPublisher.publish(debugPose);
}
#endif // DEBUG_OUTPUT
}
#ifdef USE_CBQ
void GazeboRosIMU::CallbackQueueThread()
{
static const double timeout = 0.01;
while (rosnode_->ok())
{
callback_queue_.callAvailable(ros::WallDuration(timeout));
}
}
#endif
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(GazeboRosIMU)
} // namespace gazebo

View file

@ -0,0 +1,173 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include <hector_gazebo_plugins/gazebo_ros_magnetic.h>
#include <gazebo/common/Events.hh>
#include <gazebo/physics/physics.hh>
static const double DEFAULT_MAGNITUDE = 1.0;
static const double DEFAULT_REFERENCE_HEADING = 0.0;
static const double DEFAULT_DECLINATION = 0.0;
static const double DEFAULT_INCLINATION = 60.0;
namespace gazebo {
GazeboRosMagnetic::GazeboRosMagnetic()
{
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
GazeboRosMagnetic::~GazeboRosMagnetic()
{
updateTimer.Disconnect(updateConnection);
dynamic_reconfigure_server_.reset();
node_handle_->shutdown();
delete node_handle_;
}
////////////////////////////////////////////////////////////////////////////////
// Load the controller
void GazeboRosMagnetic::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
world = _model->GetWorld();
// load parameters
if (_sdf->HasElement("robotNamespace"))
namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
else
namespace_.clear();
if (!_sdf->HasElement("topicName"))
topic_ = "magnetic";
else
topic_ = _sdf->GetElement("topicName")->Get<std::string>();
if (_sdf->HasElement("bodyName"))
{
link_name_ = _sdf->GetElement("bodyName")->GetValue()->GetAsString();
link = _model->GetLink(link_name_);
}
else
{
link = _model->GetLink();
link_name_ = link->GetName();
}
if (!link)
{
ROS_FATAL("GazeboRosMagnetic plugin error: bodyName: %s does not exist\n", link_name_.c_str());
return;
}
// default parameters
frame_id_ = link_name_;
magnitude_ = DEFAULT_MAGNITUDE;
reference_heading_ = DEFAULT_REFERENCE_HEADING * M_PI/180.0;
declination_ = DEFAULT_DECLINATION * M_PI/180.0;
inclination_ = DEFAULT_INCLINATION * M_PI/180.0;
if (_sdf->HasElement("frameId"))
frame_id_ = _sdf->GetElement("frameId")->GetValue()->GetAsString();
if (_sdf->HasElement("magnitude"))
_sdf->GetElement("magnitude")->GetValue()->Get(magnitude_);
if (_sdf->HasElement("referenceHeading"))
if (_sdf->GetElement("referenceHeading")->GetValue()->Get(reference_heading_))
reference_heading_ *= M_PI/180.0;
if (_sdf->HasElement("declination"))
if (_sdf->GetElement("declination")->GetValue()->Get(declination_))
declination_ *= M_PI/180.0;
if (_sdf->HasElement("inclination"))
if (_sdf->GetElement("inclination")->GetValue()->Get(inclination_))
inclination_ *= M_PI/180.0;
// Note: Gazebo uses NorthWestUp coordinate system, heading and declination are compass headings
magnetic_field_.header.frame_id = frame_id_;
magnetic_field_world_.x = magnitude_ * cos(inclination_) * cos(reference_heading_ - declination_);
magnetic_field_world_.y = magnitude_ * cos(inclination_) * sin(reference_heading_ - declination_);
magnetic_field_world_.z = magnitude_ * -sin(inclination_);
sensor_model_.Load(_sdf);
// start ros node
if (!ros::isInitialized())
{
int argc = 0;
char** argv = NULL;
ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
}
node_handle_ = new ros::NodeHandle(namespace_);
publisher_ = node_handle_->advertise<geometry_msgs::Vector3Stamped>(topic_, 1);
// setup dynamic_reconfigure server
dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, topic_)));
dynamic_reconfigure_server_->setCallback(boost::bind(&SensorModel3::dynamicReconfigureCallback, &sensor_model_, _1, _2));
Reset();
// connect Update function
updateTimer.Load(world, _sdf);
updateConnection = updateTimer.Connect(boost::bind(&GazeboRosMagnetic::Update, this));
}
void GazeboRosMagnetic::Reset()
{
updateTimer.Reset();
sensor_model_.reset();
}
////////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosMagnetic::Update()
{
common::Time sim_time = world->GetSimTime();
double dt = updateTimer.getTimeSinceLastUpdate().Double();
math::Pose pose = link->GetWorldPose();
math::Vector3 field = sensor_model_(pose.rot.RotateVectorReverse(magnetic_field_world_), dt);
magnetic_field_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec);
magnetic_field_.vector.x = field.x;
magnetic_field_.vector.y = field.y;
magnetic_field_.vector.z = field.z;
publisher_.publish(magnetic_field_);
}
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(GazeboRosMagnetic)
} // namespace gazebo

View file

@ -0,0 +1,160 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include <hector_gazebo_plugins/gazebo_ros_sonar.h>
#include <gazebo/common/Events.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/sensors/RaySensor.hh>
#include <limits>
namespace gazebo {
GazeboRosSonar::GazeboRosSonar()
{
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
GazeboRosSonar::~GazeboRosSonar()
{
updateTimer.Disconnect(updateConnection);
sensor_->SetActive(false);
dynamic_reconfigure_server_.reset();
node_handle_->shutdown();
delete node_handle_;
}
////////////////////////////////////////////////////////////////////////////////
// Load the controller
void GazeboRosSonar::Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
{
// Get then name of the parent sensor
sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(_sensor);
if (!sensor_)
{
gzthrow("GazeboRosSonar requires a Ray Sensor as its parent");
return;
}
// Get the world name.
std::string worldName = sensor_->GetWorldName();
world = physics::get_world(worldName);
// default parameters
namespace_.clear();
topic_ = "sonar";
frame_id_ = "/sonar_link";
// load parameters
if (_sdf->HasElement("robotNamespace"))
namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
if (_sdf->HasElement("frameId"))
frame_id_ = _sdf->GetElement("frameId")->GetValue()->GetAsString();
if (_sdf->HasElement("topicName"))
topic_ = _sdf->GetElement("topicName")->GetValue()->GetAsString();
sensor_model_.Load(_sdf);
range_.header.frame_id = frame_id_;
range_.radiation_type = sensor_msgs::Range::ULTRASOUND;
range_.field_of_view = std::min(fabs((sensor_->GetAngleMax() - sensor_->GetAngleMin()).Radian()), fabs((sensor_->GetVerticalAngleMax() - sensor_->GetVerticalAngleMin()).Radian()));
range_.max_range = sensor_->GetRangeMax();
range_.min_range = sensor_->GetRangeMin();
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
node_handle_ = new ros::NodeHandle(namespace_);
publisher_ = node_handle_->advertise<sensor_msgs::Range>(topic_, 1);
// setup dynamic_reconfigure server
dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server<SensorModelConfig>(ros::NodeHandle(*node_handle_, topic_)));
dynamic_reconfigure_server_->setCallback(boost::bind(&SensorModel::dynamicReconfigureCallback, &sensor_model_, _1, _2));
Reset();
// connect Update function
updateTimer.setUpdateRate(10.0);
updateTimer.Load(world, _sdf);
updateConnection = updateTimer.Connect(boost::bind(&GazeboRosSonar::Update, this));
// activate RaySensor
sensor_->SetActive(true);
}
void GazeboRosSonar::Reset()
{
updateTimer.Reset();
sensor_model_.reset();
}
////////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosSonar::Update()
{
common::Time sim_time = world->GetSimTime();
double dt = updateTimer.getTimeSinceLastUpdate().Double();
// activate RaySensor if it is not yet active
if (!sensor_->IsActive()) sensor_->SetActive(true);
range_.header.stamp.sec = (world->GetSimTime()).sec;
range_.header.stamp.nsec = (world->GetSimTime()).nsec;
// find ray with minimal range
range_.range = std::numeric_limits<sensor_msgs::Range::_range_type>::max();
int num_ranges = sensor_->GetLaserShape()->GetSampleCount() * sensor_->GetLaserShape()->GetVerticalSampleCount();
for(int i = 0; i < num_ranges; ++i) {
double ray = sensor_->GetLaserShape()->GetRange(i);
if (ray < range_.range) range_.range = ray;
}
// add Gaussian noise (and limit to min/max range)
if (range_.range < range_.max_range) {
range_.range = sensor_model_(range_.range, dt);
if (range_.range < range_.min_range) range_.range = range_.min_range;
if (range_.range > range_.max_range) range_.range = range_.max_range;
}
publisher_.publish(range_);
}
// Register this plugin with the simulator
GZ_REGISTER_SENSOR_PLUGIN(GazeboRosSonar)
} // namespace gazebo

View file

@ -0,0 +1,76 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include <hector_gazebo_plugins/reset_plugin.h>
#include <gazebo/common/Events.hh>
#include <std_msgs/String.h>
namespace gazebo {
GazeboResetPlugin::GazeboResetPlugin()
{
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
GazeboResetPlugin::~GazeboResetPlugin()
{
node_handle_->shutdown();
delete node_handle_;
}
////////////////////////////////////////////////////////////////////////////////
// Load the controller
void GazeboResetPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
node_handle_ = new ros::NodeHandle;
publisher_ = node_handle_->advertise<std_msgs::String>("/syscommand", 1);
}
////////////////////////////////////////////////////////////////////////////////
// Reset the controller
void GazeboResetPlugin::Reset()
{
std_msgs::String command;
command.data = "reset";
publisher_.publish(command);
}
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(GazeboResetPlugin)
} // namespace gazebo

View file

@ -0,0 +1,386 @@
//=================================================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include <hector_gazebo_plugins/servo_plugin.h>
#include <gazebo/common/Events.hh>
#include <gazebo/physics/physics.hh>
#include <sensor_msgs/JointState.h>
#if (GAZEBO_MAJOR_VERSION > 1) || (GAZEBO_MINOR_VERSION >= 2)
#define RADIAN Radian
#else
#define RADIAN GetAsRadian
#endif
namespace gazebo {
GZ_REGISTER_MODEL_PLUGIN(ServoPlugin)
enum
{
FIRST = 0, SECOND = 1, THIRD = 2
};
enum
{
xyz, zyx
};
// Constructor
ServoPlugin::ServoPlugin()
{
rosnode_ = 0;
transform_listener_ = 0;
}
// Destructor
ServoPlugin::~ServoPlugin()
{
event::Events::DisconnectWorldUpdateBegin(updateConnection);
delete transform_listener_;
rosnode_->shutdown();
delete rosnode_;
}
// Load the controller
void ServoPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
// Get the world name.
world = _model->GetWorld();
// default parameters
topicName = "drive";
jointStateName = "joint_states";
robotNamespace.clear();
controlPeriod = 0;
proportionalControllerGain = 8.0;
derivativeControllerGain = 0.0;
maximumVelocity = 0.0;
maximumTorque = 0.0;
// load parameters
if (_sdf->HasElement("robotNamespace")) robotNamespace = _sdf->Get<std::string>("robotNamespace");
if (_sdf->HasElement("topicName")) topicName = _sdf->Get<std::string>("topicName");
if (_sdf->HasElement("jointStateName")) jointStateName = _sdf->Get<std::string>("jointStateName");
if (_sdf->HasElement("firstServoName")) servo[FIRST].name = _sdf->Get<std::string>("firstServoName");
if (_sdf->HasElement("firstServoAxis")) servo[FIRST].axis = _sdf->Get<math::Vector3>("firstServoAxis");
if (_sdf->HasElement("secondServoName")) servo[SECOND].name = _sdf->Get<std::string>("secondServoName");
if (_sdf->HasElement("secondServoAxis")) servo[SECOND].axis = _sdf->Get<math::Vector3>("secondServoAxis");
if (_sdf->HasElement("thirdServoName")) servo[THIRD].name = _sdf->Get<std::string>("thirdServoName");
if (_sdf->HasElement("thirdServoAxis")) servo[THIRD].axis = _sdf->Get<math::Vector3>("thirdServoAxis");
if (_sdf->HasElement("proportionalControllerGain")) proportionalControllerGain = _sdf->Get<double>("proportionalControllerGain");
if (_sdf->HasElement("derivativeControllerGain")) derivativeControllerGain = _sdf->Get<double>("derivativeControllerGain");
if (_sdf->HasElement("maxVelocity")) maximumVelocity = _sdf->Get<double>("maxVelocity");
if (_sdf->HasElement("torque")) maximumTorque = _sdf->Get<double>("torque");
double controlRate = 0.0;
if (_sdf->HasElement("controlRate")) controlRate = _sdf->Get<double>("controlRate");
controlPeriod = controlRate > 0.0 ? 1.0/controlRate : 0.0;
servo[FIRST].joint = _model->GetJoint(servo[FIRST].name);
servo[SECOND].joint = _model->GetJoint(servo[SECOND].name);
servo[THIRD].joint = _model->GetJoint(servo[THIRD].name);
if (!servo[FIRST].joint)
gzthrow("The controller couldn't get first joint");
countOfServos = 1;
if (servo[SECOND].joint) {
countOfServos = 2;
if (servo[THIRD].joint) {
countOfServos = 3;
}
}
else {
if (servo[THIRD].joint) {
gzthrow("The controller couldn't get second joint, but third joint was loaded");
}
}
if (!ros::isInitialized()) {
int argc = 0;
char** argv = NULL;
ros::init(argc, argv, "gazebo", ros::init_options::NoSigintHandler | ros::init_options::AnonymousName);
}
rosnode_ = new ros::NodeHandle(robotNamespace);
transform_listener_ = new tf::TransformListener();
transform_listener_->setExtrapolationLimit(ros::Duration(1.0));
if (!topicName.empty()) {
ros::SubscribeOptions so = ros::SubscribeOptions::create<geometry_msgs::QuaternionStamped>(topicName, 1,
boost::bind(&ServoPlugin::cmdCallback, this, _1),
ros::VoidPtr(), &queue_);
sub_ = rosnode_->subscribe(so);
}
if (!jointStateName.empty()) {
jointStatePub_ = rosnode_->advertise<sensor_msgs::JointState>(jointStateName, 10);
}
joint_state.header.frame_id = transform_listener_->resolve(_model->GetLink()->GetName());
// New Mechanism for Updating every World Cycle
// Listen to the update event. This event is broadcast every
// simulation iteration.
updateConnection = event::Events::ConnectWorldUpdateBegin(
boost::bind(&ServoPlugin::Update, this));
}
// Initialize the controller
void ServoPlugin::Init()
{
Reset();
}
// Reset
void ServoPlugin::Reset()
{
// Reset orientation
current_cmd.reset();
enableMotors = true;
servo[FIRST].velocity = 0;
servo[SECOND].velocity = 0;
servo[THIRD].velocity = 0;
prevUpdateTime = world->GetSimTime();
}
// Update the controller
void ServoPlugin::Update()
{
// handle callbacks
queue_.callAvailable();
common::Time stepTime;
stepTime = world->GetSimTime() - prevUpdateTime;
if (controlPeriod == 0.0 || stepTime > controlPeriod) {
CalculateVelocities();
publish_joint_states();
prevUpdateTime = world->GetSimTime();
}
if (enableMotors)
{
servo[FIRST].joint->SetVelocity(0, servo[FIRST].velocity);
if (countOfServos > 1) {
servo[SECOND].joint->SetVelocity(0, servo[SECOND].velocity);
if (countOfServos > 2) {
servo[THIRD].joint->SetVelocity(0, servo[THIRD].velocity);
}
}
servo[FIRST].joint->SetMaxForce(0, maximumTorque);
if (countOfServos > 1) {
servo[SECOND].joint->SetMaxForce(0, maximumTorque);
if (countOfServos > 2) {
servo[THIRD].joint->SetMaxForce(0, maximumTorque);
}
}
} else {
servo[FIRST].joint->SetMaxForce(0, 0.0);
if (countOfServos > 1) {
servo[SECOND].joint->SetMaxForce(0, 0.0);
if (countOfServos > 2) {
servo[THIRD].joint->SetMaxForce(0, 0.0);
}
}
}
}
void ServoPlugin::CalculateVelocities()
{
tf::StampedTransform transform;
boost::mutex::scoped_lock lock(mutex);
if(!current_cmd){
geometry_msgs::QuaternionStamped *default_cmd = new geometry_msgs::QuaternionStamped;
default_cmd->header.frame_id = "base_stabilized";
default_cmd->quaternion.w = 1;
current_cmd.reset(default_cmd);
}
try{
// ros::Time simTime(world->GetSimTime().sec, world->GetSimTime().nsec);
transform_listener_->lookupTransform("base_link", current_cmd->header.frame_id, ros::Time(0), transform);
}
catch (tf::TransformException ex){
ROS_DEBUG("%s",ex.what());
servo[FIRST].velocity = 0.0;
servo[SECOND].velocity = 0.0;
servo[THIRD].velocity = 0.0;
return;
}
rotation_.Set(current_cmd->quaternion.w, current_cmd->quaternion.x, current_cmd->quaternion.y, current_cmd->quaternion.z);
math::Quaternion quat(transform.getRotation().getW(),transform.getRotation().getX(),transform.getRotation().getY(),transform.getRotation().getZ());
rotation_ = quat * rotation_;
double temp[5];
double desAngle[3];
double actualAngle[3] = {0.0, 0.0, 0.0};
double actualVel[3] = {0.0, 0.0, 0.0};
//TODO use countOfServos for calculation
rotationConv = 99;
orderOfAxes[0] = 99;
orderOfAxes[1] = 99;
orderOfAxes[2] = 99;
switch(countOfServos) {
case 2:
if ((servo[FIRST].axis.z == 1) && (servo[SECOND].axis.y == 1)) {
rotationConv = zyx;
orderOfAxes[0] = 0;
orderOfAxes[1] = 1;
}
else {
if ((servo[FIRST].axis.x == 1) && (servo[SECOND].axis.y == 1)) {
rotationConv = xyz;
orderOfAxes[0] = 0;
orderOfAxes[1] = 1;
}
}
break;
case 3:
if ((servo[FIRST].axis.z == 1) && (servo[SECOND].axis.y == 1) && (servo[THIRD].axis.x == 1)) {
rotationConv = zyx;
orderOfAxes[0] = 0;
orderOfAxes[1] = 1;
orderOfAxes[2] = 2;
}
else if ((servo[FIRST].axis.x == 1) && (servo[SECOND].axis.y == 1) && (servo[THIRD].axis.z == 1)) {
rotationConv = xyz;
orderOfAxes[0] = 0;
orderOfAxes[1] = 1;
orderOfAxes[2] = 2;
}
break;
case 1:
if (servo[FIRST].axis.y == 1) {
rotationConv = xyz;
orderOfAxes[0] = 1;
}
break;
default:
gzthrow("Something went wrong. The count of servos is greater than 3");
break;
}
switch(rotationConv) {
case zyx:
temp[0] = 2*(rotation_.x*rotation_.y + rotation_.w*rotation_.z);
temp[1] = rotation_.w*rotation_.w + rotation_.x*rotation_.x - rotation_.y*rotation_.y - rotation_.z*rotation_.z;
temp[2] = -2*(rotation_.x*rotation_.z - rotation_.w*rotation_.y);
temp[3] = 2*(rotation_.y*rotation_.z + rotation_.w*rotation_.x);
temp[4] = rotation_.w*rotation_.w - rotation_.x*rotation_.x - rotation_.y*rotation_.y + rotation_.z*rotation_.z;
break;
case xyz:
temp[0] = -2*(rotation_.y*rotation_.z - rotation_.w*rotation_.x);
temp[1] = rotation_.w*rotation_.w - rotation_.x*rotation_.x - rotation_.y*rotation_.y + rotation_.z*rotation_.z;
temp[2] = 2*(rotation_.x*rotation_.z + rotation_.w*rotation_.y);
temp[3] = -2*(rotation_.x*rotation_.y - rotation_.w*rotation_.z);
temp[4] = rotation_.w*rotation_.w + rotation_.x*rotation_.x - rotation_.y*rotation_.y - rotation_.z*rotation_.z;
break;
default:
gzthrow("joint order " << rotationConv << " not supported");
break;
}
desAngle[0] = atan2(temp[0], temp[1]);
desAngle[1] = asin(temp[2]);
desAngle[2] = atan2(temp[3], temp[4]);
actualAngle[FIRST] = servo[FIRST].joint->GetAngle(0).RADIAN();
actualVel[FIRST] = servo[FIRST].joint->GetVelocity(0);
ROS_DEBUG_NAMED("servo_plugin", "%s servo angle: %f - %f", servo[FIRST].name.c_str(), desAngle[orderOfAxes[FIRST]], actualAngle[FIRST]);
servo[FIRST].velocity = ( proportionalControllerGain*(desAngle[orderOfAxes[FIRST]] - actualAngle[FIRST]) - derivativeControllerGain*actualVel[FIRST]);
if (maximumVelocity > 0.0 && fabs(servo[FIRST].velocity) > maximumVelocity) servo[FIRST].velocity = (servo[FIRST].velocity > 0 ? maximumVelocity : -maximumVelocity);
if (countOfServos > 1) {
actualAngle[SECOND] = servo[SECOND].joint->GetAngle(0).RADIAN();
actualVel[SECOND] = servo[SECOND].joint->GetVelocity(0);
ROS_DEBUG_NAMED("servo_plugin", "%s servo angle: %f - %f", servo[SECOND].name.c_str(), desAngle[orderOfAxes[SECOND]], actualAngle[SECOND]);
servo[SECOND].velocity = ( proportionalControllerGain*(desAngle[orderOfAxes[SECOND]] - actualAngle[SECOND]) - derivativeControllerGain*actualVel[SECOND]);
if (maximumVelocity > 0.0 && fabs(servo[SECOND].velocity) > maximumVelocity) servo[SECOND].velocity = (servo[SECOND].velocity > 0 ? maximumVelocity : -maximumVelocity);
if (countOfServos == 3) {
actualAngle[THIRD] = servo[THIRD].joint->GetAngle(0).RADIAN();
actualVel[THIRD] = servo[THIRD].joint->GetVelocity(0);
ROS_DEBUG_NAMED("servo_plugin", "%s servo angle: %f - %f", servo[THIRD].name.c_str(), desAngle[orderOfAxes[THIRD]], actualAngle[THIRD]);
servo[THIRD].velocity = ( proportionalControllerGain*(desAngle[orderOfAxes[THIRD]] - actualAngle[THIRD]) - derivativeControllerGain*actualVel[THIRD]);
if (maximumVelocity > 0.0 && fabs(servo[THIRD].velocity) > maximumVelocity) servo[THIRD].velocity = (servo[THIRD].velocity > 0 ? maximumVelocity : -maximumVelocity);
}
}
// Changed motors to be always on, which is probably what we want anyway
enableMotors = true; //myIface->data->cmdEnableMotors > 0;
}
// NEW: Store the velocities from the ROS message
void ServoPlugin::cmdCallback(const geometry_msgs::QuaternionStamped::ConstPtr& cmd_msg)
{
boost::mutex::scoped_lock lock(mutex);
current_cmd = cmd_msg;
}
void ServoPlugin::publish_joint_states()
{
if (!jointStatePub_) return;
joint_state.header.stamp.sec = (world->GetSimTime()).sec;
joint_state.header.stamp.nsec = (world->GetSimTime()).nsec;
joint_state.name.resize(countOfServos);
joint_state.position.resize(countOfServos);
joint_state.velocity.resize(countOfServos);
joint_state.effort.resize(countOfServos);
for (unsigned int i = 0; i < countOfServos; i++) {
joint_state.name[i] = servo[i].joint->GetName();
joint_state.position[i] = servo[i].joint->GetAngle(0).RADIAN();
joint_state.velocity[i] = servo[i].joint->GetVelocity(0);
joint_state.effort[i] = servo[i].joint->GetForce(0u);
}
jointStatePub_.publish(joint_state);
}
} // namespace gazebo

View file

@ -0,0 +1,2 @@
geometry_msgs/Vector3 bias
---

View file

@ -0,0 +1,31 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package hector_gazebo_thermal_camera
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
0.3.6 (2015-03-21)
------------------
0.3.5 (2015-02-23)
------------------
0.3.4 (2014-09-01)
------------------
0.3.3 (2014-05-27)
------------------
* Fix bad bug with index access
* Contributors: Stefan Kohlbrecher
0.3.2 (2014-03-30)
------------------
* added missing dependency to roscpp
* hector_gazebo: deleted deprecated export sections from package.xml files
* Contributors: Johannes Meyer
0.3.1 (2013-09-23)
------------------
* fixed image_connect_count_ compile issues with the latest gazebo_plugins version 2.3.2
0.3.0 (2013-09-02)
------------------
* Catkinization of stack hector_gazebo

View file

@ -0,0 +1,83 @@
cmake_minimum_required(VERSION 2.8.3)
project(hector_gazebo_thermal_camera)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS nodelet image_transport dynamic_reconfigure driver_base gazebo_plugins)
include_directories(include ${catkin_INCLUDE_DIRS})
## Find gazebo
find_package(gazebo REQUIRED)
include_directories(${GAZEBO_INCLUDE_DIRS})
link_directories(${GAZEBO_LIBRARY_DIRS})
## Find OGRE and OGRE-Paging (required for CameraPlugin.hh in Gazebo 5)
include (FindPkgConfig)
if (PKG_CONFIG_FOUND)
pkg_check_modules(OGRE OGRE)
pkg_check_modules(OGRE-Paging OGRE-Paging)
endif()
include_directories(${OGRE_INCLUDE_DIRS} ${OGRE-Paging_INCLUDE_DIRS})
link_directories(${OGRE_LIBRARY_DIRS} ${OGRE-Paging_LIBRARY_DIRS})
## Find Boost
find_package(Boost REQUIRED COMPONENTS thread)
include_directories(${Boost_INCLUDE_DIRS})
###################################
## dynamic_reconfigure ##
###################################
generate_dynamic_reconfigure_options(
cfg/GazeboRosThermalCamera.cfg
)
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
DEPENDS gazebo
CATKIN_DEPENDS nodelet image_transport dynamic_reconfigure driver_base gazebo_plugins
INCLUDE_DIRS include
LIBRARIES
)
###########
## Build ##
###########
add_library(gazebo_ros_thermal_camera src/gazebo_ros_thermal_camera_plugin.cpp)
target_link_libraries(gazebo_ros_thermal_camera ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES} CameraPlugin)
add_dependencies(gazebo_ros_thermal_camera ${PROJECT_NAME}_gencfg)
add_library(gazebo_ros_thermal_depth_camera src/gazebo_ros_thermal_depth_camera_plugin.cpp)
target_link_libraries(gazebo_ros_thermal_depth_camera ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES} DepthCameraPlugin)
add_dependencies(gazebo_ros_thermal_depth_camera ${PROJECT_NAME}_gencfg)
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h"
PATTERN ".svn" EXCLUDE
)
install(TARGETS
gazebo_ros_thermal_camera
gazebo_ros_thermal_depth_camera
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

View file

@ -0,0 +1,12 @@
#!/usr/bin/env python
PKG = 'hector_gazebo_thermal_camera'
from driver_base.msg import SensorLevels
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("imager_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, \
"Sets the frame rate of the imager. In externally triggered mode this must be more than trig_rate", 2, 1, 50)
exit(gen.generate(PKG, "gazebo_ros_thermal_camera", "GazeboRosThermalCamera"))

View file

@ -0,0 +1,93 @@
//=================================================================================================
// Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Simulation, Systems Optimization and Robotics
// group, TU Darmstadt nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
/**
* Copy of the DepthCameraSensor plugin with minor changes
*/
/*
* Gazebo - Outdoor Multi-Robot Simulator
* Copyright (C) 2003
* Nate Koenig & Andrew Howard
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/
#ifndef GAZEBO_ROS_THERMAL_CAMERA_HH
#define GAZEBO_ROS_THERMAL_CAMERA_HH
// camera stuff
#include <gazebo_plugins/gazebo_ros_camera_utils.h>
namespace gazebo
{
template <typename Base>
class GazeboRosThermalCamera_ : public Base, GazeboRosCameraUtils
{
/// \brief Constructor
/// \param parent The parent entity, must be a Model or a Sensor
public: GazeboRosThermalCamera_();
/// \brief Destructor
public: ~GazeboRosThermalCamera_();
/// \brief Load the plugin
/// \param take in SDF root element
public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
public: void LoadImpl(sensors::SensorPtr _parent, sdf::ElementPtr _sdf) {}
/// \brief Update the controller
protected: virtual void OnNewFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height,
unsigned int _depth, const std::string &_format);
/// \brief Update the controller
protected: virtual void OnNewImageFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height,
unsigned int _depth, const std::string &_format);
/// \brief Put camera data to the ROS topic
protected: void PutCameraData(const unsigned char *_src);
protected: void PutCameraData(const unsigned char *_src, common::Time &last_update_time);
};
}
#endif

View file

@ -0,0 +1,35 @@
<package>
<name>hector_gazebo_thermal_camera</name>
<version>0.3.6</version>
<description>hector_gazebo_thermal_camera provides a gazebo plugin that produces simulated thermal camera images. The plugin uses modified code from the gazebo_ros_camera plugin.</description>
<maintainer email="meyer@fsr.tu-darmstadt.de">Johannes Meyer</maintainer>
<license>BSD</license>
<url type="website">http://ros.org/wiki/hector_gazebo_thermal_camera</url>
<!-- <url type="bugtracker"></url> -->
<author email="kohlbrecher@sim.tu-darmstadt.de">Stefan Kohlbrecher</author>
<!-- Dependencies which this package needs to build itself. -->
<buildtool_depend>catkin</buildtool_depend>
<!-- Dependencies needed to compile this package. -->
<build_depend>roscpp</build_depend>
<build_depend>nodelet</build_depend>
<build_depend>gazebo</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>driver_base</build_depend>
<build_depend>gazebo_plugins</build_depend>
<!-- Dependencies needed after this package is compiled. -->
<run_depend>roscpp</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>driver_base</run_depend>
<run_depend>gazebo_plugins</run_depend>
</package>

View file

@ -0,0 +1,194 @@
//=================================================================================================
// Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Simulation, Systems Optimization and Robotics
// group, TU Darmstadt nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
/**
* Copy of the CameraSensor/DepthCameraSensor plugin with minor changes
*/
/*
* Gazebo - Outdoor Multi-Robot Simulator
* Copyright (C) 2003
* Nate Koenig & Andrew Howard
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/
#include <hector_gazebo_thermal_camera/gazebo_ros_thermal_camera.h>
#include <gazebo/sensors/Sensor.hh>
#include <gazebo/sensors/SensorTypes.hh>
#include <sensor_msgs/image_encodings.h>
namespace gazebo
{
////////////////////////////////////////////////////////////////////////////////
// Constructor
template <class Base>
GazeboRosThermalCamera_<Base>::GazeboRosThermalCamera_()
{
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
template <class Base>
GazeboRosThermalCamera_<Base>::~GazeboRosThermalCamera_()
{
}
template <class Base>
void GazeboRosThermalCamera_<Base>::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
{
Base::Load(_parent, _sdf);
// copying from CameraPlugin into GazeboRosCameraUtils
this->parentSensor_ = this->parentSensor;
this->width_ = this->width;
this->height_ = this->height;
this->depth_ = this->depth;
this->format_ = this->format;
this->image_connect_count_ = boost::shared_ptr<int>(new int);
*this->image_connect_count_ = 0;
this->image_connect_count_lock_ = boost::shared_ptr<boost::mutex>(new boost::mutex);
this->was_active_ = boost::shared_ptr<bool>(new bool);
*this->was_active_ = false;
LoadImpl(_parent, _sdf);
GazeboRosCameraUtils::Load(_parent, _sdf);
}
////////////////////////////////////////////////////////////////////////////////
// Update the controller
template <class Base>
void GazeboRosThermalCamera_<Base>::OnNewFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format)
{
if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
return;
this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
if (!this->parentSensor->IsActive())
{
if ((*this->image_connect_count_) > 0)
// do this first so there's chance for sensor to run 1 frame after activate
this->parentSensor->SetActive(true);
}
else
{
if ((*this->image_connect_count_) > 0)
{
common::Time cur_time = this->world_->GetSimTime();
if (cur_time - this->last_update_time_ >= this->update_period_)
{
this->PutCameraData(_image);
this->PublishCameraInfo();
this->last_update_time_ = cur_time;
}
}
}
}
template <class Base>
void GazeboRosThermalCamera_<Base>::OnNewImageFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format)
{
OnNewFrame(_image, _width, _height, _depth, _format);
}
////////////////////////////////////////////////////////////////////////////////
// Put camera_ data to the interface
template <class Base>
void GazeboRosThermalCamera_<Base>::PutCameraData(const unsigned char *_src, common::Time &last_update_time)
{
this->sensor_update_time_ = last_update_time;
this->PutCameraData(_src);
}
template <class Base>
void GazeboRosThermalCamera_<Base>::PutCameraData(const unsigned char *_src)
{
if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
return;
this->lock_.lock();
// copy data into image
this->image_msg_.header.frame_id = this->frame_name_;
this->image_msg_.header.stamp.sec = this->sensor_update_time_.sec;
this->image_msg_.header.stamp.nsec = this->sensor_update_time_.nsec;
/// don't bother if there are no subscribers
if ((*this->image_connect_count_) > 0)
{
this->image_msg_.width = this->width_;
this->image_msg_.height = this->height_;
this->image_msg_.encoding = sensor_msgs::image_encodings::MONO8;
this->image_msg_.step = this->image_msg_.width;
size_t size = this->width_ * this->height_;
std::vector<uint8_t>& data (this->image_msg_.data);
data.resize(size);
size_t img_index = 0;
for (size_t i = 0; i < size; ++i){
if ((_src[img_index] >254) && (_src[img_index+1] < 1) && (_src[img_index+2] < 1)){
//RGB [255,0,0] translates to white (white hot)
data[i]= 255;
}else{
//Everything else is written to the MONO8 output image much darker
data[i]= (_src[img_index] + _src[img_index+1] + _src[img_index+2]) /8 ;
}
img_index += 3;
}
// publish to ros
this->image_pub_.publish(this->image_msg_);
}
this->lock_.unlock();
}
}

View file

@ -0,0 +1,49 @@
//=================================================================================================
// Copyright (c) 2013, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include "gazebo_ros_thermal_camera.cpp"
// gazebo stuff
#include <gazebo/plugins/CameraPlugin.hh>
namespace gazebo
{
template <>
void GazeboRosThermalCamera_<CameraPlugin>::LoadImpl(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
{
this->camera_ = this->CameraPlugin::camera;
}
template class GazeboRosThermalCamera_<CameraPlugin>;
typedef GazeboRosThermalCamera_<CameraPlugin> GazeboRosThermalCamera;
// Register this plugin with the simulator
GZ_REGISTER_SENSOR_PLUGIN(GazeboRosThermalCamera)
}

View file

@ -0,0 +1,49 @@
//=================================================================================================
// Copyright (c) 2013, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//=================================================================================================
#include "gazebo_ros_thermal_camera.cpp"
// gazebo stuff
#include <gazebo/plugins/DepthCameraPlugin.hh>
namespace gazebo
{
template <>
void GazeboRosThermalCamera_<DepthCameraPlugin>::LoadImpl(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
{
this->camera_ = this->DepthCameraPlugin::depthCamera;
}
template class GazeboRosThermalCamera_<DepthCameraPlugin>;
typedef GazeboRosThermalCamera_<DepthCameraPlugin> GazeboRosThermalCamera;
// Register this plugin with the simulator
GZ_REGISTER_SENSOR_PLUGIN(GazeboRosThermalCamera)
}

View file

@ -0,0 +1,50 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package hector_gazebo_worlds
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
0.3.6 (2015-03-21)
------------------
0.3.5 (2015-02-23)
------------------
* Change drc qual 4 settings to be same as current Atlas default
* Add drc final qual step block world and launch file
* - Adjusted lighting
* - Update world
* -Add inner block with stations model
* -Add complete sick robot day 2014 outer ring with stations
* -Add two target panel examples to world
* -Update world file
* -Add complete sick robot day 2014 target stations
* -Add inner block to world
* -Add inner block for sick robot day 2014
* -Add target model to sick robot day 2014 world
* -Add sick robot day target model
* Contributors: Stefan Kohlbrecher
0.3.4 (2014-09-01)
------------------
* updated world files to SDF 1.4 using gzsdf
* Change light for sick robot day 2014 world, add number panel example
* Add sick robot number panel stl file for collision geom
* Add collada files for sick robot day number panels
* Add sick robot day number panels
* Add sick robot day 2014 related files
* Add model for sick robot day 2014 ring
* added args roslaunch argument to pass additional command line arguments to gzserver
* Contributors: Johannes Meyer, Stefan Kohlbrecher
0.3.3 (2014-05-27)
------------------
0.3.2 (2014-03-30)
------------------
* added missing install rule
* Contributors: Johannes Meyer
0.3.1 (2013-09-23)
------------------
0.3.0 (2013-09-02)
------------------
* Catkinization of stack hector_gazebo

View file

@ -0,0 +1,39 @@
cmake_minimum_required(VERSION 2.8.3)
project(hector_gazebo_worlds)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED)
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
DEPENDS
CATKIN_DEPENDS
INCLUDE_DIRS
LIBRARIES
)
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
# Mark other files for installation (e.g. launch and bag files, etc.)
install(DIRECTORY
launch
maps
Media
worlds
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

View file

@ -0,0 +1,177 @@
material Hector/Gouraud
{
receive_shadows on
shading gouraud
technique
{
pass Ambient
{
ambient 1.000000 1.000000 1.000000 1.000000
diffuse 1.0 1.0 1.0 1.0
specular 0.8 0.8 0.8 1 20
shading gouraud
}
pass PointLight
{
ambient 1.000000 1.000000 1.000000 1.000000
diffuse 1.0 1.0 1.0 1.0
specular 0.8 0.8 0.8 1 20
shading gouraud
}
}
}
material Hector/Black
{
receive_shadows on
lighting on
technique
{
pass
{
ambient 0.1 0.1 0.1 1.0
diffuse 0.1 0.1 0.1 1.0
specular 0.0 0.0 0.0 0.0
}
}
}
material Hector/Blue
{
receive_shadows on
technique
{
pass
{
ambient 0.0 0.0 0.2 1.0
diffuse 0.0 0.0 0.8 1.0
specular 0.0 0.0 0.2 1.0
emissive 0.0 0.0 0.0 1.0
shading gouraud
}
}
}
material Hector/Green
{
receive_shadows on
technique
{
pass
{
ambient 0.0 0.2 0.0 1.0
diffuse 0.0 0.8 0.0 1.0
specular 0.0 0.2 0.0 1.0
emissive 0.0 0.0 0.0 0.0
lighting on
shading phong
}
}
}
material Hector/Grey
{
receive_shadows on
lighting on
technique
{
pass
{
ambient 0.1 0.1 0.1 1.0
diffuse 0.7 0.7 0.7 1.0
specular 0.8 0.8 0.8 1
}
}
}
material Hector/Grey2
{
receive_shadows on
lighting on
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 0.9 0.9 0.9 1.0
specular 0.8 0.8 0.8 1
lighting on
}
}
}
material Hector/Red
{
receive_shadows on
technique
{
pass
{
ambient 0.2 0.0 0.0 1.0
diffuse 0.8 0.0 0.0 1.0
specular 0.2 0.0 0.0 1.0
emissive 0.0 0.0 0.0 1.0
lighting on
shading phong
}
}
}
material Hector/White
{
receive_shadows on
lighting on
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 1.0 1.0 1.0 1.0
specular 1.0 1.0 1.0 1.0
shading gouraud
}
}
}
material Hector/Yellow
{
receive_shadows on
technique
{
pass
{
ambient 0.2 0.2 0.0 1.0
diffuse 0.8 0.8 0.0 1.0
specular 0.2 0.2 0.0 1.0
emissive 0.0 0.0 0.0 1.0
lighting on
}
}
}
material Hector/BlueBrushedAluminum
{
technique
{
pass
{
ambient 0.75 0.75 0.75
cull_hardware none
cull_software none
texture_unit
{
texture blue_brushed_aluminum.jpg
}
}
}
}

View file

@ -0,0 +1,229 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-05T19:46:50</created>
<modified>2014-09-05T19:46:50</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_cameras>
<camera id="Camera-camera" name="Camera">
<optics>
<technique_common>
<perspective>
<xfov sid="xfov">49.13434</xfov>
<aspect_ratio>1.777778</aspect_ratio>
<znear sid="znear">0.1</znear>
<zfar sid="zfar">100</zfar>
</perspective>
</technique_common>
</optics>
<extra>
<technique profile="blender">
<YF_dofdist>0</YF_dofdist>
<shiftx>0</shiftx>
<shifty>0</shifty>
</technique>
</extra>
</camera>
</library_cameras>
<library_lights>
<light id="Lamp-light" name="Lamp">
<technique_common>
<point>
<color sid="color">1 1 1</color>
<constant_attenuation>1</constant_attenuation>
<linear_attenuation>0</linear_attenuation>
<quadratic_attenuation>0.00111109</quadratic_attenuation>
</point>
</technique_common>
<extra>
<technique profile="blender">
<adapt_thresh>0.000999987</adapt_thresh>
<area_shape>1</area_shape>
<area_size>0.1</area_size>
<area_sizey>0.1</area_sizey>
<area_sizez>1</area_sizez>
<atm_distance_factor>1</atm_distance_factor>
<atm_extinction_factor>1</atm_extinction_factor>
<atm_turbidity>2</atm_turbidity>
<att1>0</att1>
<att2>1</att2>
<backscattered_light>1</backscattered_light>
<bias>1</bias>
<blue>1</blue>
<buffers>1</buffers>
<bufflag>0</bufflag>
<bufsize>2880</bufsize>
<buftype>2</buftype>
<clipend>30.002</clipend>
<clipsta>1.000799</clipsta>
<compressthresh>0.04999995</compressthresh>
<dist sid="blender_dist">29.99998</dist>
<energy sid="blender_energy">1</energy>
<falloff_type>2</falloff_type>
<filtertype>0</filtertype>
<flag>0</flag>
<gamma sid="blender_gamma">1</gamma>
<green>1</green>
<halo_intensity sid="blnder_halo_intensity">1</halo_intensity>
<horizon_brightness>1</horizon_brightness>
<mode>8192</mode>
<ray_samp>1</ray_samp>
<ray_samp_method>1</ray_samp_method>
<ray_samp_type>0</ray_samp_type>
<ray_sampy>1</ray_sampy>
<ray_sampz>1</ray_sampz>
<red>1</red>
<samp>3</samp>
<shadhalostep>0</shadhalostep>
<shadow_b sid="blender_shadow_b">0</shadow_b>
<shadow_g sid="blender_shadow_g">0</shadow_g>
<shadow_r sid="blender_shadow_r">0</shadow_r>
<sky_colorspace>0</sky_colorspace>
<sky_exposure>1</sky_exposure>
<skyblendfac>1</skyblendfac>
<skyblendtype>1</skyblendtype>
<soft>3</soft>
<spotblend>0.15</spotblend>
<spotsize>75</spotsize>
<spread>1</spread>
<sun_brightness>1</sun_brightness>
<sun_effect_type>0</sun_effect_type>
<sun_intensity>1</sun_intensity>
<sun_size>1</sun_size>
<type>0</type>
</technique>
</extra>
</light>
</library_lights>
<library_images/>
<library_effects>
<effect id="Orange-material-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0.11 0.11 0.11 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.5629584 0.08859625 0.01129085 1</color>
</diffuse>
<specular>
<color sid="specular">0.25 0.25 0.25 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Perch_Blue-material-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.03636133 0.512 1</color>
</diffuse>
<specular>
<color sid="specular">0.25 0.25 0.25 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Orange-material-material" name="Orange-material">
<instance_effect url="#Orange-material-effect"/>
</material>
<material id="Perch_Blue-material-material" name="Perch_Blue-material">
<instance_effect url="#Perch_Blue-material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="BoundaryBank_002-mesh" name="BoundaryBank.002">
<mesh>
<source id="BoundaryBank_002-mesh-positions">
<float_array id="BoundaryBank_002-mesh-positions-array" count="144">112.2869 1.690699 0 177.7534 -1.126392 0 175.7931 -1.130356 0 110.3266 1.686735 0 112.2869 1.690699 0.5 177.7534 -1.126392 0.5 175.793 -1.130356 0.5 110.3266 1.686735 0.5 -172.9723 1.043429 0 108.3853 1.71305 0 108.7922 1.693469 0 -172.5655 1.023848 0 -172.9723 1.043429 0.5 108.3854 1.71305 0.5 108.7921 1.693468 0.5 -172.5655 1.023848 0.5 112.2869 1.690699 0 177.7534 -1.126392 0 175.7931 -1.130356 0 110.3266 1.686735 0 112.2869 1.690699 0.5 177.7534 -1.126392 0.5 175.793 -1.130356 0.5 110.3266 1.686735 0.5 112.2869 1.690699 0 177.7534 -1.126392 0 175.7931 -1.130356 0 110.3266 1.686735 0 112.2869 1.690699 0.5 177.7534 -1.126392 0.5 175.793 -1.130356 0.5 110.3266 1.686735 0.5 -171.582 1.010482 0 -106.1155 -1.806609 0 -108.0757 -1.810573 0 -173.5423 1.006518 0 -171.582 1.010482 0.5 -106.1155 -1.806609 0.5 -108.0759 -1.810573 0.5 -173.5423 1.006518 0.5 -104.8782 -1.815099 0 176.4794 -1.145478 0 176.8863 -1.165059 0 -104.4714 -1.83468 0 -104.8782 -1.815099 0.5 176.4795 -1.145478 0.5 176.8862 -1.16506 0.5 -104.4714 -1.83468 0.5</float_array>
<technique_common>
<accessor source="#BoundaryBank_002-mesh-positions-array" count="48" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="BoundaryBank_002-mesh-normals">
<float_array id="BoundaryBank_002-mesh-normals-array" count="216">0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 -0.002379953 0.9999972 0 0.04808807 0.9988431 -5.87013e-6 0.002379894 -0.9999972 -2.33208e-6 -0.04808509 -0.9988432 0 0 0 -1 0 0 1 -0.002379953 0.9999971 3.25395e-7 0.04807043 0.9988439 8.48712e-6 0.002379953 -0.9999972 0 -0.04808509 -0.9988432 0 0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 -0.002379953 0.9999972 0 0.04808807 0.9988431 -5.87013e-6 0.002379894 -0.9999972 -2.33208e-6 -0.04808485 -0.9988432 0 0 0 -1 0 0 1 -0.002379953 0.9999971 3.25395e-7 0.04807043 0.9988439 8.48712e-6 0.002379953 -0.9999972 0 -0.04808485 -0.9988432 0</float_array>
<technique_common>
<accessor source="#BoundaryBank_002-mesh-normals-array" count="72" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="BoundaryBank_002-mesh-vertices">
<input semantic="POSITION" source="#BoundaryBank_002-mesh-positions"/>
</vertices>
<polylist material="Orange-material-material" count="72">
<input semantic="VERTEX" source="#BoundaryBank_002-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#BoundaryBank_002-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 1 0 2 0 4 1 7 1 6 1 0 2 4 2 5 2 1 3 5 3 6 3 2 4 6 4 7 4 4 5 0 5 3 5 3 6 0 6 2 6 5 7 4 7 6 7 1 8 0 8 5 8 2 9 1 9 6 9 3 10 2 10 7 10 7 11 4 11 3 11 8 12 9 12 10 12 12 13 15 13 14 13 8 14 12 14 13 14 9 15 13 15 14 15 10 16 14 16 15 16 12 17 8 17 11 17 11 18 8 18 10 18 13 19 12 19 14 19 9 20 8 20 13 20 10 21 9 21 14 21 11 22 10 22 15 22 15 23 12 23 11 23 16 24 17 24 18 24 20 25 23 25 22 25 16 26 20 26 21 26 17 27 21 27 22 27 18 28 22 28 23 28 20 29 16 29 19 29 19 30 16 30 18 30 21 31 20 31 22 31 17 32 16 32 21 32 18 33 17 33 22 33 19 34 18 34 23 34 23 35 20 35 19 35 24 36 25 36 26 36 28 37 31 37 30 37 24 38 28 38 29 38 25 39 29 39 30 39 26 40 30 40 31 40 28 41 24 41 27 41 27 42 24 42 26 42 29 43 28 43 30 43 25 44 24 44 29 44 26 45 25 45 30 45 27 46 26 46 31 46 31 47 28 47 27 47 32 48 33 48 34 48 36 49 39 49 38 49 32 50 36 50 37 50 33 51 37 51 38 51 34 52 38 52 39 52 36 53 32 53 35 53 35 54 32 54 34 54 37 55 36 55 38 55 33 56 32 56 37 56 34 57 33 57 38 57 35 58 34 58 39 58 39 59 36 59 35 59 40 60 41 60 42 60 44 61 47 61 46 61 40 62 44 62 45 62 41 63 45 63 46 63 42 64 46 64 47 64 44 65 40 65 43 65 43 66 40 66 42 66 45 67 44 67 46 67 41 68 40 68 45 68 42 69 41 69 46 69 43 70 42 70 47 70 47 71 44 71 43 71</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Camera" name="Camera" type="NODE">
<matrix sid="transform">1.114218 -0.3567156 0.9827452 16.73198 1.182047 0.3512065 -0.9164203 -11.37074 -0.01757195 1.006342 0.6681756 5.343665 0 0 0 1</matrix>
<instance_camera url="#Camera-camera"/>
</node>
<node id="Lamp" name="Lamp" type="NODE">
<matrix sid="transform">-0.4474778 -1.043213 0.6901001 11.62465 1.469473 -0.2704199 0.2660904 -0.1011007 -0.08490505 0.8178545 0.9682381 5.903862 0 0 0 1</matrix>
<instance_light url="#Lamp-light"/>
</node>
<node id="BoundaryBank_002" name="BoundaryBank_002" type="NODE">
<matrix sid="transform">0.00782801 0.1835659 0 4.76837e-7 -0.001835657 0.7828018 0 -2.38419e-7 0 0 1 -2.22045e-16 0 0 0 1</matrix>
<instance_geometry url="#BoundaryBank_002-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Orange-material-material" target="#Orange-material-material"/>
<instance_material symbol="Perch_Blue-material-material" target="#Perch_Blue-material-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,927 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-07T22:58:23</created>
<modified>2014-09-07T22:58:23</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_cameras>
<camera id="Camera-camera" name="Camera">
<optics>
<technique_common>
<perspective>
<xfov sid="xfov">49.13434</xfov>
<aspect_ratio>1.777778</aspect_ratio>
<znear sid="znear">0.1</znear>
<zfar sid="zfar">100</zfar>
</perspective>
</technique_common>
</optics>
<extra>
<technique profile="blender">
<YF_dofdist>0</YF_dofdist>
<shiftx>0</shiftx>
<shifty>0</shifty>
</technique>
</extra>
</camera>
</library_cameras>
<library_lights>
<light id="Lamp-light" name="Lamp">
<technique_common>
<point>
<color sid="color">1 1 1</color>
<constant_attenuation>1</constant_attenuation>
<linear_attenuation>0</linear_attenuation>
<quadratic_attenuation>0.00111109</quadratic_attenuation>
</point>
</technique_common>
<extra>
<technique profile="blender">
<adapt_thresh>0.000999987</adapt_thresh>
<area_shape>1</area_shape>
<area_size>0.1</area_size>
<area_sizey>0.1</area_sizey>
<area_sizez>1</area_sizez>
<atm_distance_factor>1</atm_distance_factor>
<atm_extinction_factor>1</atm_extinction_factor>
<atm_turbidity>2</atm_turbidity>
<att1>0</att1>
<att2>1</att2>
<backscattered_light>1</backscattered_light>
<bias>1</bias>
<blue>1</blue>
<buffers>1</buffers>
<bufflag>0</bufflag>
<bufsize>2880</bufsize>
<buftype>2</buftype>
<clipend>30.002</clipend>
<clipsta>1.000799</clipsta>
<compressthresh>0.04999995</compressthresh>
<dist sid="blender_dist">29.99998</dist>
<energy sid="blender_energy">1</energy>
<falloff_type>2</falloff_type>
<filtertype>0</filtertype>
<flag>0</flag>
<gamma sid="blender_gamma">1</gamma>
<green>1</green>
<halo_intensity sid="blnder_halo_intensity">1</halo_intensity>
<horizon_brightness>1</horizon_brightness>
<mode>8192</mode>
<ray_samp>1</ray_samp>
<ray_samp_method>1</ray_samp_method>
<ray_samp_type>0</ray_samp_type>
<ray_sampy>1</ray_sampy>
<ray_sampz>1</ray_sampz>
<red>1</red>
<samp>3</samp>
<shadhalostep>0</shadhalostep>
<shadow_b sid="blender_shadow_b">0</shadow_b>
<shadow_g sid="blender_shadow_g">0</shadow_g>
<shadow_r sid="blender_shadow_r">0</shadow_r>
<sky_colorspace>0</sky_colorspace>
<sky_exposure>1</sky_exposure>
<skyblendfac>1</skyblendfac>
<skyblendtype>1</skyblendtype>
<soft>3</soft>
<spotblend>0.15</spotblend>
<spotsize>75</spotsize>
<spread>1</spread>
<sun_brightness>1</sun_brightness>
<sun_effect_type>0</sun_effect_type>
<sun_intensity>1</sun_intensity>
<sun_size>1</sun_size>
<type>0</type>
</technique>
</extra>
</light>
</library_lights>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_002-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.1541236 0.005637094 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Orange-material-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.5629584 0.08859625 0.01129085 1</color>
</diffuse>
<specular>
<color sid="specular">0.25 0.25 0.25 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Perch_Blue-material-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.03636133 0.512 1</color>
</diffuse>
<specular>
<color sid="specular">0.25 0.25 0.25 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_002-material" name="Material_002">
<instance_effect url="#Material_002-effect"/>
</material>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Orange-material-material" name="Orange-material">
<instance_effect url="#Orange-material-effect"/>
</material>
<material id="Perch_Blue-material-material" name="Perch_Blue-material">
<instance_effect url="#Perch_Blue-material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_002-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="BoundaryBank_002-mesh" name="BoundaryBank_002">
<mesh>
<source id="BoundaryBank_002-mesh-positions">
<float_array id="BoundaryBank_002-mesh-positions-array" count="144">112.2869 1.690699 0 177.7534 -1.126392 0 175.7931 -1.130356 0 110.3266 1.686735 0 112.2869 1.690699 0.5 177.7534 -1.126392 0.5 175.793 -1.130356 0.5 110.3266 1.686735 0.5 -172.9723 1.043429 0 108.3853 1.71305 0 108.7922 1.693469 0 -172.5655 1.023848 0 -172.9723 1.043429 0.5 108.3854 1.71305 0.5 108.7921 1.693468 0.5 -172.5655 1.023848 0.5 112.2869 1.690699 0 177.7534 -1.126392 0 175.7931 -1.130356 0 110.3266 1.686735 0 112.2869 1.690699 0.5 177.7534 -1.126392 0.5 175.793 -1.130356 0.5 110.3266 1.686735 0.5 112.2869 1.690699 0 177.7534 -1.126392 0 175.7931 -1.130356 0 110.3266 1.686735 0 112.2869 1.690699 0.5 177.7534 -1.126392 0.5 175.793 -1.130356 0.5 110.3266 1.686735 0.5 -171.582 1.010482 0 -106.1155 -1.806609 0 -108.0757 -1.810573 0 -173.5423 1.006518 0 -171.582 1.010482 0.5 -106.1155 -1.806609 0.5 -108.0759 -1.810573 0.5 -173.5423 1.006518 0.5 -104.8782 -1.815099 0 176.4794 -1.145478 0 176.8863 -1.165059 0 -104.4714 -1.83468 0 -104.8782 -1.815099 0.5 176.4795 -1.145478 0.5 176.8862 -1.16506 0.5 -104.4714 -1.83468 0.5</float_array>
<technique_common>
<accessor source="#BoundaryBank_002-mesh-positions-array" count="48" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="BoundaryBank_002-mesh-normals">
<float_array id="BoundaryBank_002-mesh-normals-array" count="216">0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 -0.002379953 0.9999972 0 0.04808807 0.9988431 -5.87013e-6 0.002379894 -0.9999972 -2.33208e-6 -0.04808509 -0.9988432 0 0 0 -1 0 0 1 -0.002379953 0.9999971 3.25395e-7 0.04807043 0.9988439 8.48712e-6 0.002379953 -0.9999972 0 -0.04808509 -0.9988432 0 0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 0 0.002021908 -0.999998 -9.53672e-7 -0.04299128 -0.9990754 -1.00195e-5 -0.002021968 0.9999979 0 0 0 -1 0 0 1 0.04299122 0.9990754 9.31449e-7 0.002022445 -0.999998 9.70658e-7 -0.04299122 -0.9990754 0 -0.002021968 0.9999979 0 0 0 -1 0 0 1 -0.002379953 0.9999972 0 0.04808807 0.9988431 -5.87013e-6 0.002379894 -0.9999972 -2.33208e-6 -0.04808485 -0.9988432 0 0 0 -1 0 0 1 -0.002379953 0.9999971 3.25395e-7 0.04807043 0.9988439 8.48712e-6 0.002379953 -0.9999972 0 -0.04808485 -0.9988432 0</float_array>
<technique_common>
<accessor source="#BoundaryBank_002-mesh-normals-array" count="72" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="BoundaryBank_002-mesh-vertices">
<input semantic="POSITION" source="#BoundaryBank_002-mesh-positions"/>
</vertices>
<polylist material="Orange-material-material" count="72">
<input semantic="VERTEX" source="#BoundaryBank_002-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#BoundaryBank_002-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 1 0 2 0 4 1 7 1 6 1 0 2 4 2 5 2 1 3 5 3 6 3 2 4 6 4 7 4 4 5 0 5 3 5 3 6 0 6 2 6 5 7 4 7 6 7 1 8 0 8 5 8 2 9 1 9 6 9 3 10 2 10 7 10 7 11 4 11 3 11 8 12 9 12 10 12 12 13 15 13 14 13 8 14 12 14 13 14 9 15 13 15 14 15 10 16 14 16 15 16 12 17 8 17 11 17 11 18 8 18 10 18 13 19 12 19 14 19 9 20 8 20 13 20 10 21 9 21 14 21 11 22 10 22 15 22 15 23 12 23 11 23 16 24 17 24 18 24 20 25 23 25 22 25 16 26 20 26 21 26 17 27 21 27 22 27 18 28 22 28 23 28 20 29 16 29 19 29 19 30 16 30 18 30 21 31 20 31 22 31 17 32 16 32 21 32 18 33 17 33 22 33 19 34 18 34 23 34 23 35 20 35 19 35 24 36 25 36 26 36 28 37 31 37 30 37 24 38 28 38 29 38 25 39 29 39 30 39 26 40 30 40 31 40 28 41 24 41 27 41 27 42 24 42 26 42 29 43 28 43 30 43 25 44 24 44 29 44 26 45 25 45 30 45 27 46 26 46 31 46 31 47 28 47 27 47 32 48 33 48 34 48 36 49 39 49 38 49 32 50 36 50 37 50 33 51 37 51 38 51 34 52 38 52 39 52 36 53 32 53 35 53 35 54 32 54 34 54 37 55 36 55 38 55 33 56 32 56 37 56 34 57 33 57 38 57 35 58 34 58 39 58 39 59 36 59 35 59 40 60 41 60 42 60 44 61 47 61 46 61 40 62 44 62 45 62 41 63 45 63 46 63 42 64 46 64 47 64 44 65 40 65 43 65 43 66 40 66 42 66 45 67 44 67 46 67 41 68 40 68 45 68 42 69 41 69 46 69 43 70 42 70 47 70 47 71 44 71 43 71</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_000-mesh" name="Cube.000">
<mesh>
<source id="Cube_000-mesh-positions">
<float_array id="Cube_000-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_000-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_000-mesh-normals">
<float_array id="Cube_000-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_000-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_000-mesh-map-0">
<float_array id="Cube_000-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_000-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_000-mesh-vertices">
<input semantic="POSITION" source="#Cube_000-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_000-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_000-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_000-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_002-mesh" name="Cube.002">
<mesh>
<source id="Cube_002-mesh-positions">
<float_array id="Cube_002-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_002-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_002-mesh-normals">
<float_array id="Cube_002-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_002-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_002-mesh-vertices">
<input semantic="POSITION" source="#Cube_002-mesh-positions"/>
</vertices>
<polylist material="Material_002-material" count="12">
<input semantic="VERTEX" source="#Cube_002-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_002-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder_001-mesh" name="Cylinder.001">
<mesh>
<source id="Cylinder_001-mesh-positions">
<float_array id="Cylinder_001-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder_001-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder_001-mesh-normals">
<float_array id="Cylinder_001-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder_001-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder_001-mesh-vertices">
<input semantic="POSITION" source="#Cylinder_001-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder_001-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder_002-mesh" name="Cylinder.002">
<mesh>
<source id="Cylinder_002-mesh-positions">
<float_array id="Cylinder_002-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder_002-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder_002-mesh-normals">
<float_array id="Cylinder_002-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder_002-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder_002-mesh-vertices">
<input semantic="POSITION" source="#Cylinder_002-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder_002-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder_002-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_002-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_005-mesh" name="Cube.005">
<mesh>
<source id="Cube_005-mesh-positions">
<float_array id="Cube_005-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_005-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_005-mesh-normals">
<float_array id="Cube_005-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_005-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_005-mesh-map-0">
<float_array id="Cube_005-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_005-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_005-mesh-vertices">
<input semantic="POSITION" source="#Cube_005-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_005-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_005-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_005-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_006-mesh" name="Cube.006">
<mesh>
<source id="Cube_006-mesh-positions">
<float_array id="Cube_006-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_006-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_006-mesh-normals">
<float_array id="Cube_006-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_006-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_006-mesh-map-0">
<float_array id="Cube_006-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_006-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_006-mesh-vertices">
<input semantic="POSITION" source="#Cube_006-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_006-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_006-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_006-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_007-mesh" name="Cube.007">
<mesh>
<source id="Cube_007-mesh-positions">
<float_array id="Cube_007-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_007-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_007-mesh-normals">
<float_array id="Cube_007-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_007-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_007-mesh-vertices">
<input semantic="POSITION" source="#Cube_007-mesh-positions"/>
</vertices>
<polylist material="Material_002-material" count="12">
<input semantic="VERTEX" source="#Cube_007-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_007-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder_003-mesh" name="Cylinder.003">
<mesh>
<source id="Cylinder_003-mesh-positions">
<float_array id="Cylinder_003-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder_003-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder_003-mesh-normals">
<float_array id="Cylinder_003-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder_003-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder_003-mesh-vertices">
<input semantic="POSITION" source="#Cylinder_003-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 1.190006 0 1 0 -0.005151541 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 1.332152 0 0.1651367 0 -0.005151541 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
<instance_material symbol="Material_002-material" target="#Material_002-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 1.190006 0 0.65306 0 -0.005151541 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Camera" name="Camera" type="NODE">
<matrix sid="transform">1.114218 -0.3567156 0.9827452 16.73198 1.182047 0.3512065 -0.9164203 -11.37074 -0.01757195 1.006342 0.6681756 5.343665 0 0 0 1</matrix>
<instance_camera url="#Camera-camera"/>
</node>
<node id="Lamp" name="Lamp" type="NODE">
<matrix sid="transform">-0.4474778 -1.043213 0.6901001 11.62465 1.469473 -0.2704199 0.2660904 -0.1011007 -0.08490505 0.8178545 0.9682381 5.903862 0 0 0 1</matrix>
<instance_light url="#Lamp-light"/>
</node>
<node id="BoundaryBank_002" name="BoundaryBank_002" type="NODE">
<matrix sid="transform">0.00782801 0.1835659 0 4.76837e-7 -0.001835657 0.7828018 0 -2.38419e-7 0 0 1 -2.22045e-16 0 0 0 1</matrix>
<instance_geometry url="#BoundaryBank_002-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Orange-material-material" target="#Orange-material-material"/>
<instance_material symbol="Perch_Blue-material-material" target="#Perch_Blue-material-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_000" name="Cube_000" type="NODE">
<matrix sid="transform">2.02191e-4 0.6530266 0 0.004444272 -0.01999896 0.006602154 0 -1.244147 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_000-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_002" name="Cube_002" type="NODE">
<matrix sid="transform">0.00166946 0.1651283 0 0.005881312 -0.1651283 0.00166946 0 -1.386286 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_002-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
<instance_material symbol="Material_002-material" target="#Material_002-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder_001" name="Cylinder_001" type="NODE">
<matrix sid="transform">0.01010957 0.9999489 0 0.004444272 -0.9999489 0.01010957 0 -1.244147 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder_002" name="Cylinder_002" type="NODE">
<matrix sid="transform">-1 2.14251e-4 0 -1.177411 -2.14251e-4 -1 0 -0.001716829 0 0 1 -3.05896e-9 0 0 0 1</matrix>
<instance_geometry url="#Cylinder_002-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">-0.1651367 3.53807e-5 0 -1.319556 -3.53807e-5 -0.1651367 0 -0.001747334 0 0 0.1651367 -3.05896e-9 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
<instance_material symbol="Material_002-material" target="#Material_002-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_005" name="Cube_005" type="NODE">
<matrix sid="transform">-0.01999998 1.39919e-4 0 -1.177411 -4.28501e-6 -0.65306 0 -0.001716829 0 0 1 -3.05896e-9 0 0 0 1</matrix>
<instance_geometry url="#Cube_005-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_006" name="Cube_006" type="NODE">
<matrix sid="transform">-4.84177e-5 -0.6530581 0 0.008723531 0.01999992 -0.001580985 0 1.14007 0 0 1 -4.1544e-8 0 0 0 1</matrix>
<instance_geometry url="#Cube_006-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_007" name="Cube_007" type="NODE">
<matrix sid="transform">-3.99777e-4 -0.1651362 0 0.008379273 0.1651362 -3.99777e-4 0 1.282215 0 0 0.1651367 -4.1544e-8 0 0 0 1</matrix>
<instance_geometry url="#Cube_007-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
<instance_material symbol="Material_002-material" target="#Material_002-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder_003" name="Cylinder_003" type="NODE">
<matrix sid="transform">-0.002420888 -0.9999971 0 0.008723531 0.9999971 -0.002420888 0 1.14007 0 0 1 -4.1544e-8 0 0 0 1</matrix>
<instance_geometry url="#Cylinder_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,199 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-29T17:29:15</created>
<modified>2014-08-29T17:29:15</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_cameras>
<camera id="Camera-camera" name="Camera">
<optics>
<technique_common>
<perspective>
<xfov sid="xfov">49.13434</xfov>
<aspect_ratio>1.777778</aspect_ratio>
<znear sid="znear">0.1</znear>
<zfar sid="zfar">100</zfar>
</perspective>
</technique_common>
</optics>
<extra>
<technique profile="blender">
<YF_dofdist>0</YF_dofdist>
<shiftx>0</shiftx>
<shifty>0</shifty>
</technique>
</extra>
</camera>
</library_cameras>
<library_lights>
<light id="Lamp-light" name="Lamp">
<technique_common>
<point>
<color sid="color">1 1 1</color>
<constant_attenuation>1</constant_attenuation>
<linear_attenuation>0</linear_attenuation>
<quadratic_attenuation>0.00111109</quadratic_attenuation>
</point>
</technique_common>
<extra>
<technique profile="blender">
<adapt_thresh>0.000999987</adapt_thresh>
<area_shape>1</area_shape>
<area_size>0.1</area_size>
<area_sizey>0.1</area_sizey>
<area_sizez>1</area_sizez>
<atm_distance_factor>1</atm_distance_factor>
<atm_extinction_factor>1</atm_extinction_factor>
<atm_turbidity>2</atm_turbidity>
<att1>0</att1>
<att2>1</att2>
<backscattered_light>1</backscattered_light>
<bias>1</bias>
<blue>1</blue>
<buffers>1</buffers>
<bufflag>0</bufflag>
<bufsize>2880</bufsize>
<buftype>2</buftype>
<clipend>30.002</clipend>
<clipsta>1.000799</clipsta>
<compressthresh>0.04999995</compressthresh>
<dist sid="blender_dist">29.99998</dist>
<energy sid="blender_energy">1</energy>
<falloff_type>2</falloff_type>
<filtertype>0</filtertype>
<flag>0</flag>
<gamma sid="blender_gamma">1</gamma>
<green>1</green>
<halo_intensity sid="blnder_halo_intensity">1</halo_intensity>
<horizon_brightness>1</horizon_brightness>
<mode>8192</mode>
<ray_samp>1</ray_samp>
<ray_samp_method>1</ray_samp_method>
<ray_samp_type>0</ray_samp_type>
<ray_sampy>1</ray_sampy>
<ray_sampz>1</ray_sampz>
<red>1</red>
<samp>3</samp>
<shadhalostep>0</shadhalostep>
<shadow_b sid="blender_shadow_b">0</shadow_b>
<shadow_g sid="blender_shadow_g">0</shadow_g>
<shadow_r sid="blender_shadow_r">0</shadow_r>
<sky_colorspace>0</sky_colorspace>
<sky_exposure>1</sky_exposure>
<skyblendfac>1</skyblendfac>
<skyblendtype>1</skyblendtype>
<soft>3</soft>
<spotblend>0.15</spotblend>
<spotsize>75</spotsize>
<spread>1</spread>
<sun_brightness>1</sun_brightness>
<sun_effect_type>0</sun_effect_type>
<sun_intensity>1</sun_intensity>
<sun_size>1</sun_size>
<type>0</type>
</technique>
</extra>
</light>
</library_lights>
<library_images/>
<library_effects>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0 0.165 -0.01249998 0 0.165 0.01249998 0.04270511 0.1593778 0.01249998 0.04270511 0.1593778 -0.01249998 0 0.145 -0.01249998 -0.03752881 0.1400592 -0.01249998 -0.07250005 0.1255736 -0.01249998 -0.1025305 0.1025304 -0.01249998 -0.1255737 0.07249993 -0.01249998 -0.1400592 0.03752863 -0.01249998 -0.145 0 -0.01249998 -0.165 0 -0.01249998 -0.1593778 0.04270505 -0.01249998 -0.1428942 0.08249992 -0.01249998 -0.1166726 0.1166725 -0.01249998 -0.0825001 0.1428941 -0.01249998 -0.04270523 0.1593777 -0.01249998 0.08249998 0.1428942 -0.01249998 0.1166726 0.1166726 -0.01249998 0.1428942 0.08249998 -0.01249998 0.1593778 0.04270511 -0.01249998 0.1400592 -0.03752869 -0.01249998 0.145 0 -0.01249998 0.1400592 0.03752875 -0.01249998 0.1255736 0.07249999 -0.01249998 0.1025305 0.1025304 -0.01249998 0.07249999 0.1255736 -0.01249998 0.03752875 0.1400592 -0.01249998 0.165 0 -0.01249998 0.1593778 -0.04270511 -0.01249998 0.1428942 -0.08249998 -0.01249998 0.1166726 -0.1166726 -0.01249998 0.08250004 -0.1428942 -0.01249998 0.04270517 -0.1593777 -0.01249998 0 -0.165 -0.01249998 -0.04270505 -0.1593778 -0.01249998 -0.08249992 -0.1428942 -0.01249998 -0.1166725 -0.1166726 -0.01249998 -0.1428942 -0.08250004 -0.01249998 -0.1593777 -0.04270517 -0.01249998 -0.1400592 -0.03752881 -0.01249998 -0.1255736 -0.07250005 -0.01249998 -0.1025304 -0.1025305 -0.01249998 -0.07249993 -0.1255737 -0.01249998 -0.03752869 -0.1400592 -0.01249998 0 -0.145 -0.01249998 0.03752881 -0.1400592 -0.01249998 0.07249999 -0.1255736 -0.01249998 0.1025305 -0.1025304 -0.01249998 0.1255736 -0.07249993 -0.01249998 -0.04270523 0.1593777 0.01249998 0 0.145 0.01249998 0.03752875 0.1400592 0.01249998 0.07249999 0.1255736 0.01249998 0.1025305 0.1025304 0.01249998 0.1255736 0.07249999 0.01249998 0.1400592 0.03752875 0.01249998 0.145 0 0.01249998 0.1400592 -0.03752869 0.01249998 0.1255736 -0.07249993 0.01249998 0.1025305 -0.1025304 0.01249998 0.07249999 -0.1255736 0.01249998 0.03752881 -0.1400592 0.01249998 0 -0.145 0.01249998 0 -0.165 0.01249998 0.04270517 -0.1593777 0.01249998 0.08250004 -0.1428942 0.01249998 0.1166726 -0.1166726 0.01249998 0.1428942 -0.08249998 0.01249998 0.1593778 -0.04270511 0.01249998 0.165 0 0.01249998 0.1593778 0.04270511 0.01249998 0.1428942 0.08249998 0.01249998 0.1166726 0.1166726 0.01249998 0.08249998 0.1428942 0.01249998 -0.0825001 0.1428941 0.01249998 -0.1166726 0.1166725 0.01249998 -0.1428942 0.08249992 0.01249998 -0.1593778 0.04270505 0.01249998 -0.165 0 0.01249998 -0.1593777 -0.04270517 0.01249998 -0.1428942 -0.08250004 0.01249998 -0.1166725 -0.1166726 0.01249998 -0.08249992 -0.1428942 0.01249998 -0.04270505 -0.1593778 0.01249998 -0.03752869 -0.1400592 0.01249998 -0.07249993 -0.1255737 0.01249998 -0.1025304 -0.1025305 0.01249998 -0.1255736 -0.07250005 0.01249998 -0.1400592 -0.03752881 0.01249998 -0.145 0 0.01249998 -0.1400592 0.03752863 0.01249998 -0.1255737 0.07249993 0.01249998 -0.1025305 0.1025304 0.01249998 -0.07250005 0.1255736 0.01249998 -0.03752881 0.1400592 0.01249998</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305265 0.9914449 0 0 0 1 0 0 1 0.3826832 0.9238796 0 0.6087615 0.7933533 0 0.7933534 0.6087613 0 0.9238796 0.3826833 0 0.9914448 0.1305261 0 0.9914448 -0.1305261 0 0.9238796 -0.3826832 0 0.7933534 -0.6087613 0 0.6087618 -0.7933531 0 0.3826836 -0.9238794 0 0.1305265 -0.9914448 0 -0.1305258 -0.991445 0 -0.3826829 -0.9238797 0 -0.6087611 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238794 -0.3826836 0 -0.9914448 -0.1305269 0 -0.991445 0.1305258 0 -0.9238797 0.3826829 0 -0.7933537 0.608761 0 -0.6087622 0.7933529 0 -0.3826839 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826841 -0.9238793 0 -0.6087614 -0.7933534 0 0.6087622 -0.7933529 0 -0.7933535 -0.6087613 0 0.7933536 -0.608761 0 -0.9238795 -0.3826833 0 0.9238798 -0.3826829 0 -0.9914449 -0.1305264 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238797 0.3826833 0 0.9238795 0.3826837 0 -0.7933533 0.6087614 0 0.7933531 0.6087616 0 -0.6087619 0.793353 0 0.6087611 0.7933536 0 -0.3826837 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914449 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305265 0.9914449 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087615 0.7933533 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238796 0 0 0 1 0.7933534 0.6087613 0 0.9238796 0.3826833 0 0.9914448 0.1305261 0 0.9914448 -0.1305261 0 0.9238796 -0.3826832 0 0.7933534 -0.6087613 0 0.6087618 -0.7933531 0 0.3826836 -0.9238794 0 0.1305265 -0.9914448 0 -0.1305258 -0.991445 0 -0.3826829 -0.9238797 0 -0.6087611 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238794 -0.3826836 0 -0.9914448 -0.1305269 0 -0.991445 0.1305258 0 -0.9238797 0.3826829 0 -0.7933537 0.608761 0 -0.6087622 0.7933529 0 -0.3826839 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826841 -0.9238793 0 -0.6087614 -0.7933534 0 0.6087622 -0.7933529 0 -0.7933535 -0.6087613 0 0.7933536 -0.608761 0 -0.9238795 -0.3826833 0 0.9238798 -0.3826829 0 -0.9914449 -0.1305264 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238797 0.3826833 0 0.9238795 0.3826837 0 -0.7933533 0.6087614 0 0.7933531 0.6087616 0 -0.6087619 0.793353 0 0.6087611 0.7933536 0 -0.3826837 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914449 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Camera" name="Camera" type="NODE">
<matrix sid="transform">0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1</matrix>
<instance_camera url="#Camera-camera"/>
</node>
<node id="Lamp" name="Lamp" type="NODE">
<matrix sid="transform">-0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1</matrix>
<instance_light url="#Lamp-light"/>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,225 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-04T22:25:27</created>
<modified>2014-09-04T22:25:27</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_cameras>
<camera id="Camera-camera" name="Camera">
<optics>
<technique_common>
<perspective>
<xfov sid="xfov">49.13434</xfov>
<aspect_ratio>1.777778</aspect_ratio>
<znear sid="znear">0.1</znear>
<zfar sid="zfar">100</zfar>
</perspective>
</technique_common>
</optics>
<extra>
<technique profile="blender">
<YF_dofdist>0</YF_dofdist>
<shiftx>0</shiftx>
<shifty>0</shifty>
</technique>
</extra>
</camera>
</library_cameras>
<library_lights>
<light id="Lamp-light" name="Lamp">
<technique_common>
<point>
<color sid="color">1 1 1</color>
<constant_attenuation>1</constant_attenuation>
<linear_attenuation>0</linear_attenuation>
<quadratic_attenuation>0.00111109</quadratic_attenuation>
</point>
</technique_common>
<extra>
<technique profile="blender">
<adapt_thresh>0.000999987</adapt_thresh>
<area_shape>1</area_shape>
<area_size>0.1</area_size>
<area_sizey>0.1</area_sizey>
<area_sizez>1</area_sizez>
<atm_distance_factor>1</atm_distance_factor>
<atm_extinction_factor>1</atm_extinction_factor>
<atm_turbidity>2</atm_turbidity>
<att1>0</att1>
<att2>1</att2>
<backscattered_light>1</backscattered_light>
<bias>1</bias>
<blue>1</blue>
<buffers>1</buffers>
<bufflag>0</bufflag>
<bufsize>2880</bufsize>
<buftype>2</buftype>
<clipend>30.002</clipend>
<clipsta>1.000799</clipsta>
<compressthresh>0.04999995</compressthresh>
<dist sid="blender_dist">29.99998</dist>
<energy sid="blender_energy">1</energy>
<falloff_type>2</falloff_type>
<filtertype>0</filtertype>
<flag>0</flag>
<gamma sid="blender_gamma">1</gamma>
<green>1</green>
<halo_intensity sid="blnder_halo_intensity">1</halo_intensity>
<horizon_brightness>1</horizon_brightness>
<mode>8192</mode>
<ray_samp>1</ray_samp>
<ray_samp_method>1</ray_samp_method>
<ray_samp_type>0</ray_samp_type>
<ray_sampy>1</ray_sampy>
<ray_sampz>1</ray_sampz>
<red>1</red>
<samp>3</samp>
<shadhalostep>0</shadhalostep>
<shadow_b sid="blender_shadow_b">0</shadow_b>
<shadow_g sid="blender_shadow_g">0</shadow_g>
<shadow_r sid="blender_shadow_r">0</shadow_r>
<sky_colorspace>0</sky_colorspace>
<sky_exposure>1</sky_exposure>
<skyblendfac>1</skyblendfac>
<skyblendtype>1</skyblendtype>
<soft>3</soft>
<spotblend>0.15</spotblend>
<spotsize>75</spotsize>
<spread>1</spread>
<sun_brightness>1</sun_brightness>
<sun_effect_type>0</sun_effect_type>
<sun_intensity>1</sun_intensity>
<sun_size>1</sun_size>
<type>0</type>
</technique>
</extra>
</light>
</library_lights>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.004999876 0.1944691 -0.09525001 0.005000114 -0.194469 -0.09525001 -1 -0.1944689 -0.09525001 -0.9999998 0.1944695 -0.09525001 0.005000352 0.1944686 0.09525001 0.004999518 -0.1944696 0.09525001 -1 -0.1944687 0.09525001 -1 0.1944692 0.09525001</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Camera" name="Camera" type="NODE">
<matrix sid="transform">0.4165272 -0.2924166 0.4388242 0.09187818 0.4418834 0.2879004 -0.4092082 -4.886189 -0.006568904 0.8249459 0.2983598 5.343665 0 0 0 1</matrix>
<instance_camera url="#Camera-camera"/>
</node>
<node id="Lamp" name="Lamp" type="NODE">
<matrix sid="transform">-0.1921522 -0.4853481 0.4603671 7.167954 0.6310092 -0.1258111 0.1775094 0.02031231 -0.03645923 0.3805014 0.6459134 5.903862 0 0 0 1</matrix>
<instance_light url="#Lamp-light"/>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_0.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_1.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_2.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_2.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_4.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_5.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_6.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_7.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_8.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,469 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-09-06T22:35:48</created>
<modified>2014-09-06T22:35:48</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_target_png" name="sick_target_png">
<init_from>sick_target.png</init_from>
</image>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_9.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material_001-effect">
<profile_COMMON>
<newparam sid="sick_target_png-surface">
<surface type="2D">
<init_from>sick_target_png</init_from>
</surface>
</newparam>
<newparam sid="sick_target_png-sampler">
<sampler2D>
<source>sick_target_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_target_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Green-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.01130602 0.24865 0 1</color>
</diffuse>
<specular>
<color sid="specular">0 0.5 0.003074352 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_003-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_004-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0 0.01840566 0.64 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
<effect id="Material_005-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.64 0.08687871 0.005790061 1</color>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material_001-material" name="Material_001">
<instance_effect url="#Material_001-effect"/>
</material>
<material id="Green-material" name="Green">
<instance_effect url="#Green-effect"/>
</material>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
<material id="Material_003-material" name="Material_003">
<instance_effect url="#Material_003-effect"/>
</material>
<material id="Material_004-material" name="Material_004">
<instance_effect url="#Material_004-effect"/>
</material>
<material id="Material_005-material" name="Material_005">
<instance_effect url="#Material_005-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube_001-mesh" name="Cube.001">
<mesh>
<source id="Cube_001-mesh-positions">
<float_array id="Cube_001-mesh-positions-array" count="24">0.004999876 0.1944691 0.1547499 0.005000114 -0.194469 0.1547499 -1 -0.1944689 0.1547499 -0.9999998 0.1944695 0.1547499 0.005000352 0.1944686 0.34525 0.004999518 -0.1944696 0.34525 -1 -0.1944687 0.34525 -1 0.1944692 0.34525</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-normals">
<float_array id="Cube_001-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -2.14549e-6 3.12885e-6 -9.4893e-7 -1 9.38655e-7 -1 6.12999e-7 -1.25154e-6 4.15157e-7 1 1.87731e-6 0 0 -1 0 0 1 1 6.12999e-7 -2.50308e-6 -1.77924e-7 -1 -3.12885e-6 -1 6.12998e-7 -1.25154e-6 5.33773e-7 1 2.50308e-6</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_001-mesh-map-0">
<float_array id="Cube_001-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_001-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_001-mesh-vertices">
<input semantic="POSITION" source="#Cube_001-mesh-positions"/>
</vertices>
<polylist material="Material_001-material" count="12">
<input semantic="VERTEX" source="#Cube_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_001-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube_001-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cylinder-mesh" name="Cylinder">
<mesh>
<source id="Cylinder-mesh-positions">
<float_array id="Cylinder-mesh-positions-array" count="288">0.25 0.165 0.4875 0.25 0.165 0.5125 0.2927051 0.1593778 0.5125 0.2927051 0.1593778 0.4875 0.25 0.145 0.4875 0.2124711 0.1400592 0.4875 0.1774999 0.1255736 0.4875 0.1474694 0.1025304 0.4875 0.1244263 0.07249993 0.4875 0.1099407 0.03752863 0.4875 0.105 0 0.4875 0.08499997 0 0.4875 0.09062218 0.04270505 0.4875 0.1071057 0.08249992 0.4875 0.1333273 0.1166725 0.4875 0.1674998 0.1428941 0.4875 0.2072947 0.1593777 0.4875 0.3325 0.1428942 0.4875 0.3666726 0.1166726 0.4875 0.3928942 0.08249998 0.4875 0.4093778 0.04270511 0.4875 0.3900592 -0.03752869 0.4875 0.395 0 0.4875 0.3900592 0.03752875 0.4875 0.3755737 0.07249999 0.4875 0.3525305 0.1025304 0.4875 0.3225 0.1255736 0.4875 0.2875288 0.1400592 0.4875 0.415 0 0.4875 0.4093778 -0.04270511 0.4875 0.3928942 -0.08249998 0.4875 0.3666726 -0.1166726 0.4875 0.3325001 -0.1428942 0.4875 0.2927052 -0.1593777 0.4875 0.2500001 -0.165 0.4875 0.2072949 -0.1593778 0.4875 0.1675 -0.1428942 0.4875 0.1333274 -0.1166726 0.4875 0.1071058 -0.08250004 0.4875 0.09062224 -0.04270517 0.4875 0.1099408 -0.03752881 0.4875 0.1244263 -0.07250005 0.4875 0.1474695 -0.1025305 0.4875 0.1775 -0.1255737 0.4875 0.2124713 -0.1400592 0.4875 0.2500001 -0.145 0.4875 0.2875288 -0.1400592 0.4875 0.3225001 -0.1255736 0.4875 0.3525305 -0.1025304 0.4875 0.3755737 -0.07249993 0.4875 0.2072947 0.1593777 0.5125 0.25 0.145 0.5125 0.2875288 0.1400592 0.5125 0.3225 0.1255736 0.5125 0.3525305 0.1025304 0.5125 0.3755737 0.07249999 0.5125 0.3900592 0.03752875 0.5125 0.395 0 0.5125 0.3900592 -0.03752869 0.5125 0.3755737 -0.07249993 0.5125 0.3525305 -0.1025304 0.5125 0.3225001 -0.1255736 0.5125 0.2875288 -0.1400592 0.5125 0.2500001 -0.145 0.5125 0.2500001 -0.165 0.5125 0.2927052 -0.1593777 0.5125 0.3325001 -0.1428942 0.5125 0.3666726 -0.1166726 0.5125 0.3928942 -0.08249998 0.5125 0.4093778 -0.04270511 0.5125 0.415 0 0.5125 0.4093778 0.04270511 0.5125 0.3928942 0.08249998 0.5125 0.3666726 0.1166726 0.5125 0.3325 0.1428942 0.5125 0.1674998 0.1428941 0.5125 0.1333273 0.1166725 0.5125 0.1071057 0.08249992 0.5125 0.09062218 0.04270505 0.5125 0.08499997 0 0.5125 0.09062224 -0.04270517 0.5125 0.1071058 -0.08250004 0.5125 0.1333274 -0.1166726 0.5125 0.1675 -0.1428942 0.5125 0.2072949 -0.1593778 0.5125 0.2124713 -0.1400592 0.5125 0.1775 -0.1255737 0.5125 0.1474695 -0.1025305 0.5125 0.1244263 -0.07250005 0.5125 0.1099408 -0.03752881 0.5125 0.105 0 0.5125 0.1099407 0.03752863 0.5125 0.1244263 0.07249993 0.5125 0.1474694 0.1025304 0.5125 0.1774999 0.1255736 0.5125 0.2124711 0.1400592 0.5125</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-positions-array" count="96" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cylinder-mesh-normals">
<float_array id="Cylinder-mesh-normals-array" count="576">0.1305261 0.9914449 0 0 0 -1 0 0 -1 -0.1305264 0.9914448 0 0 0 1 0 0 1 0.3826832 0.9238797 0 0.6087616 0.7933532 0 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0 0.1305261 0.9914449 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 -0.1305264 0.9914448 0 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6087616 0.7933532 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3826832 0.9238797 0 0 0 1 0.7933534 0.6087614 0 0.9238798 0.382683 0 0.9914448 0.1305269 0 0.9914448 -0.1305269 0 0.9238798 -0.3826829 0 0.7933533 -0.6087616 0 0.608762 -0.793353 0 0.3826838 -0.9238794 0 0.1305265 -0.9914449 0 -0.1305258 -0.9914449 0 -0.3826829 -0.9238798 0 -0.608761 -0.7933536 0 -0.7933531 -0.6087617 0 -0.9238795 -0.3826836 0 -0.9914448 -0.1305269 0 -0.9914448 0.1305258 0 -0.9238798 0.3826829 0 -0.7933538 0.6087609 0 -0.6087621 0.7933529 0 -0.3826841 0.9238793 0 -0.1305264 -0.9914448 0 0.1305264 -0.9914448 0 -0.3826832 -0.9238796 0 0.3826842 -0.9238793 0 -0.6087614 -0.7933534 0 0.608762 -0.7933529 0 -0.7933533 -0.6087616 0 0.7933537 -0.608761 0 -0.9238798 -0.382683 0 0.9238798 -0.3826829 0 -0.9914449 -0.130526 0 0.9914449 -0.1305256 0 -0.9914449 0.130526 0 0.9914448 0.1305268 0 -0.9238798 0.3826829 0 0.9238795 0.3826837 0 -0.7933534 0.6087613 0 0.7933531 0.6087617 0 -0.608762 0.7933529 0 0.6087611 0.7933536 0 -0.3826836 0.9238795 0 0.3826829 0.9238798 0 -0.1305264 0.9914448 0 0.1305256 0.9914449 0</float_array>
<technique_common>
<accessor source="#Cylinder-mesh-normals-array" count="192" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cylinder-mesh-vertices">
<input semantic="POSITION" source="#Cylinder-mesh-positions"/>
</vertices>
<polylist material="Green-material" count="192">
<input semantic="VERTEX" source="#Cylinder-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cylinder-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>1 0 2 0 3 0 0 1 3 1 4 1 34 2 35 2 45 2 50 3 1 3 0 3 70 4 56 4 57 4 79 5 80 5 90 5 2 6 74 6 17 6 74 7 73 7 18 7 73 8 72 8 19 8 72 9 71 9 20 9 71 10 70 10 28 10 70 11 69 11 29 11 69 12 68 12 30 12 30 13 68 13 67 13 67 14 66 14 32 14 66 15 65 15 33 15 65 16 64 16 34 16 64 17 84 17 35 17 84 18 83 18 36 18 83 19 82 19 37 19 82 20 81 20 38 20 81 21 80 21 39 21 80 22 79 22 11 22 79 23 78 23 12 23 78 24 77 24 13 24 77 25 76 25 14 25 76 26 75 26 15 26 75 27 50 27 16 27 27 28 52 28 51 28 4 29 51 29 95 29 26 30 53 30 52 30 5 31 95 31 94 31 25 32 54 32 53 32 6 33 94 33 93 33 24 34 55 34 54 34 7 35 93 35 92 35 23 36 56 36 55 36 8 37 92 37 91 37 22 38 57 38 56 38 9 39 91 39 90 39 21 40 58 40 57 40 10 41 90 41 89 41 49 42 59 42 58 42 40 43 89 43 88 43 48 44 60 44 59 44 41 45 88 45 87 45 47 46 61 46 60 46 42 47 87 47 86 47 46 48 62 48 61 48 43 49 86 49 85 49 45 50 63 50 62 50 44 51 85 51 63 51 0 52 1 52 3 52 9 53 10 53 11 53 13 54 8 54 12 54 15 55 6 55 14 55 0 56 4 56 16 56 17 57 26 57 3 57 19 58 24 58 18 58 20 59 21 59 22 59 11 60 12 60 9 60 20 61 24 61 19 61 20 62 22 62 23 62 12 63 8 63 9 63 20 64 23 64 24 64 7 65 8 65 13 65 3 66 27 66 4 66 13 67 14 67 7 67 17 68 18 68 25 68 14 69 6 69 7 69 17 70 25 70 26 70 5 71 6 71 15 71 3 72 26 72 27 72 15 73 16 73 5 73 30 74 49 74 29 74 16 75 4 75 5 75 21 76 20 76 28 76 18 77 24 77 25 77 32 78 47 78 31 78 34 79 45 79 33 79 36 80 43 80 35 80 41 81 42 81 38 81 39 82 40 82 41 82 40 83 39 83 10 83 28 84 29 84 21 84 42 85 37 85 38 85 29 86 49 86 21 86 38 87 39 87 41 87 48 88 49 88 30 88 37 89 42 89 43 89 30 90 31 90 48 90 39 91 11 91 10 91 31 92 47 92 48 92 36 93 37 93 43 93 46 94 47 94 32 94 35 95 43 95 44 95 32 96 33 96 46 96 52 97 2 97 51 97 33 98 45 98 46 98 16 99 50 99 0 99 35 100 44 100 45 100 62 101 63 101 64 101 66 102 61 102 65 102 68 103 59 103 67 103 70 104 57 104 69 104 55 105 56 105 72 105 53 106 54 106 74 106 2 107 1 107 51 107 56 108 71 108 72 108 64 109 65 109 62 109 67 110 60 110 61 110 65 111 61 111 62 111 73 112 54 112 55 112 66 113 67 113 61 113 94 114 95 114 75 114 52 115 53 115 74 115 72 116 73 116 55 116 67 117 59 117 60 117 54 118 73 118 74 118 58 119 59 119 68 119 70 120 71 120 56 120 68 121 69 121 58 121 1 122 50 122 51 122 69 123 57 123 58 123 2 124 52 124 74 124 92 125 93 125 77 125 90 126 91 126 79 126 81 127 88 127 80 127 83 128 86 128 82 128 64 129 85 129 84 129 64 130 63 130 85 130 17 131 74 131 18 131 93 132 76 132 77 132 80 133 89 133 90 133 83 134 84 134 86 134 75 135 76 135 94 135 82 136 86 136 87 136 84 137 85 137 86 137 81 138 82 138 87 138 76 139 93 139 94 139 81 140 87 140 88 140 77 141 78 141 92 141 80 142 88 142 89 142 95 143 50 143 75 143 50 144 95 144 51 144 78 145 91 145 92 145 3 146 2 146 17 146 91 147 78 147 79 147 18 148 73 148 19 148 19 149 72 149 20 149 20 150 71 150 28 150 28 151 70 151 29 151 29 152 69 152 30 152 31 153 30 153 67 153 31 154 67 154 32 154 32 155 66 155 33 155 33 156 65 156 34 156 34 157 64 157 35 157 35 158 84 158 36 158 36 159 83 159 37 159 37 160 82 160 38 160 38 161 81 161 39 161 39 162 80 162 11 162 11 163 79 163 12 163 12 164 78 164 13 164 13 165 77 165 14 165 14 166 76 166 15 166 15 167 75 167 16 167 4 168 27 168 51 168 5 169 4 169 95 169 27 170 26 170 52 170 6 171 5 171 94 171 26 172 25 172 53 172 7 173 6 173 93 173 25 174 24 174 54 174 8 175 7 175 92 175 24 176 23 176 55 176 9 177 8 177 91 177 23 178 22 178 56 178 10 179 9 179 90 179 22 180 21 180 57 180 40 181 10 181 89 181 21 182 49 182 58 182 41 183 40 183 88 183 49 184 48 184 59 184 42 185 41 185 87 185 48 186 47 186 60 186 43 187 42 187 86 187 47 188 46 188 61 188 44 189 43 189 85 189 46 190 45 190 62 190 45 191 44 191 63 191</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0.5278729 0.5278729 -3.21865e-6 0.5278729 -0.527873 -3.21865e-6 -0.5278731 -0.5278729 -3.21865e-6 -0.5278728 0.5278732 -3.21865e-6 0.5278732 0.5278727 1.055743 0.5278726 -0.5278733 1.055743 -0.5278732 -0.5278728 1.055743 -0.527873 0.5278729 1.055743</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.08116e-7 2.82287e-7 -4.51659e-7 -1 0 -1 2.2583e-7 0 2.2583e-7 1 2.2583e-7 0 0 -1 0 0 1 1 0 -2.2583e-7 0 -1 -2.2583e-7 -1 2.82287e-7 -1.69372e-7 2.25829e-7 1 2.25829e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 4 1 3 7 1 4 6 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 5 7 21 4 7 22 6 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_003-mesh" name="Cube.003">
<mesh>
<source id="Cube_003-mesh-positions">
<float_array id="Cube_003-mesh-positions-array" count="24">-1 -0.3758965 0 -1 0.3758965 0 -0.2486995 0.3758965 0 -0.2486995 -0.3758965 0 -1 -0.3758965 4.707077 -1 0.3758965 4.707077 -0.2486995 0.3758965 4.707077 -0.2486995 -0.3758965 4.707077</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_003-mesh-normals">
<float_array id="Cube_003-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_003-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_003-mesh-vertices">
<input semantic="POSITION" source="#Cube_003-mesh-positions"/>
</vertices>
<polylist material="Material_003-material" count="12">
<input semantic="VERTEX" source="#Cube_003-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_003-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
<geometry id="Cube_004-mesh" name="Cube.004">
<mesh>
<source id="Cube_004-mesh-positions">
<float_array id="Cube_004-mesh-positions-array" count="24">-1 -0.3758965 2.93456 -1 0.3758965 2.93456 -0.2486995 0.3758965 2.93456 -0.2486995 -0.3758965 2.93456 -1 -0.3758965 3.041528 -1 0.3758965 3.041528 -0.2486995 0.3758965 3.041528 -0.2486995 -0.3758965 3.041528</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube_004-mesh-normals">
<float_array id="Cube_004-mesh-normals-array" count="36">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube_004-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube_004-mesh-vertices">
<input semantic="POSITION" source="#Cube_004-mesh-positions"/>
</vertices>
<polylist material="Material_005-material" count="12">
<input semantic="VERTEX" source="#Cube_004-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube_004-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>4 0 5 0 1 0 5 1 6 1 2 1 6 2 7 2 3 2 7 3 4 3 0 3 0 4 1 4 2 4 7 5 6 5 5 5 0 6 4 6 1 6 1 7 5 7 2 7 2 8 6 8 3 8 3 9 7 9 0 9 3 10 0 10 2 10 4 11 7 11 5 11</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube_001" name="Cube_001" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_001-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_001-material" target="#Material_001-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cylinder" name="Cylinder" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cylinder-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Green-material" target="#Green-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01663818 0 0 -0.04 0 0.5432869 0 0 0 0 0.8319097 0.57 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_003" name="Cube_003" type="NODE">
<matrix sid="transform">0.1651367 0 0 0 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_003-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_003-material" target="#Material_003-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
<node id="Cube_004" name="Cube_004" type="NODE">
<matrix sid="transform">0.1651367 0 0 0.1421456 0 0.1651367 0 0 0 0 0.1651367 0 0 0 0 1</matrix>
<instance_geometry url="#Cube_004-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material_004-material" target="#Material_004-material"/>
<instance_material symbol="Material_005-material" target="#Material_005-material"/>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_0.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.7 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_1.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_2.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.5 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_3.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.4 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_4.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.9 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_5.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.7 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_6.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.8 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_7.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.8 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_8.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.9 KiB

View file

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Stefan Kohlbrecher</author>
<authoring_tool>Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b</authoring_tool>
</contributor>
<created>2014-08-30T23:18:41</created>
<modified>2014-08-30T23:18:41</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images>
<image id="sick_robot_panel_0_png" name="sick_robot_panel_0_png">
<init_from>sick_robot_panel_9.png</init_from>
</image>
</library_images>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<newparam sid="sick_robot_panel_0_png-surface">
<surface type="2D">
<init_from>sick_robot_panel_0_png</init_from>
</surface>
</newparam>
<newparam sid="sick_robot_panel_0_png-sampler">
<sampler2D>
<source>sick_robot_panel_0_png-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
</ambient>
<diffuse>
<texture texture="sick_robot_panel_0_png-sampler" texcoord="UVMap"/>
</diffuse>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 2.38419e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 1.78814e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map-0">
<float_array id="Cube-mesh-map-0-array" count="72">0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 0.9998998 9.998e-5 0.9999001 9.998e-5 1.00278e-4 0.9998996 0.9998997 9.998e-5 0.9998998 9.998e-5 9.998e-5 0 0 0 0 0 0 0 0 0.9999999 0 1 0.9999997 0 0 0 0 0 0 0 0 0 0 0 0 0.9998998 9.998e-5 0.9998998 0.9998998 9.998e-5 1.00278e-4 0.9999001 1.0004e-4 0.9998996 0.9998997 9.998e-5 9.998e-5 0 0 0 0 0 0 0 1 0 0 1 0.9999997</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-0-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map-0" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 4 5 15 0 5 16 3 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 7 11 33 4 11 34 3 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.01999998 0 0 0 0 0.65306 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.7 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 29 KiB

View file

@ -0,0 +1,12 @@
<?xml version="1.0"?>
<launch>
<arg name="args" default=""/>
<include file="$(find hector_gazebo_worlds)/launch/start.launch">
<arg name="world" value="$(find hector_gazebo_worlds)/worlds/drc_final_qual_4_step_block.world"/>
<arg name="args" default="$(arg args)"/>
</include>
</launch>

View file

@ -0,0 +1,8 @@
<?xml version="1.0"?>
<launch>
<include file="$(find hector_gazebo_worlds)/launch/start.launch">
<arg name="world" value="$(find hector_gazebo_worlds)/worlds/rolling_landscape_120m.world"/>
</include>
</launch>

View file

@ -0,0 +1,8 @@
<?xml version="1.0"?>
<launch>
<include file="$(find hector_gazebo_worlds)/launch/start.launch">
<arg name="world" value="$(find hector_gazebo_worlds)/worlds/sick_robot_day_2012_20m.world"/>
</include>
</launch>

View file

@ -0,0 +1,8 @@
<?xml version="1.0"?>
<launch>
<include file="$(find hector_gazebo_worlds)/launch/start.launch">
<arg name="world" value="$(find hector_gazebo_worlds)/worlds/sick_robot_day_2014.world"/>
</include>
</launch>

View file

@ -0,0 +1,8 @@
<?xml version="1.0"?>
<launch>
<include file="$(find hector_gazebo_worlds)/launch/start.launch">
<arg name="world" value="$(find hector_gazebo_worlds)/worlds/small_indoor_scenario.world"/>
</include>
</launch>

View file

@ -0,0 +1,18 @@
<?xml version="1.0"?>
<launch>
<arg name="world" default="worlds/empty.world"/>
<arg name="gui" default="true"/>
<arg name="args" default=""/>
<param name="/use_sim_time" value="true" />
<node name="gazebo" pkg="gazebo_ros" type="gzserver" args="$(arg world) $(arg args)" respawn="false" output="screen"/>
<!-- start gui -->
<group if="$(arg gui)">
<node name="gazebo_gui" pkg="gazebo_ros" type="gzclient" respawn="false" output="screen"/>
</group>
</launch>

View file

@ -0,0 +1,8 @@
<?xml version="1.0"?>
<launch>
<include file="$(find hector_gazebo_worlds)/launch/start.launch">
<arg name="world" value="$(find hector_gazebo_worlds)/worlds/willow_garage.world"/>
</include>
</launch>

View file

@ -0,0 +1,7 @@
image: small_indoor_scenario_edited_map_hector_mapping.pgm
resolution: 0.050000
origin: [-19.224998, -19.224998, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196

View file

@ -0,0 +1,31 @@
<package>
<name>hector_gazebo_worlds</name>
<version>0.3.6</version>
<description>hector_gazebo_worlds provides gazebo scenarios used by Team Hector Darmstadt</description>
<maintainer email="meyer@fsr.tu-darmstadt.de">Johannes Meyer</maintainer>
<license>BSD</license>
<url type="website">http://ros.org/wiki/hector_gazebo_worlds</url>
<!-- <url type="bugtracker"></url> -->
<author email="kohlbrecher@sim.tu-darmstadt.de">Stefan Kohlbrecher</author>
<!-- Dependencies which this package needs to build itself. -->
<buildtool_depend>catkin</buildtool_depend>
<!-- Dependencies needed to compile this package. -->
<!-- Dependencies needed after this package is compiled. -->
<run_depend>gazebo_ros</run_depend>
<run_depend>hector_gazebo_plugins</run_depend>
<!-- Dependencies needed only for running tests. -->
<!-- <test_depend>gazebo_ros</test_depend> -->
<!-- <test_depend>hector_gazebo_plugins</test_depend> -->
<export>
<gazebo_ros gazebo_media_path="${prefix}"/>
</export>
</package>

View file

@ -0,0 +1,147 @@
<sdf version='1.5'>
<world name='default'>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>0 0 10 0 -0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<model name='ground_plane'>
<static>1</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
</friction>
<contact>
<ode/>
</contact>
<bounce/>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<velocity_decay>
<linear>0</linear>
<angular>0</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
</model>
<model name="drc_qual4_block">
<link name="drc_qual4_block_link">
<pose>0.3 0 0 0 0 0</pose>
<collision name="drc_qual4_block_collision">
<geometry>
<mesh>
<uri>file://drc_qual4_block.stl</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
</collision>
<visual name="drc_qual4_block">
<geometry>
<mesh>
<uri>file://drc_qual4_block.stl</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
<cast_shadows>false</cast_shadows>
</visual>
</link>
<static>true</static>
</model>
<physics type="ode">
<gravity>0 0 -9.81</gravity>
<simbody>
<accuracy>0.005</accuracy>
<max_transient_velocity>0.005</max_transient_velocity>
<contact>
<stiffness>1e8</stiffness>
<dissipation>20.0</dissipation>
</contact>
</simbody>
<ode>
<solver>
<use_dynamic_moi_rescaling>true</use_dynamic_moi_rescaling>
<type>quick</type>
<iters>200</iters>
<sor>1.0</sor>
</solver>
<constraints>
<cfm>0.0</cfm>
<erp>0.2</erp>
<contact_max_correcting_vel>100.0</contact_max_correcting_vel>
<contact_surface_layer>0.0</contact_surface_layer>
</constraints>
</ode>
<real_time_update_rate>1000</real_time_update_rate>
<max_step_size>0.001</max_step_size>
</physics>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>0</latitude_deg>
<longitude_deg>0</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<state world_name='default'>
<sim_time>5369 943000000</sim_time>
<real_time>5800 685587240</real_time>
<wall_time>1423245799 456557065</wall_time>
<model name='ground_plane'>
<pose>0 0 0 0 -0 0</pose>
<link name='link'>
<pose>0 0 0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>-0.572734 7.93393 1.30199 -1.4159e-17 0.199643 -1.57102</pose>
<view_controller>orbit</view_controller>
</camera>
</gui>
</world>
</sdf>

View file

@ -0,0 +1,60 @@
<?xml version="1.0" encoding="UTF-8" ?>
<sdf version="1.4">
<world name="default">
<scene>
<ambient>0.5 0.5 0.5 1</ambient>
<background>0.5 0.5 0.5 1</background>
<shadows>false</shadows>
</scene>
<physics type="ode">
<gravity>0 0 -9.81</gravity>
<ode>
<solver>
<type>quick</type>
<iters>10</iters>
<sor>1.3</sor>
</solver>
<constraints>
<cfm>0.0</cfm>
<erp>0.2</erp>
<contact_max_correcting_vel>10</contact_max_correcting_vel>
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.001</max_step_size>
</physics>
<light type="directional" name="directional_light_1">
<pose>0 20 20 0.1 0.1 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>1 1 1 1</specular>
<attenuation>
<range>300</range>
</attenuation>
<direction>0.1 0.1 -1</direction>
<cast_shadows>false</cast_shadows>
</light>
<model name="120m_landscape_smooth_tri">
<link name="120m_landscape_smooth_tri_link">
<pose>0 0 0 0 0 0</pose>
<collision name="120m_landscape_smooth_tri_collision">
<geometry>
<mesh>
<uri>file://120m_landscape_smooth_tri.dae</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
</collision>
<visual name="120m_landscape_smooth_tri">
<geometry>
<mesh>
<uri>file://120m_landscape_smooth_tri.dae</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
<cast_shadows>false</cast_shadows>
</visual>
</link>
<static>true</static>
</model>
</world>
</sdf>

Some files were not shown because too many files have changed in this diff Show more