mesh.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <rve_transformer/transformer_manager.h>
00031 #include <rve_transformer/frame_manager.h>
00032 #include <rve_common_transformers/mesh.h>
00033 #include <rve_properties/property_node.h>
00034 #include <rve_properties/messages.h>
00035 #include <rve_render_client/mesh_instance.h>
00036 #include <rve_render_client/material.h>
00037 
00038 #include <tf2/exceptions.h>
00039 #include <ros/callback_queue.h>
00040 
00041 #include <rve_msgs/make_vector3.h>
00042 #include <rve_msgs/make_quaternion.h>
00043 #include <rve_msgs/Mesh.h>
00044 #include <rve_msgs/Material.h>
00045 #include <rve_common/eigen_conversions.h>
00046 #include <geometry_msgs/TransformStamped.h>
00047 
00048 namespace rve_common_transformers
00049 {
00050 
00051 Mesh::Mesh()
00052 {
00053 }
00054 
00055 Mesh::~Mesh()
00056 {
00057   getPropertyNode()->removeChangeCallback(this);
00058 }
00059 
00060 void Mesh::onInit()
00061 {
00062   rve_msgs::Vector3 v;
00063   rve_msgs::Quaternion q;
00064   q.w = 1.0;
00065   getPropertyNode()->get("position_offset", v, v);
00066   getPropertyNode()->get("orientation_offset", q, q);
00067   position_offset_ = rve_common::msgToEigen(v);
00068   orientation_offset_ = rve_common::msgToEigen(q);
00069 
00070   getPropertyNode()->get("resource", resource_);
00071   getPropertyNode()->get("frame", frame_);
00072 
00073   opacity_ = 1.0;
00074   getPropertyNode()->get("opacity", opacity_, opacity_);
00075 
00076   getPropertyNode()->addChangeCallback(boost::bind(&Mesh::onPropertyChanged, this, _1, _2, _3), this, getCallbackQueue());
00077 
00078   mesh_ = addObject(rve_render_client::createMeshInstance(resource_));
00079 
00080   rve_render_client::MeshPtr mesh = mesh_->getMesh();
00081   rve_msgs::MeshConstPtr msg = mesh->getMesh();
00082   for (size_t i = 0; i < msg->materials.size(); ++i)
00083   {
00084     rve_render_client::MaterialPtr mat = addObject(rve_render_client::createMaterial());
00085     rve_msgs::Material m = msg->materials[i];
00086     m.opacity = opacity_;
00087     mat->setMaterial(m);
00088     materials_.push_back(mat);
00089   }
00090 
00091   for (size_t i = 0; i < msg->submeshes.size(); ++i)
00092   {
00093     uint8_t mat_index = msg->submeshes[i].material_index;
00094     if (mat_index < msg->materials.size())
00095     {
00096       mesh_->setMaterial(mat_index, materials_[mat_index]);
00097     }
00098   }
00099 }
00100 
00101 void Mesh::onUpdate()
00102 {
00103   try
00104   {
00105     geometry_msgs::TransformStamped transform = getManager()->getFrameManager()->lookupTransform(frame_, ros::Time());
00106     const geometry_msgs::Vector3& vm = transform.transform.translation;
00107     Eigen::Vector3f v(vm.x, vm.y, vm.z);
00108     v += position_offset_;
00109     mesh_->setPosition(rve_msgs::makeVector3(v.x(), v.y(), v.z()));
00110     const geometry_msgs::Quaternion& qm = transform.transform.rotation;
00111     Eigen::Quaternionf q(qm.w, qm.x, qm.y, qm.z);
00112     q *= orientation_offset_;
00113     mesh_->setOrientation(rve_msgs::makeQuaternion(q.x(), q.y(), q.z(), q.w()));
00114   }
00115   catch (tf2::TransformException& e)
00116   {
00117   }
00118 }
00119 
00120 void Mesh::onPropertyChanged(const rve_properties::PropertyNodePtr& node, const std::string& path, rve_properties::PropertyChangeType type)
00121 {
00122   if (type != rve_properties::PropertyChanged)
00123   {
00124     return;
00125   }
00126 
00127   if (path == "opacity")
00128   {
00129     opacity_ = node->get<float>();
00130     for (size_t i = 0; i < materials_.size(); ++i)
00131     {
00132       const rve_render_client::MaterialPtr& mat = materials_[i];
00133       mat->setOpacity(opacity_);
00134     }
00135   }
00136 }
00137 
00138 } // namespace rve_common_transformers
00139 


rve_common_transformers
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:58