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
00037 #include <moveit/robot_state_rviz_plugin/robot_state_display.h>
00038 #include <moveit/robot_state/conversions.h>
00039
00040 #include <rviz/visualization_manager.h>
00041 #include <rviz/robot/robot.h>
00042 #include <rviz/robot/robot_link.h>
00043
00044 #include <rviz/properties/property.h>
00045 #include <rviz/properties/string_property.h>
00046 #include <rviz/properties/bool_property.h>
00047 #include <rviz/properties/float_property.h>
00048 #include <rviz/properties/ros_topic_property.h>
00049 #include <rviz/properties/color_property.h>
00050 #include <rviz/display_context.h>
00051 #include <rviz/frame_manager.h>
00052 #include <tf/transform_listener.h>
00053
00054 #include <OgreSceneManager.h>
00055 #include <OgreSceneNode.h>
00056
00057 namespace moveit_rviz_plugin
00058 {
00059
00060
00061
00062 RobotStateDisplay::RobotStateDisplay() : Display(), update_state_(false)
00063 {
00064 robot_description_property_ = new rviz::StringProperty(
00065 "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded",
00066 this, SLOT(changedRobotDescription()), this);
00067
00068 robot_state_topic_property_ = new rviz::RosTopicProperty(
00069 "Robot State Topic", "display_robot_state", ros::message_traits::datatype<moveit_msgs::DisplayRobotState>(),
00070 "The topic on which the moveit_msgs::RobotState messages are received", this, SLOT(changedRobotStateTopic()),
00071 this);
00072
00073
00074 root_link_name_property_ =
00075 new rviz::StringProperty("Robot Root Link", "", "Shows the name of the root link for the robot model", this,
00076 SLOT(changedRootLinkName()), this);
00077 root_link_name_property_->setReadOnly(true);
00078
00079 robot_alpha_property_ = new rviz::FloatProperty("Robot Alpha", 1.0f, "Specifies the alpha for the robot links", this,
00080 SLOT(changedRobotSceneAlpha()), this);
00081 robot_alpha_property_->setMin(0.0);
00082 robot_alpha_property_->setMax(1.0);
00083
00084 attached_body_color_property_ =
00085 new rviz::ColorProperty("Attached Body Color", QColor(150, 50, 150), "The color for the attached bodies", this,
00086 SLOT(changedAttachedBodyColor()), this);
00087
00088 enable_link_highlight_ =
00089 new rviz::BoolProperty("Show Highlights", true, "Specifies whether link highlighting is enabled", this,
00090 SLOT(changedEnableLinkHighlight()), this);
00091 enable_visual_visible_ =
00092 new rviz::BoolProperty("Visual Enabled", true, "Whether to display the visual representation of the robot.", this,
00093 SLOT(changedEnableVisualVisible()), this);
00094 enable_collision_visible_ = new rviz::BoolProperty("Collision Enabled", false,
00095 "Whether to display the collision representation of the robot.",
00096 this, SLOT(changedEnableCollisionVisible()), this);
00097
00098 show_all_links_ = new rviz::BoolProperty("Show All Links", true, "Toggle all links visibility on or off.", this,
00099 SLOT(changedAllLinks()), this);
00100 }
00101
00102
00103
00104
00105 RobotStateDisplay::~RobotStateDisplay()
00106 {
00107 }
00108
00109 void RobotStateDisplay::onInitialize()
00110 {
00111 Display::onInitialize();
00112 robot_.reset(new RobotStateVisualization(scene_node_, context_, "Robot State", this));
00113 changedEnableVisualVisible();
00114 changedEnableCollisionVisible();
00115 robot_->setVisible(false);
00116 }
00117
00118 void RobotStateDisplay::reset()
00119 {
00120 robot_->clear();
00121 rdf_loader_.reset();
00122
00123 loadRobotModel();
00124 Display::reset();
00125
00126 changedEnableVisualVisible();
00127 changedEnableCollisionVisible();
00128 robot_->setVisible(true);
00129 }
00130
00131 void RobotStateDisplay::changedAllLinks()
00132 {
00133 Property* links_prop = subProp("Links");
00134 QVariant value(show_all_links_->getBool());
00135
00136 for (int i = 0; i < links_prop->numChildren(); ++i)
00137 {
00138 Property* link_prop = links_prop->childAt(i);
00139 link_prop->setValue(value);
00140 }
00141 }
00142
00143 void RobotStateDisplay::setHighlight(const std::string& link_name, const std_msgs::ColorRGBA& color)
00144 {
00145 rviz::RobotLink* link = robot_->getRobot().getLink(link_name);
00146 if (link)
00147 {
00148 link->setColor(color.r, color.g, color.b);
00149 link->setRobotAlpha(color.a * robot_alpha_property_->getFloat());
00150 }
00151 }
00152
00153 void RobotStateDisplay::unsetHighlight(const std::string& link_name)
00154 {
00155 rviz::RobotLink* link = robot_->getRobot().getLink(link_name);
00156 if (link)
00157 {
00158 link->unsetColor();
00159 link->setRobotAlpha(robot_alpha_property_->getFloat());
00160 }
00161 }
00162
00163 void RobotStateDisplay::changedEnableLinkHighlight()
00164 {
00165 if (enable_link_highlight_->getBool())
00166 {
00167 for (std::map<std::string, std_msgs::ColorRGBA>::iterator it = highlights_.begin(); it != highlights_.end(); ++it)
00168 {
00169 setHighlight(it->first, it->second);
00170 }
00171 }
00172 else
00173 {
00174 for (std::map<std::string, std_msgs::ColorRGBA>::iterator it = highlights_.begin(); it != highlights_.end(); ++it)
00175 {
00176 unsetHighlight(it->first);
00177 }
00178 }
00179 }
00180
00181 void RobotStateDisplay::changedEnableVisualVisible()
00182 {
00183 robot_->setVisualVisible(enable_visual_visible_->getBool());
00184 }
00185
00186 void RobotStateDisplay::changedEnableCollisionVisible()
00187 {
00188 robot_->setCollisionVisible(enable_collision_visible_->getBool());
00189 }
00190
00191 static bool operator!=(const std_msgs::ColorRGBA& a, const std_msgs::ColorRGBA& b)
00192 {
00193 return a.r != b.r || a.g != b.g || a.b != b.b || a.a != b.a;
00194 }
00195
00196 void RobotStateDisplay::setRobotHighlights(const moveit_msgs::DisplayRobotState::_highlight_links_type& highlight_links)
00197 {
00198 if (highlight_links.empty() && highlights_.empty())
00199 return;
00200
00201 std::map<std::string, std_msgs::ColorRGBA> highlights;
00202 for (moveit_msgs::DisplayRobotState::_highlight_links_type::const_iterator it = highlight_links.begin();
00203 it != highlight_links.end(); ++it)
00204 {
00205 highlights[it->id] = it->color;
00206 }
00207
00208 if (enable_link_highlight_->getBool())
00209 {
00210 std::map<std::string, std_msgs::ColorRGBA>::iterator ho = highlights_.begin();
00211 std::map<std::string, std_msgs::ColorRGBA>::iterator hn = highlights.begin();
00212 while (ho != highlights_.end() || hn != highlights.end())
00213 {
00214 if (ho == highlights_.end())
00215 {
00216 setHighlight(hn->first, hn->second);
00217 ++hn;
00218 }
00219 else if (hn == highlights.end())
00220 {
00221 unsetHighlight(ho->first);
00222 ++ho;
00223 }
00224 else if (hn->first < ho->first)
00225 {
00226 setHighlight(hn->first, hn->second);
00227 ++hn;
00228 }
00229 else if (hn->first > ho->first)
00230 {
00231 unsetHighlight(ho->first);
00232 ++ho;
00233 }
00234 else if (hn->second != ho->second)
00235 {
00236 setHighlight(hn->first, hn->second);
00237 ++ho;
00238 ++hn;
00239 }
00240 else
00241 {
00242 ++ho;
00243 ++hn;
00244 }
00245 }
00246 }
00247
00248 swap(highlights, highlights_);
00249 }
00250
00251 void RobotStateDisplay::changedAttachedBodyColor()
00252 {
00253 if (robot_)
00254 {
00255 QColor color = attached_body_color_property_->getColor();
00256 std_msgs::ColorRGBA color_msg;
00257 color_msg.r = color.redF();
00258 color_msg.g = color.greenF();
00259 color_msg.b = color.blueF();
00260 color_msg.a = robot_alpha_property_->getFloat();
00261 robot_->setDefaultAttachedObjectColor(color_msg);
00262 update_state_ = true;
00263 }
00264 }
00265
00266 void RobotStateDisplay::changedRobotDescription()
00267 {
00268 if (isEnabled())
00269 reset();
00270 }
00271
00272 void RobotStateDisplay::changedRootLinkName()
00273 {
00274 }
00275
00276 void RobotStateDisplay::changedRobotSceneAlpha()
00277 {
00278 if (robot_)
00279 {
00280 robot_->setAlpha(robot_alpha_property_->getFloat());
00281 QColor color = attached_body_color_property_->getColor();
00282 std_msgs::ColorRGBA color_msg;
00283 color_msg.r = color.redF();
00284 color_msg.g = color.greenF();
00285 color_msg.b = color.blueF();
00286 color_msg.a = robot_alpha_property_->getFloat();
00287 robot_->setDefaultAttachedObjectColor(color_msg);
00288 update_state_ = true;
00289 }
00290 }
00291
00292 void RobotStateDisplay::changedRobotStateTopic()
00293 {
00294 robot_state_subscriber_.shutdown();
00295
00296
00297 if (static_cast<bool>(kstate_))
00298 kstate_->setToDefaultValues();
00299 update_state_ = true;
00300
00301 robot_state_subscriber_ = root_nh_.subscribe(robot_state_topic_property_->getStdString(), 10,
00302 &RobotStateDisplay::newRobotStateCallback, this);
00303 }
00304
00305 void RobotStateDisplay::newRobotStateCallback(const moveit_msgs::DisplayRobotStateConstPtr& state_msg)
00306 {
00307 if (!kmodel_)
00308 return;
00309 if (!kstate_)
00310 kstate_.reset(new robot_state::RobotState(kmodel_));
00311
00312 robot_state::robotStateMsgToRobotState(state_msg->state, *kstate_);
00313 setRobotHighlights(state_msg->highlight_links);
00314 update_state_ = true;
00315 }
00316
00317 void RobotStateDisplay::setLinkColor(const std::string& link_name, const QColor& color)
00318 {
00319 setLinkColor(&robot_->getRobot(), link_name, color);
00320 }
00321
00322 void RobotStateDisplay::unsetLinkColor(const std::string& link_name)
00323 {
00324 unsetLinkColor(&robot_->getRobot(), link_name);
00325 }
00326
00327 void RobotStateDisplay::setLinkColor(rviz::Robot* robot, const std::string& link_name, const QColor& color)
00328 {
00329 rviz::RobotLink* link = robot->getLink(link_name);
00330
00331
00332 if (link)
00333 link->setColor(color.redF(), color.greenF(), color.blueF());
00334 }
00335
00336 void RobotStateDisplay::unsetLinkColor(rviz::Robot* robot, const std::string& link_name)
00337 {
00338 rviz::RobotLink* link = robot->getLink(link_name);
00339
00340
00341 if (link)
00342 link->unsetColor();
00343 }
00344
00345
00346
00347
00348 void RobotStateDisplay::loadRobotModel()
00349 {
00350 if (!rdf_loader_)
00351 rdf_loader_.reset(new rdf_loader::RDFLoader(robot_description_property_->getStdString()));
00352
00353 if (rdf_loader_->getURDF())
00354 {
00355 const boost::shared_ptr<srdf::Model>& srdf =
00356 rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : boost::shared_ptr<srdf::Model>(new srdf::Model());
00357 kmodel_.reset(new robot_model::RobotModel(rdf_loader_->getURDF(), srdf));
00358 robot_->load(*kmodel_->getURDF());
00359 kstate_.reset(new robot_state::RobotState(kmodel_));
00360 kstate_->setToDefaultValues();
00361 bool oldState = root_link_name_property_->blockSignals(true);
00362 root_link_name_property_->setStdString(getRobotModel()->getRootLinkName());
00363 root_link_name_property_->blockSignals(oldState);
00364 update_state_ = true;
00365 setStatus(rviz::StatusProperty::Ok, "RobotState", "Planning Model Loaded Successfully");
00366 }
00367 else
00368 setStatus(rviz::StatusProperty::Error, "RobotState", "No Planning Model Loaded");
00369
00370 highlights_.clear();
00371 }
00372
00373 void RobotStateDisplay::onEnable()
00374 {
00375 Display::onEnable();
00376 loadRobotModel();
00377 if (robot_)
00378 {
00379 changedEnableVisualVisible();
00380 changedEnableCollisionVisible();
00381 robot_->setVisible(true);
00382 }
00383 calculateOffsetPosition();
00384 changedRobotStateTopic();
00385 }
00386
00387
00388
00389
00390 void RobotStateDisplay::onDisable()
00391 {
00392 robot_state_subscriber_.shutdown();
00393 if (robot_)
00394 robot_->setVisible(false);
00395 Display::onDisable();
00396 }
00397
00398 void RobotStateDisplay::update(float wall_dt, float ros_dt)
00399 {
00400 Display::update(wall_dt, ros_dt);
00401 calculateOffsetPosition();
00402 if (robot_ && update_state_)
00403 {
00404 update_state_ = false;
00405 kstate_->update();
00406 robot_->update(kstate_);
00407 }
00408 }
00409
00410
00411
00412
00413 void RobotStateDisplay::calculateOffsetPosition()
00414 {
00415 if (!getRobotModel())
00416 return;
00417
00418 Ogre::Vector3 position;
00419 Ogre::Quaternion orientation;
00420
00421 context_->getFrameManager()->getTransform(getRobotModel()->getModelFrame(), ros::Time(0), position, orientation);
00422
00423 scene_node_->setPosition(position);
00424 scene_node_->setOrientation(orientation);
00425 }
00426
00427 void RobotStateDisplay::fixedFrameChanged()
00428 {
00429 Display::fixedFrameChanged();
00430 calculateOffsetPosition();
00431 }
00432
00433 }