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
00036 #include "footstep_display.h"
00037 #include <rviz/validate_floats.h>
00038 #include <jsk_topic_tools/color_utils.h>
00039
00040 namespace jsk_rviz_plugins
00041 {
00042 FootstepDisplay::FootstepDisplay()
00043 {
00044 alpha_property_ = new rviz::FloatProperty( "Alpha", 0.5,
00045 "0 is fully transparent, 1.0 is fully opaque.",
00046 this, SLOT( updateAlpha() ));
00047 show_name_property_ = new rviz::BoolProperty(
00048 "Show Name", true,
00049 "Show name of each footstep",
00050 this, SLOT(updateShowName()));
00051 use_group_coloring_property_ = new rviz::BoolProperty(
00052 "Use Group Coloring", false,
00053 "Use footstep_group field to colorize footsteps",
00054 this, SLOT(updateUseGroupColoring()));
00055 width_property_ = new rviz::FloatProperty(
00056 "Width", 0.15,
00057 "width of the footstep, it's not used if the dimensions is specified in Footstep message.",
00058 this, SLOT( updateWidth() ));
00059 height_property_ = new rviz::FloatProperty(
00060 "height", 0.01,
00061 "height of the footstep, it's not used if the dimensions is specified in Footstep message.",
00062 this, SLOT( updateHeight() ));
00063
00064 depth_property_ = new rviz::FloatProperty(
00065 "depth", 0.3,
00066 "depth of the footstep, it's not used if the dimensions is specified in Footstep message.",
00067 this, SLOT( updateDepth() ));
00068 }
00069
00070 FootstepDisplay::~FootstepDisplay()
00071 {
00072 delete alpha_property_;
00073 delete width_property_;
00074 delete height_property_;
00075 delete depth_property_;
00076 delete show_name_property_;
00077 delete use_group_coloring_property_;
00078 delete line_;
00079
00080 for (size_t i = 0; i < text_nodes_.size(); i++) {
00081 Ogre::SceneNode* node = text_nodes_[i];
00082 node->removeAndDestroyAllChildren();
00083 node->detachAllObjects();
00084 scene_manager_->destroySceneNode(node);
00085 }
00086 }
00087
00088 void FootstepDisplay::updateWidth()
00089 {
00090 width_ = width_property_->getFloat();
00091 }
00092
00093 void FootstepDisplay::updateHeight()
00094 {
00095 height_ = height_property_->getFloat();
00096 }
00097
00098 void FootstepDisplay::updateDepth()
00099 {
00100 depth_ = depth_property_->getFloat();
00101 }
00102
00103 void FootstepDisplay::updateAlpha()
00104 {
00105 alpha_ = alpha_property_->getFloat();
00106 }
00107
00108 void FootstepDisplay::updateShowName()
00109 {
00110 show_name_ = show_name_property_->getBool();
00111 }
00112
00113 void FootstepDisplay::updateUseGroupColoring()
00114 {
00115 use_group_coloring_ = use_group_coloring_property_->getBool();
00116 }
00117
00118
00119 void FootstepDisplay::reset()
00120 {
00121 MFDClass::reset();
00122 shapes_.clear();
00123 line_->clear();
00124 allocateTexts(0);
00125 }
00126
00127 bool FootstepDisplay::validateFloats( const jsk_footstep_msgs::FootstepArray& msg )
00128 {
00129 for (std::vector<jsk_footstep_msgs::Footstep>::const_iterator it = msg.footsteps.begin();
00130 it != msg.footsteps.end();
00131 ++it) {
00132 if (!rviz::validateFloats((*it).pose.position.x)
00133 || !rviz::validateFloats((*it).pose.position.y)
00134 || !rviz::validateFloats((*it).pose.position.z)
00135 || !rviz::validateFloats((*it).pose.orientation.x)
00136 || !rviz::validateFloats((*it).pose.orientation.y)
00137 || !rviz::validateFloats((*it).pose.orientation.z)
00138 || !rviz::validateFloats((*it).pose.orientation.w)
00139 ) {
00140 return false;
00141 }
00142 }
00143 return true;
00144 }
00145
00146 void FootstepDisplay::onInitialize()
00147 {
00148 MFDClass::onInitialize();
00149 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00150 line_ = new rviz::BillboardLine(context_->getSceneManager(), scene_node_);
00151 updateShowName();
00152 updateWidth();
00153 updateHeight();
00154 updateDepth();
00155 updateAlpha();
00156 updateUseGroupColoring();
00157 }
00158
00159 void FootstepDisplay::allocateCubes(size_t num) {
00160 if (num > shapes_.size()) {
00161
00162 for (size_t i = shapes_.size(); i < num; i++) {
00163 ShapePtr shape;
00164 shape.reset(new rviz::Shape(rviz::Shape::Cube, context_->getSceneManager(),
00165 scene_node_));
00166 shapes_.push_back(shape);
00167 }
00168 }
00169 else if (num < shapes_.size()) {
00170
00171 shapes_.resize(num);
00172 }
00173 }
00174
00175 void FootstepDisplay::allocateTexts(size_t num) {
00176 if (num > texts_.size()) {
00177
00178 for (size_t i = texts_.size(); i < num; i++) {
00179
00180 Ogre::SceneNode* node = scene_node_->createChildSceneNode();
00181 rviz::MovableText* text
00182 = new rviz::MovableText("not initialized", "Liberation Sans", 0.05);
00183 text->setVisible(false);
00184 text->setTextAlignment(rviz::MovableText::H_CENTER,
00185 rviz::MovableText::V_ABOVE);
00186 node->attachObject(text);
00187 texts_.push_back(text);
00188 text_nodes_.push_back(node);
00189 }
00190 }
00191 else if (num < texts_.size()) {
00192 for (int i = texts_.size() - 1; i >= (int)num; i--) {
00193 Ogre::SceneNode* node = text_nodes_[i];
00194 node->detachAllObjects();
00195 node->removeAndDestroyAllChildren();
00196 scene_manager_->destroySceneNode(node);
00197 }
00198 text_nodes_.resize(num);
00199 texts_.resize(num);
00200
00201 }
00202 }
00203
00204 double FootstepDisplay::minNotZero(double a, double b) {
00205 if (a == 0.0) {
00206 return b;
00207 }
00208 else if (b == 0.0) {
00209 return a;
00210 }
00211 else {
00212 return std::min(a, b);
00213 }
00214 }
00215
00216 void FootstepDisplay::update(float wall_dt, float ros_dt)
00217 {
00218 for (size_t i = 0; i < shapes_.size(); i++) {
00219 ShapePtr shape = shapes_[i];
00220 texts_[i]->setVisible(show_name_);
00221 jsk_footstep_msgs::Footstep footstep = latest_footstep_->footsteps[i];
00222
00223 if (use_group_coloring_) {
00224 std_msgs::ColorRGBA color
00225 = jsk_topic_tools::colorCategory20(footstep.footstep_group);
00226 shape->setColor(color.r, color.g, color.b, alpha_);
00227 }
00228 else {
00229 if (footstep.leg == jsk_footstep_msgs::Footstep::LLEG) {
00230 shape->setColor(0, 1, 0, alpha_);
00231 }
00232 else if (footstep.leg == jsk_footstep_msgs::Footstep::RLEG) {
00233 shape->setColor(1, 0, 0, alpha_);
00234 }
00235 else if (footstep.leg == jsk_footstep_msgs::Footstep::LARM) {
00236 shape->setColor(0, 1, 1, alpha_);
00237 }
00238 else if (footstep.leg == jsk_footstep_msgs::Footstep::RARM) {
00239 shape->setColor(1, 0, 1, alpha_);
00240 }
00241 else {
00242 shape->setColor(1, 1, 1, alpha_);
00243 }
00244 }
00245
00246 }
00247 }
00248
00249 double FootstepDisplay::estimateTextSize(
00250 const jsk_footstep_msgs::Footstep& footstep)
00251 {
00252 if (footstep.dimensions.x == 0 &&
00253 footstep.dimensions.y == 0 &&
00254 footstep.dimensions.z == 0) {
00255 return std::max(minNotZero(minNotZero(footstep.dimensions.x,
00256 footstep.dimensions.y),
00257 footstep.dimensions.z),
00258 0.1);
00259 }
00260 else {
00261 return std::max(minNotZero(minNotZero(depth_property_->getFloat(),
00262 width_property_->getFloat()),
00263 height_property_->getFloat()),
00264 0.1);
00265
00266 }
00267 }
00268
00269
00270 void FootstepDisplay::processMessage(const jsk_footstep_msgs::FootstepArray::ConstPtr& msg)
00271 {
00272 if (!validateFloats(*msg)) {
00273 setStatus(rviz::StatusProperty::Error, "Topic", "message contained invalid floating point values (nans or infs)");
00274 return;
00275 }
00276 latest_footstep_ = msg;
00277 Ogre::Quaternion orientation;
00278 Ogre::Vector3 position;
00279 if(!context_->getFrameManager()->getTransform( msg->header.frame_id,
00280 msg->header.stamp,
00281 position, orientation)) {
00282 std::ostringstream oss;
00283 oss << "Error transforming pose";
00284 oss << " from frame '" << msg->header.frame_id << "'";
00285 oss << " to frame '" << qPrintable(fixed_frame_) << "'";
00286 ROS_ERROR_STREAM(oss.str());
00287 setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
00288 return;
00289 }
00290
00291
00292 allocateCubes(msg->footsteps.size());
00293 allocateTexts(msg->footsteps.size());
00294 line_->clear();
00295 line_->setLineWidth(0.01);
00296 line_->setNumLines(1);
00297 line_->setMaxPointsPerLine(1024);
00298
00299 for (size_t i = 0; i < msg->footsteps.size(); i++)
00300 {
00301 ShapePtr shape = shapes_[i];
00302 rviz::MovableText* text = texts_[i];
00303 Ogre::SceneNode* node = text_nodes_[i];
00304 jsk_footstep_msgs::Footstep footstep = msg->footsteps[i];
00305 Ogre::Vector3 step_position;
00306 Ogre::Vector3 shape_position;
00307 Ogre::Quaternion step_quaternion;
00308 if( !context_->getFrameManager()->transform( msg->header, footstep.pose,
00309 step_position,
00310 step_quaternion ))
00311 {
00312 std::ostringstream oss;
00313 oss << "Error transforming pose";
00314 oss << " from frame '" << msg->header.frame_id << "'";
00315 oss << " to frame '" << qPrintable(fixed_frame_) << "'";
00316 ROS_ERROR_STREAM(oss.str());
00317 setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
00318 return;
00319 }
00320
00321 Ogre::Vector3 step_offset (footstep.offset.x, footstep.offset.y, footstep.offset.z);
00322 shape_position = step_position + (step_quaternion * step_offset);
00323
00324 shape->setPosition(shape_position);
00325 shape->setOrientation(step_quaternion);
00326
00327 Ogre::Vector3 scale;
00328 if (footstep.dimensions.x == 0 &&
00329 footstep.dimensions.y == 0 &&
00330 footstep.dimensions.z == 0) {
00331 scale[0] = depth_;
00332 scale[1] = width_;
00333 scale[2] = height_;
00334 }
00335 else {
00336 scale[0] = footstep.dimensions.x;
00337 scale[1] = footstep.dimensions.y;
00338 scale[2] = footstep.dimensions.z;
00339 }
00340 shape->setScale(scale);
00341
00342 if (footstep.leg == jsk_footstep_msgs::Footstep::LLEG) {
00343 text->setCaption("LLEG");
00344 }
00345 else if (footstep.leg == jsk_footstep_msgs::Footstep::RLEG) {
00346 text->setCaption("RLEG");
00347 }
00348 else if (footstep.leg == jsk_footstep_msgs::Footstep::LARM) {
00349 text->setCaption("LARM");
00350 }
00351 else if (footstep.leg == jsk_footstep_msgs::Footstep::RARM) {
00352 text->setCaption("RARM");
00353 }
00354 else {
00355 text->setCaption("unknown");
00356 }
00357 text->setCharacterHeight(estimateTextSize(footstep));
00358 node->setPosition(shape_position);
00359 node->setOrientation(step_quaternion);
00360 text->setVisible(show_name_);
00361 line_->addPoint(step_position);
00362
00363 }
00364
00365 updateAlpha();
00366 context_->queueRender();
00367 }
00368
00369 }
00370
00371 #include <pluginlib/class_list_macros.h>
00372 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::FootstepDisplay, rviz::Display )