void InteractiveMarkerDisplay::onInitialize() { tf::Transformer* tf = context_->getFrameManager()->getTFClient(); im_client_.reset( new interactive_markers::InteractiveMarkerClient( *tf, fixed_frame_.toStdString() ) ); im_client_->setInitCb( boost::bind( &InteractiveMarkerDisplay::initCb, this, _1 ) ); im_client_->setUpdateCb( boost::bind( &InteractiveMarkerDisplay::updateCb, this, _1 ) ); im_client_->setResetCb( boost::bind( &InteractiveMarkerDisplay::resetCb, this, _1 ) ); im_client_->setStatusCb( boost::bind( &InteractiveMarkerDisplay::statusCb, this, _1, _2, _3 ) ); client_id_ = ros::this_node::getName() + "/" + getNameStd(); onEnable(); }
// ****************************************************************************************** // Load // ****************************************************************************************** void PlanningSceneDisplay::loadRobotModel() { planning_scene_render_.reset(); planning_scene_monitor_.reset(); // this so that the destructor of the PlanningSceneMonitor gets called before a new instance of a scene monitor is constructed planning_scene_monitor_.reset(new planning_scene_monitor::PlanningSceneMonitor(robot_description_property_->getStdString(), context_->getFrameManager()->getTFClientPtr(), getNameStd() + "_planning_scene_monitor")); if (planning_scene_monitor_->getPlanningScene()) { planning_scene_monitor_->addUpdateCallback(boost::bind(&PlanningSceneDisplay::sceneMonitorReceivedUpdate, this, _1)); planning_scene_monitor_->startSceneMonitor(planning_scene_topic_property_->getStdString()); planning_scene_render_.reset(new PlanningSceneRender(planning_scene_node_, context_, planning_scene_robot_)); planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool()); onRobotModelLoaded(); setStatus( rviz::StatusProperty::Ok, "PlanningScene", "Planning Scene Loaded Successfully" ); } else { planning_scene_monitor_.reset(); setStatus( rviz::StatusProperty::Error, "PlanningScene", "No Planning Scene Loaded" ); } }