00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 5/4/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #include "srs_assisted_arm_navigation_ui/arm_navigation_display.h" 00029 00030 #include <OGRE/OgreSceneManager.h> 00031 00032 #include <rviz/render_panel.h> 00033 #include <rviz/visualization_manager.h> 00034 #include <rviz/window_manager_interface.h> 00035 00036 #include <sstream> 00037 00038 using namespace srs_assisted_arm_navigation_ui; 00039 00040 00044 CButArmNavDisplay::CButArmNavDisplay(const std::string & name,rviz::VisualizationManager * manager) 00045 : Display( name, manager ) 00046 { 00047 // Get node handle 00048 ros::NodeHandle private_nh("~"); 00049 00050 // Connect to the controller changed signal 00051 //vis_manager_->getViewControllerTypeChangedSignal().connect( boost::bind(&CButArmNavDisplay::onViewControllerChange, this, _1 ) ); 00052 00053 // Get scene node 00054 //m_sceneNode = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00055 00056 // Try to connect camera listener 00057 //connectListener(); 00058 00059 // Try to create, add and show example window 00060 rviz::WindowManagerInterface * wi( manager->getWindowManager() ); 00061 00062 if( wi != 0 ) 00063 { 00064 // Arm manipulation controls 00065 m_armmanipulation_window = new CArmManipulationControls( wi->getParentWindow(), wxT("Manual arm navigation"), wi); 00066 00067 if( m_armmanipulation_window != 0 ) 00068 { 00069 std::cerr << "Adding to the window manager..." << std::endl; 00070 wi->addPane( "Assisted arm navigation", m_armmanipulation_window ); 00071 wi->showPane( m_armmanipulation_window ); 00072 std::cerr << "Added..." << std::endl; 00073 } 00074 }else{ 00075 std::cerr << "No window manager, no panes :( " << std::endl; 00076 } 00077 } 00078 00079 00080 /* 00081 * Destructor 00082 */ 00083 CButArmNavDisplay::~CButArmNavDisplay() 00084 { 00085 } 00086