$search
00001 /* 00002 * Copyright (c) 2008, 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 "axes_display.h" 00031 #include "rviz/visualization_manager.h" 00032 #include "rviz/properties/property.h" 00033 #include "rviz/properties/property_manager.h" 00034 #include "rviz/frame_manager.h" 00035 00036 #include "ogre_tools/axes.h" 00037 00038 #include <boost/bind.hpp> 00039 00040 #include <OGRE/OgreSceneNode.h> 00041 #include <OGRE/OgreSceneManager.h> 00042 00043 namespace rviz 00044 { 00045 00046 AxesDisplay::AxesDisplay() 00047 : Display() 00048 , length_( 1.0 ) 00049 , radius_( 0.1 ) 00050 , axes_( 0 ) 00051 { 00052 } 00053 00054 AxesDisplay::~AxesDisplay() 00055 { 00056 delete axes_; 00057 } 00058 00059 void AxesDisplay::onInitialize() 00060 { 00061 axes_ = new ogre_tools::Axes( scene_manager_, 0, length_, radius_ ); 00062 00063 axes_->getSceneNode()->setVisible( isEnabled() ); 00064 00065 setFrame(FIXED_FRAME_STRING); 00066 } 00067 00068 void AxesDisplay::onEnable() 00069 { 00070 axes_->getSceneNode()->setVisible( true ); 00071 } 00072 00073 void AxesDisplay::onDisable() 00074 { 00075 axes_->getSceneNode()->setVisible( false ); 00076 } 00077 00078 void AxesDisplay::create() 00079 { 00080 axes_->set( length_, radius_ ); 00081 00082 causeRender(); 00083 } 00084 00085 void AxesDisplay::set( float length, float radius ) 00086 { 00087 length_ = length; 00088 radius_ = radius; 00089 00090 create(); 00091 00092 propertyChanged(length_property_); 00093 propertyChanged(radius_property_); 00094 } 00095 00096 void AxesDisplay::setFrame(const std::string& frame) 00097 { 00098 frame_ = frame; 00099 propertyChanged(frame_property_); 00100 } 00101 00102 void AxesDisplay::setLength( float length ) 00103 { 00104 set( length, radius_ ); 00105 } 00106 00107 void AxesDisplay::setRadius( float radius ) 00108 { 00109 set( length_, radius ); 00110 } 00111 00112 void AxesDisplay::update(float dt, float ros_dt) 00113 { 00114 std::string frame = frame_; 00115 if (frame == FIXED_FRAME_STRING) 00116 { 00117 frame = fixed_frame_; 00118 } 00119 00120 Ogre::Vector3 position; 00121 Ogre::Quaternion orientation; 00122 if (vis_manager_->getFrameManager()->getTransform(frame, ros::Time(), position, orientation)) 00123 { 00124 axes_->setPosition(position); 00125 axes_->setOrientation(orientation); 00126 setStatus(status_levels::Ok, "Transform", "Transform OK"); 00127 } 00128 else 00129 { 00130 std::string error; 00131 if (vis_manager_->getFrameManager()->transformHasProblems(frame, ros::Time(), error)) 00132 { 00133 setStatus(status_levels::Error, "Transform", error); 00134 } 00135 else 00136 { 00137 std::stringstream ss; 00138 ss << "Could not transform from [" << frame << "] to Fixed Frame [" << fixed_frame_ << "] for an unknown reason"; 00139 setStatus(status_levels::Error, "Transform", ss.str()); 00140 } 00141 } 00142 } 00143 00144 void AxesDisplay::createProperties() 00145 { 00146 frame_property_ = property_manager_->createProperty<TFFrameProperty>("Reference Frame", property_prefix_, boost::bind(&AxesDisplay::getFrame, this), 00147 boost::bind(&AxesDisplay::setFrame, this, _1), parent_category_, this); 00148 setPropertyHelpText(frame_property_, "The TF frame these axes will use for their origin."); 00149 length_property_ = property_manager_->createProperty<FloatProperty>( "Length", property_prefix_, boost::bind( &AxesDisplay::getLength, this ), 00150 boost::bind( &AxesDisplay::setLength, this, _1 ), parent_category_, this ); 00151 FloatPropertyPtr float_prop = length_property_.lock(); 00152 float_prop->setMin( 0.0001 ); 00153 setPropertyHelpText(length_property_, "Length of each axis, in meters."); 00154 00155 radius_property_ = property_manager_->createProperty<FloatProperty>( "Radius", property_prefix_, boost::bind( &AxesDisplay::getRadius, this ), 00156 boost::bind( &AxesDisplay::setRadius, this, _1 ), parent_category_, this ); 00157 float_prop = radius_property_.lock(); 00158 float_prop->setMin( 0.0001 ); 00159 setPropertyHelpText(radius_property_, "Width of each axis, in meters."); 00160 } 00161 00162 } // namespace rviz