marker_detection_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2016, Lukas Pfeifhofer <lukas.pfeifhofer@devlabs.pro>
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  * 1. Redistributions of source code must retain the above copyright notice,
00009  * this list of conditions and the following disclaimer.
00010  *
00011  * 2. Redistributions in binary form must reproduce the above copyright notice,
00012  * this list of conditions and the following disclaimer in the documentation
00013  * and/or other materials provided with the distribution.
00014  *
00015  * 3. Neither the name of the copyright holder nor the names of its contributors
00016  * may be used to endorse or promote products derived from this software without
00017  * specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #include <OGRE/OgreManualObject.h>
00033 #include <OGRE/OgreEntity.h>
00034 #include <OGRE/OgreMeshManager.h>
00035 #include <OGRE/OgreSceneNode.h>
00036 #include <OGRE/OgreSceneManager.h>
00037 
00038 #include <ros/package.h>
00039 
00040 #include <tf/transform_listener.h>
00041 
00042 #include <rviz/visualization_manager.h>
00043 #include <rviz/properties/color_property.h>
00044 #include <rviz/properties/float_property.h>
00045 #include <rviz/properties/int_property.h>
00046 #include <rviz/properties/bool_property.h>
00047 #include <rviz/frame_manager.h>
00048 #include "rviz/ogre_helpers/axes.h"
00049 
00050 #include "marker_detection/marker_detection_visual.h"
00051 #include "marker_detection/marker_detection_display.h"
00052 
00053 namespace marker_rviz_plugin {
00054 
00055     MarkerDetectionDisplay::MarkerDetectionDisplay() {
00056 
00057         _showAxesProperty = new rviz::BoolProperty("Show Axes", true, "Show or hide axes.", this, SLOT (updateVisual()));
00058         _showMarkerProperty = new rviz::BoolProperty("Show Marker", true, "Show or hide marker image.", this, SLOT (updateVisual()));
00059         _showLabelProperty = new rviz::BoolProperty("Show Label", true, "Show or hide marker label.", this, SLOT (updateVisual()));
00060         _colourLabelProperty = new rviz::ColorProperty ( "Color Label", QColor ( 170, 170, 170 ), "Color id label", this, SLOT ( updateVisual() ) );
00061         _markerSizeProperty = new rviz::FloatProperty("Marker Size", 0.3, "Size of the marker image.", this, SLOT (updateVisual()));
00062         _markerSizeProperty->setMin(0);
00063 
00064         // Add the plugin media folder to the Ogre ResourceGroup so it is possible to access plugin textures later on
00065         std::string rviz_path = ros::package::getPath(ROS_PACKAGE_NAME);
00066         Ogre::ResourceGroupManager::getSingleton().addResourceLocation(rviz_path + "/media", "FileSystem", ROS_PACKAGE_NAME);
00067         Ogre::ResourceGroupManager::getSingleton().initialiseResourceGroup(ROS_PACKAGE_NAME);
00068 
00069     }
00070 
00071     void MarkerDetectionDisplay::onInitialize() {
00072         MFDClass::onInitialize();
00073 
00074         _visual = new MarkerDetectionVisual(context_->getSceneManager(), scene_node_);
00075     }
00076 
00077     MarkerDetectionDisplay::~MarkerDetectionDisplay() {
00078     }
00079 
00080 // Clear the ogre_visuals by deleting their objects.
00081     void MarkerDetectionDisplay::reset() {
00082         MFDClass::reset();
00083     }
00084 
00085     void MarkerDetectionDisplay::updateVisual() {
00086         _visual->setShowAxes(_showAxesProperty->getBool());
00087         _visual->setShowMarker(_showMarkerProperty->getBool());
00088         _visual->setShowLabel(_showLabelProperty->getBool());
00089         _visual->setColorLabel(_colourLabelProperty->getOgreColor());
00090         _visual->setScale(_markerSizeProperty->getFloat());
00091     }
00092 
00093 // This is our callback to handle an incoming message.
00094     void MarkerDetectionDisplay::processMessage(const marker_msgs::MarkerDetection::ConstPtr &msg) {
00095 
00096         // Here we call the rviz::FrameManager to get the transform from the
00097         // fixed frame to the frame in the header of this Imu message.  If
00098         // it fails, we can't do anything else so we return.
00099         Ogre::Quaternion orientation;
00100         Ogre::Vector3 position;
00101         if (!context_->getFrameManager()->getTransform(msg->header.frame_id, msg->header.stamp, position, orientation)) {
00102             ROS_DEBUG ("Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), qPrintable(fixed_frame_));
00103             return;
00104         }
00105 
00106         // Now set or update the contents of the chosen visual.
00107         _visual->setMessage(msg);
00108         _visual->setFramePosition(position);
00109         _visual->setFrameOrientation(orientation);
00110         _visual->setShowAxes(_showAxesProperty->getBool());
00111         _visual->setShowMarker(_showMarkerProperty->getBool());
00112         _visual->setShowLabel(_showLabelProperty->getBool());
00113         _visual->setScale(_markerSizeProperty->getFloat());
00114 
00115         context_->queueRender();
00116     }
00117 
00118 } // end namespace marker_rviz_plugin
00119 
00120 // Tell pluginlib about this class.  It is important to do this in
00121 // global scope, outside our package's namespace.
00122 #include <pluginlib/class_list_macros.h>
00123 
00124 PLUGINLIB_EXPORT_CLASS (marker_rviz_plugin::MarkerDetectionDisplay, rviz::Display)


marker_rviz_plugin
Author(s): Markus Bader, Lukas Pfeifhofer, Markus Macsek
autogenerated on Wed Nov 9 2016 04:02:20