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
00038 #include <moveit/planning_scene_rviz_plugin/planning_scene_display.h>
00039 #include <moveit/rviz_plugin_render_tools/robot_state_visualization.h>
00040 #include <moveit/rviz_plugin_render_tools/octomap_render.h>
00041
00042 #include <rviz/visualization_manager.h>
00043 #include <rviz/robot/robot.h>
00044 #include <rviz/robot/robot_link.h>
00045
00046 #include <rviz/properties/property.h>
00047 #include <rviz/properties/string_property.h>
00048 #include <rviz/properties/bool_property.h>
00049 #include <rviz/properties/float_property.h>
00050 #include <rviz/properties/ros_topic_property.h>
00051 #include <rviz/properties/color_property.h>
00052 #include <rviz/properties/enum_property.h>
00053 #include <rviz/display_context.h>
00054 #include <rviz/frame_manager.h>
00055 #include <tf/transform_listener.h>
00056
00057 #include <OgreSceneManager.h>
00058 #include <OgreSceneNode.h>
00059
00060 namespace moveit_rviz_plugin
00061 {
00062
00063
00064
00065 PlanningSceneDisplay::PlanningSceneDisplay(bool listen_to_planning_scene, bool show_scene_robot)
00066 : Display(), model_is_loading_(false), planning_scene_needs_render_(true), current_scene_time_(0.0f)
00067 {
00068 move_group_ns_property_ = new rviz::StringProperty("Move Group Namespace", "", "The name of the ROS namespace in "
00069 "which the move_group node is running",
00070 this, SLOT(changedMoveGroupNS()), this);
00071 robot_description_property_ = new rviz::StringProperty(
00072 "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded",
00073 this, SLOT(changedRobotDescription()), this);
00074
00075 if (listen_to_planning_scene)
00076 planning_scene_topic_property_ =
00077 new rviz::RosTopicProperty("Planning Scene Topic", "move_group/monitored_planning_scene",
00078 ros::message_traits::datatype<moveit_msgs::PlanningScene>(),
00079 "The topic on which the moveit_msgs::PlanningScene messages are received", this,
00080 SLOT(changedPlanningSceneTopic()), this);
00081 else
00082 planning_scene_topic_property_ = NULL;
00083
00084
00085 scene_category_ = new rviz::Property("Scene Geometry", QVariant(), "", this);
00086
00087 scene_name_property_ = new rviz::StringProperty("Scene Name", "(noname)", "Shows the name of the planning scene",
00088 scene_category_, SLOT(changedSceneName()), this);
00089 scene_name_property_->setShouldBeSaved(false);
00090 scene_enabled_property_ =
00091 new rviz::BoolProperty("Show Scene Geometry", true, "Indicates whether planning scenes should be displayed",
00092 scene_category_, SLOT(changedSceneEnabled()), this);
00093
00094 scene_alpha_property_ = new rviz::FloatProperty("Scene Alpha", 0.9f, "Specifies the alpha for the scene geometry",
00095 scene_category_, SLOT(changedSceneAlpha()), this);
00096 scene_alpha_property_->setMin(0.0);
00097 scene_alpha_property_->setMax(1.0);
00098
00099 scene_color_property_ = new rviz::ColorProperty(
00100 "Scene Color", QColor(50, 230, 50), "The color for the planning scene obstacles (if a color is not defined)",
00101 scene_category_, SLOT(changedSceneColor()), this);
00102
00103 octree_render_property_ = new rviz::EnumProperty("Voxel Rendering", "Occupied Voxels", "Select voxel type.",
00104 scene_category_, SLOT(changedOctreeRenderMode()), this);
00105
00106 octree_render_property_->addOption("Occupied Voxels", OCTOMAP_OCCUPIED_VOXELS);
00107 octree_render_property_->addOption("Free Voxels", OCTOMAP_FREE_VOXELS);
00108 octree_render_property_->addOption("All Voxels", OCTOMAP_FREE_VOXELS | OCTOMAP_OCCUPIED_VOXELS);
00109
00110 octree_coloring_property_ = new rviz::EnumProperty("Voxel Coloring", "Z-Axis", "Select voxel coloring mode",
00111 scene_category_, SLOT(changedOctreeColorMode()), this);
00112
00113 octree_coloring_property_->addOption("Z-Axis", OCTOMAP_Z_AXIS_COLOR);
00114 octree_coloring_property_->addOption("Cell Probability", OCTOMAP_PROBABLILTY_COLOR);
00115
00116 scene_display_time_property_ =
00117 new rviz::FloatProperty("Scene Display Time", 0.2f, "The amount of wall-time to wait in between rendering "
00118 "updates to the planning scene (if any)",
00119 scene_category_, SLOT(changedSceneDisplayTime()), this);
00120 scene_display_time_property_->setMin(0.0001);
00121
00122 if (show_scene_robot)
00123 {
00124 robot_category_ = new rviz::Property("Scene Robot", QVariant(), "", this);
00125
00126 scene_robot_visual_enabled_property_ = new rviz::BoolProperty(
00127 "Show Robot Visual", true, "Indicates whether the robot state specified by the planning scene should be "
00128 "displayed as defined for visualisation purposes.",
00129 robot_category_, SLOT(changedSceneRobotVisualEnabled()), this);
00130
00131 scene_robot_collision_enabled_property_ = new rviz::BoolProperty(
00132 "Show Robot Collision", false, "Indicates whether the robot state specified by the planning scene should be "
00133 "displayed as defined for collision detection purposes.",
00134 robot_category_, SLOT(changedSceneRobotCollisionEnabled()), this);
00135
00136 robot_alpha_property_ = new rviz::FloatProperty("Robot Alpha", 1.0f, "Specifies the alpha for the robot links",
00137 robot_category_, SLOT(changedRobotSceneAlpha()), this);
00138 robot_alpha_property_->setMin(0.0);
00139 robot_alpha_property_->setMax(1.0);
00140
00141 attached_body_color_property_ =
00142 new rviz::ColorProperty("Attached Body Color", QColor(150, 50, 150), "The color for the attached bodies",
00143 robot_category_, SLOT(changedAttachedBodyColor()), this);
00144 }
00145 else
00146 {
00147 robot_category_ = NULL;
00148 scene_robot_visual_enabled_property_ = NULL;
00149 scene_robot_collision_enabled_property_ = NULL;
00150 robot_alpha_property_ = NULL;
00151 attached_body_color_property_ = NULL;
00152 }
00153 }
00154
00155
00156
00157
00158 PlanningSceneDisplay::~PlanningSceneDisplay()
00159 {
00160 clearJobs();
00161
00162 planning_scene_render_.reset();
00163 if (context_ && context_->getSceneManager() && planning_scene_node_)
00164 context_->getSceneManager()->destroySceneNode(planning_scene_node_->getName());
00165 if (planning_scene_robot_)
00166 planning_scene_robot_.reset();
00167 planning_scene_monitor_.reset();
00168 }
00169
00170 void PlanningSceneDisplay::clearJobs()
00171 {
00172 background_process_.clear();
00173 {
00174 boost::unique_lock<boost::mutex> ulock(main_loop_jobs_lock_);
00175 main_loop_jobs_.clear();
00176 }
00177 }
00178
00179 void PlanningSceneDisplay::onInitialize()
00180 {
00181 Display::onInitialize();
00182
00183
00184 planning_scene_node_ = scene_node_->createChildSceneNode();
00185
00186 if (robot_category_)
00187 {
00188 planning_scene_robot_.reset(
00189 new RobotStateVisualization(planning_scene_node_, context_, "Planning Scene", robot_category_));
00190 planning_scene_robot_->setVisible(true);
00191 planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
00192 planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
00193 changedRobotSceneAlpha();
00194 changedAttachedBodyColor();
00195 }
00196 }
00197
00198 void PlanningSceneDisplay::reset()
00199 {
00200 planning_scene_render_.reset();
00201 if (planning_scene_robot_)
00202 planning_scene_robot_->clear();
00203
00204 addBackgroundJob(boost::bind(&PlanningSceneDisplay::loadRobotModel, this), "loadRobotModel");
00205 Display::reset();
00206
00207 if (planning_scene_robot_)
00208 {
00209 planning_scene_robot_->setVisible(true);
00210 planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
00211 planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
00212 }
00213 }
00214
00215 void PlanningSceneDisplay::addBackgroundJob(const boost::function<void()>& job, const std::string& name)
00216 {
00217 background_process_.addJob(job, name);
00218 }
00219
00220 void PlanningSceneDisplay::spawnBackgroundJob(const boost::function<void()>& job)
00221 {
00222 boost::thread t(job);
00223 }
00224
00225 void PlanningSceneDisplay::addMainLoopJob(const boost::function<void()>& job)
00226 {
00227 boost::unique_lock<boost::mutex> ulock(main_loop_jobs_lock_);
00228 main_loop_jobs_.push_back(job);
00229 }
00230
00231 void PlanningSceneDisplay::waitForAllMainLoopJobs()
00232 {
00233 boost::unique_lock<boost::mutex> ulock(main_loop_jobs_lock_);
00234 while (!main_loop_jobs_.empty())
00235 main_loop_jobs_empty_condition_.wait(ulock);
00236 }
00237
00238 void PlanningSceneDisplay::executeMainLoopJobs()
00239 {
00240 main_loop_jobs_lock_.lock();
00241 while (!main_loop_jobs_.empty())
00242 {
00243 boost::function<void()> fn = main_loop_jobs_.front();
00244 main_loop_jobs_.pop_front();
00245 main_loop_jobs_lock_.unlock();
00246 try
00247 {
00248 fn();
00249 }
00250 catch (std::runtime_error& ex)
00251 {
00252 ROS_ERROR("Exception caught executing main loop job: %s", ex.what());
00253 }
00254 catch (...)
00255 {
00256 ROS_ERROR("Exception caught executing main loop job");
00257 }
00258 main_loop_jobs_lock_.lock();
00259 }
00260 main_loop_jobs_empty_condition_.notify_all();
00261 main_loop_jobs_lock_.unlock();
00262 }
00263
00264 const planning_scene_monitor::PlanningSceneMonitorPtr& PlanningSceneDisplay::getPlanningSceneMonitor()
00265 {
00266 return planning_scene_monitor_;
00267 }
00268
00269 const std::string PlanningSceneDisplay::getMoveGroupNS() const
00270 {
00271 return move_group_ns_property_->getStdString();
00272 }
00273
00274 const robot_model::RobotModelConstPtr& PlanningSceneDisplay::getRobotModel() const
00275 {
00276 if (planning_scene_monitor_)
00277 return planning_scene_monitor_->getRobotModel();
00278 else
00279 {
00280 static robot_model::RobotModelConstPtr empty;
00281 return empty;
00282 }
00283 }
00284
00285 planning_scene_monitor::LockedPlanningSceneRO PlanningSceneDisplay::getPlanningSceneRO() const
00286 {
00287 return planning_scene_monitor::LockedPlanningSceneRO(planning_scene_monitor_);
00288 }
00289
00290 planning_scene_monitor::LockedPlanningSceneRW PlanningSceneDisplay::getPlanningSceneRW()
00291 {
00292 return planning_scene_monitor::LockedPlanningSceneRW(planning_scene_monitor_);
00293 }
00294
00295 void PlanningSceneDisplay::changedAttachedBodyColor()
00296 {
00297 queueRenderSceneGeometry();
00298 }
00299
00300 void PlanningSceneDisplay::changedSceneColor()
00301 {
00302 queueRenderSceneGeometry();
00303 }
00304
00305 void PlanningSceneDisplay::changedMoveGroupNS()
00306 {
00307 if (isEnabled())
00308 reset();
00309 }
00310
00311 void PlanningSceneDisplay::changedRobotDescription()
00312 {
00313 if (isEnabled())
00314 reset();
00315 }
00316
00317 void PlanningSceneDisplay::changedSceneName()
00318 {
00319 planning_scene_monitor::LockedPlanningSceneRW ps = getPlanningSceneRW();
00320 if (ps)
00321 ps->setName(scene_name_property_->getStdString());
00322 }
00323
00324 void PlanningSceneDisplay::renderPlanningScene()
00325 {
00326 if (planning_scene_render_ && planning_scene_needs_render_)
00327 {
00328 QColor color = scene_color_property_->getColor();
00329 rviz::Color env_color(color.redF(), color.greenF(), color.blueF());
00330 if (attached_body_color_property_)
00331 color = attached_body_color_property_->getColor();
00332 rviz::Color attached_color(color.redF(), color.greenF(), color.blueF());
00333
00334 try
00335 {
00336 const planning_scene_monitor::LockedPlanningSceneRO& ps = getPlanningSceneRO();
00337 planning_scene_render_->renderPlanningScene(
00338 ps, env_color, attached_color, static_cast<OctreeVoxelRenderMode>(octree_render_property_->getOptionInt()),
00339 static_cast<OctreeVoxelColorMode>(octree_coloring_property_->getOptionInt()),
00340 scene_alpha_property_->getFloat());
00341 }
00342 catch (...)
00343 {
00344 ROS_ERROR("Exception thrown while rendering planning scene");
00345 }
00346 planning_scene_needs_render_ = false;
00347 planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
00348 }
00349 }
00350
00351 void PlanningSceneDisplay::changedSceneAlpha()
00352 {
00353 queueRenderSceneGeometry();
00354 }
00355
00356 void PlanningSceneDisplay::changedRobotSceneAlpha()
00357 {
00358 if (planning_scene_robot_)
00359 {
00360 planning_scene_robot_->setAlpha(robot_alpha_property_->getFloat());
00361 queueRenderSceneGeometry();
00362 }
00363 }
00364
00365 void PlanningSceneDisplay::changedPlanningSceneTopic()
00366 {
00367 if (planning_scene_monitor_ && planning_scene_topic_property_)
00368 {
00369 planning_scene_monitor_->startSceneMonitor(planning_scene_topic_property_->getStdString());
00370 std::string service_name = planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_SERVICE;
00371 if (!getMoveGroupNS().empty())
00372 service_name = ros::names::append(getMoveGroupNS(), service_name);
00373 planning_scene_monitor_->requestPlanningSceneState(service_name);
00374 }
00375 }
00376
00377 void PlanningSceneDisplay::changedSceneDisplayTime()
00378 {
00379 }
00380
00381 void PlanningSceneDisplay::changedOctreeRenderMode()
00382 {
00383 }
00384
00385 void PlanningSceneDisplay::changedOctreeColorMode()
00386 {
00387 }
00388
00389 void PlanningSceneDisplay::changedSceneRobotVisualEnabled()
00390 {
00391 if (isEnabled() && planning_scene_robot_)
00392 {
00393 planning_scene_robot_->setVisible(true);
00394 planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
00395 }
00396 }
00397
00398 void PlanningSceneDisplay::changedSceneRobotCollisionEnabled()
00399 {
00400 if (isEnabled() && planning_scene_robot_)
00401 {
00402 planning_scene_robot_->setVisible(true);
00403 planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
00404 }
00405 }
00406
00407 void PlanningSceneDisplay::changedSceneEnabled()
00408 {
00409 if (planning_scene_render_)
00410 planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
00411 }
00412
00413 void PlanningSceneDisplay::setGroupColor(rviz::Robot* robot, const std::string& group_name, const QColor& color)
00414 {
00415 if (getRobotModel())
00416 {
00417 const robot_model::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(group_name);
00418 if (jmg)
00419 {
00420 const std::vector<std::string>& links = jmg->getLinkModelNamesWithCollisionGeometry();
00421 for (std::size_t i = 0; i < links.size(); ++i)
00422 setLinkColor(robot, links[i], color);
00423 }
00424 }
00425 }
00426
00427 void PlanningSceneDisplay::unsetAllColors(rviz::Robot* robot)
00428 {
00429 if (getRobotModel())
00430 {
00431 const std::vector<std::string>& links = getRobotModel()->getLinkModelNamesWithCollisionGeometry();
00432 for (std::size_t i = 0; i < links.size(); ++i)
00433 unsetLinkColor(robot, links[i]);
00434 }
00435 }
00436
00437 void PlanningSceneDisplay::unsetGroupColor(rviz::Robot* robot, const std::string& group_name)
00438 {
00439 if (getRobotModel())
00440 {
00441 const robot_model::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(group_name);
00442 if (jmg)
00443 {
00444 const std::vector<std::string>& links = jmg->getLinkModelNamesWithCollisionGeometry();
00445 for (std::size_t i = 0; i < links.size(); ++i)
00446 unsetLinkColor(robot, links[i]);
00447 }
00448 }
00449 }
00450
00451 void PlanningSceneDisplay::setLinkColor(const std::string& link_name, const QColor& color)
00452 {
00453 if (planning_scene_robot_)
00454 setLinkColor(&planning_scene_robot_->getRobot(), link_name, color);
00455 }
00456
00457 void PlanningSceneDisplay::unsetLinkColor(const std::string& link_name)
00458 {
00459 if (planning_scene_robot_)
00460 unsetLinkColor(&planning_scene_robot_->getRobot(), link_name);
00461 }
00462
00463 void PlanningSceneDisplay::setLinkColor(rviz::Robot* robot, const std::string& link_name, const QColor& color)
00464 {
00465 rviz::RobotLink* link = robot->getLink(link_name);
00466
00467
00468 if (link)
00469 link->setColor(color.redF(), color.greenF(), color.blueF());
00470 }
00471
00472 void PlanningSceneDisplay::unsetLinkColor(rviz::Robot* robot, const std::string& link_name)
00473 {
00474 rviz::RobotLink* link = robot->getLink(link_name);
00475
00476
00477 if (link)
00478 link->unsetColor();
00479 }
00480
00481
00482
00483
00484 planning_scene_monitor::PlanningSceneMonitorPtr PlanningSceneDisplay::createPlanningSceneMonitor()
00485 {
00486 return planning_scene_monitor::PlanningSceneMonitorPtr(new planning_scene_monitor::PlanningSceneMonitor(
00487 robot_description_property_->getStdString(), context_->getFrameManager()->getTFClientPtr(),
00488 getNameStd() + "_planning_scene_monitor"));
00489 }
00490
00491 void PlanningSceneDisplay::clearRobotModel()
00492 {
00493 planning_scene_render_.reset();
00494 planning_scene_monitor_.reset();
00495
00496 }
00497
00498 void PlanningSceneDisplay::loadRobotModel()
00499 {
00500
00501 boost::mutex::scoped_lock _(robot_model_loading_lock_);
00502 model_is_loading_ = true;
00503
00504
00505
00506
00507 addMainLoopJob(boost::bind(&PlanningSceneDisplay::clearRobotModel, this));
00508
00509 waitForAllMainLoopJobs();
00510
00511 planning_scene_monitor::PlanningSceneMonitorPtr psm = createPlanningSceneMonitor();
00512 if (psm->getPlanningScene())
00513 {
00514 planning_scene_monitor_.swap(psm);
00515 addMainLoopJob(boost::bind(&PlanningSceneDisplay::onRobotModelLoaded, this));
00516 setStatus(rviz::StatusProperty::Ok, "PlanningScene", "Planning Scene Loaded Successfully");
00517 waitForAllMainLoopJobs();
00518 }
00519 else
00520 {
00521 setStatus(rviz::StatusProperty::Error, "PlanningScene", "No Planning Scene Loaded");
00522 }
00523
00524 if (planning_scene_monitor_)
00525 planning_scene_monitor_->addUpdateCallback(
00526 boost::bind(&PlanningSceneDisplay::sceneMonitorReceivedUpdate, this, _1));
00527
00528 model_is_loading_ = false;
00529 }
00530
00531 void PlanningSceneDisplay::onRobotModelLoaded()
00532 {
00533 changedPlanningSceneTopic();
00534 planning_scene_render_.reset(new PlanningSceneRender(planning_scene_node_, context_, planning_scene_robot_));
00535 planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
00536
00537 const planning_scene_monitor::LockedPlanningSceneRO& ps = getPlanningSceneRO();
00538 if (planning_scene_robot_)
00539 {
00540 planning_scene_robot_->load(*getRobotModel()->getURDF());
00541 robot_state::RobotState* rs = new robot_state::RobotState(ps->getCurrentState());
00542 rs->update();
00543 planning_scene_robot_->update(robot_state::RobotStateConstPtr(rs));
00544 }
00545
00546 bool oldState = scene_name_property_->blockSignals(true);
00547 scene_name_property_->setStdString(ps->getName());
00548 scene_name_property_->blockSignals(oldState);
00549 }
00550
00551 void PlanningSceneDisplay::sceneMonitorReceivedUpdate(
00552 planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
00553 {
00554 onSceneMonitorReceivedUpdate(update_type);
00555 }
00556
00557 void PlanningSceneDisplay::onSceneMonitorReceivedUpdate(
00558 planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
00559 {
00560 bool oldState = scene_name_property_->blockSignals(true);
00561 getPlanningSceneRW()->getCurrentStateNonConst().update();
00562 scene_name_property_->setStdString(getPlanningSceneRO()->getName());
00563 scene_name_property_->blockSignals(oldState);
00564
00565 planning_scene_needs_render_ = true;
00566 }
00567
00568 void PlanningSceneDisplay::onEnable()
00569 {
00570 Display::onEnable();
00571
00572 addBackgroundJob(boost::bind(&PlanningSceneDisplay::loadRobotModel, this), "loadRobotModel");
00573
00574 if (planning_scene_robot_)
00575 {
00576 planning_scene_robot_->setVisible(true);
00577 planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
00578 planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
00579 }
00580 if (planning_scene_render_)
00581 planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
00582
00583 calculateOffsetPosition();
00584 }
00585
00586
00587
00588
00589 void PlanningSceneDisplay::onDisable()
00590 {
00591 if (planning_scene_monitor_)
00592 {
00593 planning_scene_monitor_->stopSceneMonitor();
00594 if (planning_scene_render_)
00595 planning_scene_render_->getGeometryNode()->setVisible(false);
00596 }
00597 if (planning_scene_robot_)
00598 planning_scene_robot_->setVisible(false);
00599 Display::onDisable();
00600 }
00601
00602 void PlanningSceneDisplay::queueRenderSceneGeometry()
00603 {
00604 planning_scene_needs_render_ = true;
00605 }
00606
00607 void PlanningSceneDisplay::update(float wall_dt, float ros_dt)
00608 {
00609 Display::update(wall_dt, ros_dt);
00610
00611 executeMainLoopJobs();
00612
00613 if (planning_scene_monitor_)
00614 updateInternal(wall_dt, ros_dt);
00615 }
00616
00617 void PlanningSceneDisplay::updateInternal(float wall_dt, float ros_dt)
00618 {
00619 current_scene_time_ += wall_dt;
00620 if (current_scene_time_ > scene_display_time_property_->getFloat())
00621 {
00622 renderPlanningScene();
00623 calculateOffsetPosition();
00624 current_scene_time_ = 0.0f;
00625 }
00626 }
00627
00628 void PlanningSceneDisplay::load(const rviz::Config& config)
00629 {
00630 Display::load(config);
00631 }
00632
00633 void PlanningSceneDisplay::save(rviz::Config config) const
00634 {
00635 Display::save(config);
00636 }
00637
00638
00639
00640
00641 void PlanningSceneDisplay::calculateOffsetPosition()
00642 {
00643 if (!getRobotModel())
00644 return;
00645
00646 Ogre::Vector3 position;
00647 Ogre::Quaternion orientation;
00648
00649 context_->getFrameManager()->getTransform(getRobotModel()->getModelFrame(), ros::Time(0), position, orientation);
00650
00651 planning_scene_node_->setPosition(position);
00652 planning_scene_node_->setOrientation(orientation);
00653 }
00654
00655 void PlanningSceneDisplay::fixedFrameChanged()
00656 {
00657 Display::fixedFrameChanged();
00658 calculateOffsetPosition();
00659 }
00660
00661 }