Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <rviz/view_manager.h>
00036 #include <rviz/render_panel.h>
00037 #include <rviz/uniform_string_stream.h>
00038 #include <OGRE/OgreCamera.h>
00039 #include <OGRE/OgreMaterialManager.h>
00040 #include "target_visualizer_display.h"
00041 #include <OGRE/OgreManualObject.h>
00042
00043 namespace jsk_rviz_plugins
00044 {
00045 const float arrow_animation_duration = 1.0;
00046 const double minimum_font_size = 0.2;
00047
00048 TargetVisualizerDisplay::TargetVisualizerDisplay():
00049 message_recieved_(false)
00050 {
00051 target_name_property_ = new rviz::StringProperty(
00052 "target name", "target",
00053 "name of the target",
00054 this, SLOT(updateTargetName())
00055 );
00056 radius_property_ = new rviz::FloatProperty(
00057 "radius", 1.0,
00058 "radius of the target mark",
00059 this, SLOT(updateRadius()));
00060 radius_property_->setMin(0.0);
00061 alpha_property_ = new rviz::FloatProperty(
00062 "alpha", 0.8,
00063 "0 is fully transparent, 1.0 is fully opaque.",
00064 this, SLOT(updateAlpha()));
00065 alpha_property_->setMin(0.0);
00066 alpha_property_->setMax(1.0);
00067 color_property_ = new rviz::ColorProperty(
00068 "color", QColor(25, 255, 240),
00069 "color of the target",
00070 this, SLOT(updateColor()));
00071 shape_type_property_ = new rviz::EnumProperty(
00072 "type", "Simple Circle",
00073 "Shape to display the pose as",
00074 this, SLOT(updateShapeType()));
00075 shape_type_property_->addOption("Simple Circle", SimpleCircle);
00076 shape_type_property_->addOption("Decoreted Circle", GISCircle);
00077 }
00078
00079 TargetVisualizerDisplay::~TargetVisualizerDisplay()
00080 {
00081 delete target_name_property_;
00082 delete alpha_property_;
00083 delete color_property_;
00084 delete radius_property_;
00085 }
00086
00087 void TargetVisualizerDisplay::onEnable()
00088 {
00089 subscribe();
00090 visualizer_->setEnable(false);
00091
00092 }
00093
00094 void TargetVisualizerDisplay::processMessage(
00095 const geometry_msgs::PoseStamped::ConstPtr& msg)
00096 {
00097 boost::mutex::scoped_lock lock(mutex_);
00098 message_recieved_ = true;
00099 visualizer_->setEnable(isEnabled());
00100 if (!isEnabled()) {
00101 return;
00102 }
00103 Ogre::Quaternion orientation;
00104 Ogre::Vector3 position;
00105 if(!context_->getFrameManager()->transform(msg->header,
00106 msg->pose,
00107 position, orientation))
00108 {
00109 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
00110 msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00111 return;
00112 }
00113 visualizer_->setPosition(position);
00114 }
00115
00116
00117 void TargetVisualizerDisplay::update(float wall_dt, float ros_dt)
00118 {
00119 if (!message_recieved_) {
00120 return;
00121 }
00122 visualizer_->setOrientation(context_);
00123 visualizer_->update(wall_dt, ros_dt);
00124 }
00125
00126 void TargetVisualizerDisplay::onInitialize()
00127 {
00128 MFDClass::onInitialize();
00129 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00130
00131 updateRadius();
00132 updateShapeType();
00133
00134
00135
00136 }
00137
00138 void TargetVisualizerDisplay::reset()
00139 {
00140 MFDClass::reset();
00141 message_recieved_ = false;
00142 if (visualizer_) {
00143 visualizer_->setEnable(false);
00144 }
00145 }
00146
00147 void TargetVisualizerDisplay::updateTargetName()
00148 {
00149 boost::mutex::scoped_lock lock(mutex_);
00150 target_name_ = target_name_property_->getStdString();
00151 if (visualizer_) {
00152 visualizer_->setText(target_name_);
00153 }
00154 }
00155
00156 void TargetVisualizerDisplay::updateRadius()
00157 {
00158 boost::mutex::scoped_lock lock(mutex_);
00159 radius_ = radius_property_->getFloat();
00160 if (visualizer_) {
00161 visualizer_->setSize(radius_);
00162 }
00163 }
00164
00165 void TargetVisualizerDisplay::updateAlpha()
00166 {
00167 boost::mutex::scoped_lock lock(mutex_);
00168 alpha_ = alpha_property_->getFloat();
00169 if (visualizer_) {
00170 visualizer_->setAlpha(alpha_);
00171 }
00172 }
00173
00174 void TargetVisualizerDisplay::updateColor()
00175 {
00176 boost::mutex::scoped_lock lock(mutex_);
00177 color_ = color_property_->getColor();
00178 if (visualizer_) {
00179 visualizer_->setColor(color_);
00180 }
00181 }
00182
00183 void TargetVisualizerDisplay::updateShapeType()
00184 {
00185 if (current_type_ != shape_type_property_->getOptionInt()) {
00186 {
00187 boost::mutex::scoped_lock lock(mutex_);
00188 if (shape_type_property_->getOptionInt() == SimpleCircle) {
00189 current_type_ = SimpleCircle;
00190
00191 visualizer_.reset(new SimpleCircleFacingVisualizer(
00192 scene_manager_,
00193 scene_node_,
00194 context_,
00195 radius_));
00196 }
00197 else {
00198 current_type_ = GISCircle;
00199
00200 GISCircleVisualizer* v = new GISCircleVisualizer(
00201 scene_manager_,
00202 scene_node_,
00203 radius_);
00204 v->setAnonymous(false);
00205 visualizer_.reset(v);
00206
00207 }
00208 }
00209 updateTargetName();
00210 updateColor();
00211 updateAlpha();
00212 }
00213 }
00214 }
00215
00216 #include <pluginlib/class_list_macros.h>
00217 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::TargetVisualizerDisplay, rviz::Display )
00218