00001 /* 00002 * Copyright (C) 2016, Bielefeld University, CITEC 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 * Author: Robert Haschke <rhaschke@techfak.uni-bielefeld.de> 00030 */ 00031 00032 #pragma once 00033 00034 #include <rviz/display.h> 00035 #include <ros/ros.h> 00036 #include <visualization_msgs/InteractiveMarker.h> 00037 #include <visualization_msgs/InteractiveMarkerFeedback.h> 00038 #include <geometry_msgs/PoseStamped.h> 00039 00040 // forward declarations of classes 00041 namespace rviz 00042 { 00043 class Property; 00044 class StringProperty; 00045 class BoolProperty; 00046 class FloatProperty; 00047 class VectorProperty; 00048 class TfFrameProperty; 00049 class EnumProperty; 00050 00051 class InteractiveMarker; 00052 } 00053 00054 class TransformBroadcaster; 00055 00056 namespace agni_tf_tools 00057 { 00058 // needed because rviz::InteractiveMarker::statusUpdate is declared without rviz namespace 00059 using rviz::StatusProperty; 00060 00061 class RotationProperty; 00062 00063 class TransformPublisherDisplay : public rviz::Display 00064 { 00065 Q_OBJECT 00066 00067 public: 00068 TransformPublisherDisplay(); 00069 ~TransformPublisherDisplay(); 00070 00071 void reset(); 00072 00073 protected: 00074 void onInitialize(); 00075 void onEnable(); 00076 void onDisable(); 00077 void update(float wall_dt, float ros_dt); 00078 00079 void addFrameControls(visualization_msgs::InteractiveMarker &im, double scale, bool interactive); 00080 void add6DOFControls(visualization_msgs::InteractiveMarker &im); 00081 bool createInteractiveMarker(int type); 00082 bool fillPoseStamped(std_msgs::Header &header, geometry_msgs::Pose &pose); 00083 00084 protected Q_SLOTS: 00085 void setStatus(int level, const QString &name, const QString &text); 00086 void setStatusStd(StatusProperty::Level, const std::string &name, const std::string &text); 00087 void onRefFrameChanged(); 00088 void onAdaptTransformChanged(); 00089 void onFramesChanged(); 00090 void onTransformChanged(); 00091 void onMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback); 00092 void onBroadcastEnableChanged(); 00093 void onMarkerTypeChanged(); 00094 void onMarkerScaleChanged(); 00095 00096 private: 00097 // properties 00098 rviz::VectorProperty *translation_property_; 00099 RotationProperty *rotation_property_; 00100 rviz::BoolProperty *broadcast_property_; 00101 rviz::TfFrameProperty *parent_frame_property_; 00102 rviz::BoolProperty *adapt_transform_property_; 00103 std::string prev_parent_frame_; 00104 rviz::TfFrameProperty *child_frame_property_; 00105 rviz::EnumProperty *marker_property_; 00106 rviz::FloatProperty *marker_scale_property_; 00107 00108 // tf publisher 00109 TransformBroadcaster *tf_pub_; 00110 00111 // interactive marker stuff 00112 boost::shared_ptr<rviz::InteractiveMarker> imarker_; 00113 Ogre::SceneNode *marker_node_; 00114 bool ignore_updates_ ; 00115 }; 00116 00117 } // namespace rviz_cbf_plugin