├── doc ├── wp_doc_001.png ├── wp_doc_002.png └── wp_doc_003.png ├── icons └── classes │ └── WaypointNav.png ├── launch ├── rviz.launch ├── waypoint_nav_plugin.rviz └── waypoint_navigation_plugin.rviz ├── waypoint_nav_plugin_description.xml ├── README.md ├── package.xml ├── LICENSE ├── CMakeLists.txt ├── src ├── waypoint_nav_tool.h ├── waypoint_nav_frame.h ├── waypoint_nav_frame.cpp └── waypoint_nav_tool.cpp ├── ui └── WaypointNavigation.ui └── media ├── flag.dae └── flag.dae.bak /doc/wp_doc_001.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/KumarRobotics/waypoint_navigation_plugin/HEAD/doc/wp_doc_001.png -------------------------------------------------------------------------------- /doc/wp_doc_002.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/KumarRobotics/waypoint_navigation_plugin/HEAD/doc/wp_doc_002.png -------------------------------------------------------------------------------- /doc/wp_doc_003.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/KumarRobotics/waypoint_navigation_plugin/HEAD/doc/wp_doc_003.png -------------------------------------------------------------------------------- /icons/classes/WaypointNav.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/KumarRobotics/waypoint_navigation_plugin/HEAD/icons/classes/WaypointNav.png -------------------------------------------------------------------------------- /launch/rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /waypoint_nav_plugin_description.xml: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | Tool for planting waypoints on the ground plane in rviz. 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # waypoint_navigation_plugin 2 | 3 | For testing 4 | ``` 5 | roslaunch waypoint_navigation_plugin rviz.launch 6 | ``` 7 | 8 | Add the WaypointNav Tool from waypoint_navigation_plugin 9 | 10 | ![WP1](doc/wp_doc_001.png "WP1") 11 | 12 | Click on the tool to add multiple waypoints and drop onto RviZ scene. The locations can be updated by dragging the Interactive marker of by using the Rviz panel 13 | ![WP2](doc/wp_doc_002.png "WP2") 14 | 15 | Clicking "Publish Waypoints" on the panel publishes nav_msgs::Path on topic entered under "Topic" 16 | ![WP3](doc/wp_doc_003.png "WP3") -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | waypoint_navigation_plugin 3 | 0.1.0 4 | 5 | Tool for planting waypoints in rviz. 6 | 7 | Dinesh Thakur 8 | BSD 9 | 10 | Dinesh Thakur 11 | 12 | catkin 13 | 14 | rviz 15 | rosbag 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2018, Kumar Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | * Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | * Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | * Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(waypoint_navigation_plugin) 3 | 4 | find_package(yaml-cpp REQUIRED) 5 | find_package(catkin REQUIRED COMPONENTS rviz rosbag) 6 | catkin_package() 7 | 8 | include_directories(${catkin_INCLUDE_DIRS}) 9 | link_directories(${catkin_LIBRARY_DIRS}) 10 | 11 | if(rviz_QT_VERSION VERSION_LESS "5") 12 | find_package(Qt4 COMPONENTS QtCore QtGui REQUIRED) 13 | include(${QT_USE_FILE}) 14 | 15 | else() 16 | find_package(Qt5 REQUIRED COMPONENTS Core Widgets OpenGL) 17 | # set variable names already used with Qt4 18 | set(QT_LIBRARIES Qt5::Widgets) 19 | set(QTVERSION ${Qt5Widgets_VERSION}) 20 | endif() 21 | 22 | ## Qt signals and slots to avoid defining "emit", "slots", 23 | ## etc because they can conflict with boost signals, so define QT_NO_KEYWORDS here. 24 | add_definitions(-DQT_NO_KEYWORDS) 25 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -frounding-math -Werror=return-type") 26 | 27 | if(rviz_QT_VERSION VERSION_LESS "5") 28 | 29 | # Header files that need Qt Moc pre-processing for use with Qt signals, etc: 30 | qt4_wrap_cpp(MOC_FILES 31 | src/waypoint_nav_frame.h 32 | src/waypoint_nav_tool.h 33 | ) 34 | 35 | # Convert the Qt Signals and Slots for QWidget events 36 | qt4_wrap_ui(UIC_FILES 37 | ui/WaypointNavigation.ui 38 | ) 39 | else() 40 | # Header files that need Qt Moc pre-processing for use with Qt signals, etc: 41 | qt5_wrap_cpp(MOC_FILES 42 | src/waypoint_nav_frame.h 43 | src/waypoint_nav_tool.h 44 | ) 45 | 46 | # Convert the Qt Signals and Slots for QWidget events 47 | qt5_wrap_ui(UIC_FILES 48 | ui/WaypointNavigation.ui 49 | ) 50 | endif() 51 | 52 | include_directories(${CMAKE_CURRENT_BINARY_DIR}) 53 | 54 | # Plugin Source 55 | set(SOURCE_FILES 56 | src/waypoint_nav_frame.cpp 57 | src/waypoint_nav_tool.cpp 58 | ${MOC_FILES} 59 | ) 60 | 61 | set(LIB_NAME waypoint_nav_plugin) 62 | add_library(${LIB_NAME} ${SOURCE_FILES} ${MOC_SOURCES} ${UIC_FILES}) 63 | target_link_libraries(${LIB_NAME} 64 | ${catkin_LIBRARIES} ${QT_LIBRARIES} ${YAML_CPP_LIBRARIES}) 65 | 66 | ## Install rules 67 | 68 | install(DIRECTORY src/ 69 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 70 | FILES_MATCHING PATTERN "*.h") 71 | 72 | install(TARGETS ${LIB_NAME} 73 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 74 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) 75 | 76 | ## Install rules 77 | install(FILES 78 | waypoint_nav_plugin_description.xml 79 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 80 | 81 | install(DIRECTORY media/ 82 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/media) 83 | 84 | install(DIRECTORY icons/ 85 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) 86 | -------------------------------------------------------------------------------- /src/waypoint_nav_tool.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2012, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | */ 29 | 30 | /* Author: Dinesh Thakur - Modified for waypoint navigation */ 31 | 32 | #pragma once 33 | 34 | #include 35 | #include 36 | #include 37 | #include 38 | 39 | #include "waypoint_nav_frame.h" 40 | namespace Ogre 41 | { 42 | class SceneNode; 43 | class Vector3; 44 | } // namespace Ogre 45 | 46 | namespace rviz 47 | { 48 | class VectorProperty; 49 | class VisualizationManager; 50 | class ViewportMouseEvent; 51 | class PanelDockWidget; 52 | } // namespace rviz 53 | 54 | 55 | namespace waypoint_nav_plugin 56 | { 57 | 58 | class WaypointNavTool: public rviz::Tool 59 | { 60 | 61 | Q_OBJECT 62 | public: 63 | WaypointNavTool(); 64 | ~WaypointNavTool(); 65 | 66 | virtual void onInitialize(); 67 | 68 | virtual void activate(); 69 | virtual void deactivate(); 70 | 71 | virtual int processMouseEvent(rviz::ViewportMouseEvent& event); 72 | 73 | virtual void load(const rviz::Config& config); 74 | virtual void save(rviz::Config config) const; 75 | void makeIm(const Ogre::Vector3& position, const Ogre::Quaternion& quat, 76 | bool full_dof = false); 77 | 78 | private: 79 | void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback); 80 | void getMarkerPoses(); 81 | void clearAllWaypoints(); 82 | 83 | Ogre::SceneNode* moving_flag_node_; 84 | std::string flag_resource_; 85 | 86 | // the waypoint nav Qt frame 87 | WaypointFrame* frame_; 88 | rviz::PanelDockWidget* frame_dock_; 89 | 90 | interactive_markers::InteractiveMarkerServer server_; 91 | interactive_markers::MenuHandler menu_handler_; 92 | 93 | // map that stores waypoints based on unique names 94 | typedef std::map M_StringToSNPtr; 95 | M_StringToSNPtr sn_map_; 96 | 97 | // index used for creating unique marker names 98 | int unique_ind_; 99 | }; 100 | 101 | } // end namespace kr_rviz_plugins 102 | -------------------------------------------------------------------------------- /src/waypoint_nav_frame.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2012, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | /* Author: Ioan Sucan */ 36 | /* Author: Dinesh Thakur - Modified for waypoint navigation */ 37 | 38 | #ifndef KR_RVIZ_PLUGIN_WAYPOINT_FRAME_ 39 | #define KR_RVIZ_PLUGIN_WAYPOINT_FRAME_ 40 | 41 | #ifndef Q_MOC_RUN 42 | #include 43 | #endif 44 | 45 | #include 46 | 47 | #include "ros/ros.h" 48 | #include 49 | 50 | #include "ui_WaypointNavigation.h" 51 | 52 | namespace Ogre 53 | { 54 | class SceneNode; 55 | class Vector3; 56 | class SceneManager; 57 | class Quaternion; 58 | } // namespace Ogre 59 | 60 | namespace rviz 61 | { 62 | class DisplayContext; 63 | } 64 | 65 | namespace interactive_markers 66 | { 67 | class InteractiveMarkerServer; 68 | } 69 | 70 | namespace Ui 71 | { 72 | class WaypointNavigationWidget; 73 | } 74 | 75 | namespace waypoint_nav_plugin 76 | { 77 | class WaypointNavTool; 78 | } 79 | 80 | namespace waypoint_nav_plugin 81 | { 82 | 83 | constexpr char g_wp_name_prefix[] = "waypoint_"; 84 | 85 | class WaypointFrame : public QWidget 86 | { 87 | friend class WaypointNavTool; 88 | Q_OBJECT 89 | 90 | public: 91 | WaypointFrame(rviz::DisplayContext *context, std::map* map_ptr, interactive_markers::InteractiveMarkerServer* server, int* unique_ind, QWidget *parent = 0, WaypointNavTool* wp_tool=0); 92 | ~WaypointFrame(); 93 | 94 | void enable(); 95 | void disable(); 96 | 97 | void setWpCount(int size); 98 | void setConfig(QString topic, QString frame, float height); 99 | void setWpLabel(Ogre::Vector3 position); 100 | void setSelectedMarkerName(std::string name); 101 | void setPose(const Ogre::Vector3& position, const Ogre::Quaternion& quat); 102 | 103 | double getDefaultHeight(); 104 | QString getFrameId(); 105 | QString getOutputTopic(); 106 | void getPose(Ogre::Vector3& position, Ogre::Quaternion& quat); 107 | 108 | // Save/Load 109 | void loadFromBag(const std::string& filename); 110 | void loadFromYaml(const std::string& filename); 111 | void loadFromJson(const std::string& filename); 112 | 113 | void saveToBag(const std::string& filename); 114 | void saveToYaml(const std::string& filename); 115 | void saveToJson(const std::string& filename); 116 | 117 | protected: 118 | Ui::WaypointNavigationWidget* ui_; 119 | rviz::DisplayContext* context_; 120 | 121 | private Q_SLOTS: 122 | void publishButtonClicked(); 123 | void clearAllWaypoints(); 124 | void heightChanged(double h); 125 | void frameChanged(); 126 | void topicChanged(); 127 | void poseChanged(double val); 128 | void saveButtonClicked(); 129 | void loadButtonClicked(); 130 | 131 | private: 132 | 133 | ros::NodeHandle nh_; 134 | ros::Publisher wp_pub_; 135 | 136 | WaypointNavTool* wp_nav_tool_; 137 | //pointers passed via contructor 138 | std::map* sn_map_ptr_; 139 | Ogre::SceneManager* scene_manager_; 140 | int* unique_ind_; 141 | 142 | interactive_markers::InteractiveMarkerServer* server_; 143 | 144 | //default height the waypoint must be placed at 145 | double default_height_; 146 | 147 | // The current name of the output topic. 148 | QString output_topic_; 149 | QString frame_id_; 150 | 151 | //mutex for changes of variables 152 | boost::mutex frame_updates_mutex_; 153 | 154 | std::string selected_marker_name_; 155 | 156 | }; 157 | 158 | } 159 | 160 | #endif 161 | -------------------------------------------------------------------------------- /launch/waypoint_nav_plugin.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 78 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: ~ 7 | Splitter Ratio: 0.5 8 | Tree Height: 563 9 | - Class: rviz/Selection 10 | Name: Selection 11 | - Class: rviz/Tool Properties 12 | Expanded: 13 | - /2D Pose Estimate1 14 | - /2D Nav Goal1 15 | - /Publish Point1 16 | Name: Tool Properties 17 | Splitter Ratio: 0.5886790156364441 18 | - Class: rviz/Views 19 | Expanded: 20 | - /Current View1 21 | Name: Views 22 | Splitter Ratio: 0.5 23 | - Class: rviz/Time 24 | Experimental: false 25 | Name: Time 26 | SyncMode: 0 27 | SyncSource: "" 28 | Preferences: 29 | PromptSaveOnExit: true 30 | Toolbars: 31 | toolButtonStyle: 2 32 | Visualization Manager: 33 | Class: "" 34 | Displays: 35 | - Alpha: 0.5 36 | Cell Size: 1 37 | Class: rviz/Grid 38 | Color: 160; 160; 164 39 | Enabled: true 40 | Line Style: 41 | Line Width: 0.029999999329447746 42 | Value: Lines 43 | Name: Grid 44 | Normal Cell Count: 0 45 | Offset: 46 | X: 0 47 | Y: 0 48 | Z: 0 49 | Plane: XY 50 | Plane Cell Count: 10 51 | Reference Frame: 52 | Value: true 53 | - Class: rviz/InteractiveMarkers 54 | Enable Transparency: true 55 | Enabled: true 56 | Name: InteractiveMarkers 57 | Show Axes: false 58 | Show Descriptions: true 59 | Show Visual Aids: false 60 | Update Topic: /waypoint_nav/update 61 | Value: true 62 | - Alpha: 1 63 | Buffer Length: 1 64 | Class: rviz/Path 65 | Color: 25; 255; 0 66 | Enabled: true 67 | Head Diameter: 0.30000001192092896 68 | Head Length: 0.20000000298023224 69 | Length: 0.30000001192092896 70 | Line Style: Lines 71 | Line Width: 0.029999999329447746 72 | Name: Path 73 | Offset: 74 | X: 0 75 | Y: 0 76 | Z: 0 77 | Pose Color: 255; 85; 255 78 | Pose Style: None 79 | Queue Size: 10 80 | Radius: 0.029999999329447746 81 | Shaft Diameter: 0.10000000149011612 82 | Shaft Length: 0.10000000149011612 83 | Topic: /waypoints 84 | Unreliable: false 85 | Value: true 86 | Enabled: true 87 | Global Options: 88 | Background Color: 48; 48; 48 89 | Default Light: true 90 | Fixed Frame: map 91 | Frame Rate: 30 92 | Name: root 93 | Tools: 94 | - Class: rviz/Interact 95 | Hide Inactive Objects: true 96 | - Class: rviz/MoveCamera 97 | - Class: rviz/Select 98 | - Class: rviz/FocusCamera 99 | - Class: rviz/Measure 100 | - Class: rviz/SetInitialPose 101 | Theta std deviation: 0.2617993950843811 102 | Topic: /initialpose 103 | X std deviation: 0.5 104 | Y std deviation: 0.5 105 | - Class: rviz/SetGoal 106 | Topic: /move_base_simple/goal 107 | - Class: rviz/PublishPoint 108 | Single click: true 109 | Topic: /clicked_point 110 | - Class: waypoint_nav_plugin/WaypointNav 111 | WaypointsTool: 112 | default_height: 0 113 | frame_id: map 114 | topic: /waypoint 115 | Value: true 116 | Views: 117 | Current: 118 | Class: rviz/Orbit 119 | Distance: 10 120 | Enable Stereo Rendering: 121 | Stereo Eye Separation: 0.05999999865889549 122 | Stereo Focal Distance: 1 123 | Swap Stereo Eyes: false 124 | Value: false 125 | Field of View: 0.7853981852531433 126 | Focal Point: 127 | X: 0 128 | Y: 0 129 | Z: 0 130 | Focal Shape Fixed Size: true 131 | Focal Shape Size: 0.05000000074505806 132 | Invert Z Axis: false 133 | Name: Current View 134 | Near Clip Distance: 0.009999999776482582 135 | Pitch: 0.785398006439209 136 | Target Frame: 137 | Yaw: 0.785398006439209 138 | Saved: ~ 139 | Window Geometry: 140 | Displays: 141 | collapsed: false 142 | Height: 1056 143 | Hide Left Dock: false 144 | Hide Right Dock: false 145 | QMainWindow State: 000000ff00000000fd0000000400000000000001d300000382fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002be000000c900fffffffb000000260057006100790070006f0069006e00740020004e0061007600690067006100740069006f006e0100000301000000be000000be00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000382fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000382000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004510000038200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 146 | Selection: 147 | collapsed: false 148 | Time: 149 | collapsed: false 150 | Tool Properties: 151 | collapsed: false 152 | Views: 153 | collapsed: false 154 | Waypoint Navigation: 155 | collapsed: false 156 | Width: 1855 157 | X: 65 158 | Y: 0 159 | -------------------------------------------------------------------------------- /launch/waypoint_navigation_plugin.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 78 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: ~ 7 | Splitter Ratio: 0.5 8 | Tree Height: 550 9 | - Class: rviz/Selection 10 | Name: Selection 11 | - Class: rviz/Tool Properties 12 | Expanded: 13 | - /2D Pose Estimate1 14 | - /2D Nav Goal1 15 | - /Publish Point1 16 | Name: Tool Properties 17 | Splitter Ratio: 0.588679 18 | - Class: rviz/Views 19 | Expanded: 20 | - /Current View1 21 | Name: Views 22 | Splitter Ratio: 0.5 23 | - Class: rviz/Time 24 | Experimental: false 25 | Name: Time 26 | SyncMode: 0 27 | SyncSource: "" 28 | Visualization Manager: 29 | Class: "" 30 | Displays: 31 | - Alpha: 0.5 32 | Cell Size: 1 33 | Class: rviz/Grid 34 | Color: 160; 160; 164 35 | Enabled: true 36 | Line Style: 37 | Line Width: 0.03 38 | Value: Lines 39 | Name: Grid 40 | Normal Cell Count: 0 41 | Offset: 42 | X: 0 43 | Y: 0 44 | Z: 0 45 | Plane: XY 46 | Plane Cell Count: 10 47 | Reference Frame: 48 | Value: true 49 | - Alpha: 1 50 | Class: rviz/RobotModel 51 | Collision Enabled: false 52 | Enabled: false 53 | Links: 54 | All Links Enabled: true 55 | Expand Joint Details: false 56 | Expand Link Details: false 57 | Expand Tree: false 58 | Link Tree Style: Links in Alphabetic Order 59 | Name: RobotModel 60 | Robot Description: robot_description 61 | TF Prefix: "" 62 | Update Interval: 0 63 | Value: false 64 | Visual Enabled: true 65 | - Class: rviz/TF 66 | Enabled: true 67 | Frame Timeout: 15 68 | Frames: 69 | All Enabled: true 70 | Marker Scale: 1 71 | Name: TF 72 | Show Arrows: false 73 | Show Axes: true 74 | Show Names: true 75 | Tree: 76 | {} 77 | Update Interval: 0 78 | Value: true 79 | - Alpha: 1 80 | Buffer Length: 1 81 | Class: rviz/Path 82 | Color: 25; 255; 0 83 | Enabled: true 84 | Name: Path 85 | Topic: /waypoints 86 | Value: true 87 | - Class: rviz/InteractiveMarkers 88 | Enable Transparency: true 89 | Enabled: true 90 | Name: InteractiveMarkers 91 | Show Axes: false 92 | Show Descriptions: true 93 | Show Visual Aids: false 94 | Update Topic: /waypoint_nav/update 95 | Value: true 96 | Enabled: true 97 | Global Options: 98 | Background Color: 48; 48; 48 99 | Fixed Frame: map 100 | Frame Rate: 30 101 | Name: root 102 | Tools: 103 | - Class: rviz/Interact 104 | Hide Inactive Objects: true 105 | - Class: rviz/MoveCamera 106 | - Class: rviz/Select 107 | - Class: rviz/FocusCamera 108 | - Class: rviz/Measure 109 | - Class: rviz/SetInitialPose 110 | Topic: /initialpose 111 | - Class: rviz/SetGoal 112 | Topic: /move_base_simple/goal 113 | - Class: rviz/PublishPoint 114 | Single click: true 115 | Topic: /clicked_point 116 | - Class: waypoint_nav_plugin/WaypointNav 117 | Waypoints: 118 | default_height: 0 119 | frame_id: /map 120 | topic: /waypoints 121 | Value: true 122 | Views: 123 | Current: 124 | Class: rviz/Orbit 125 | Distance: 14.4665 126 | Enable Stereo Rendering: 127 | Stereo Eye Separation: 0.06 128 | Stereo Focal Distance: 1 129 | Swap Stereo Eyes: false 130 | Value: false 131 | Focal Point: 132 | X: -0.612388 133 | Y: -1.58615 134 | Z: -0.0159853 135 | Name: Current View 136 | Near Clip Distance: 0.01 137 | Pitch: 0.504798 138 | Target Frame: 139 | Value: Orbit (rviz) 140 | Yaw: 4.16857 141 | Saved: ~ 142 | Window Geometry: 143 | Displays: 144 | collapsed: false 145 | Height: 1056 146 | Hide Left Dock: false 147 | Hide Right Dock: false 148 | QMainWindow State: 000000ff00000000fd00000004000000000000013c00000396fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002b5000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000010004b007200430061006d006500720061000000021a000000d20000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000218000000d40000000000000000fb00000010004b007200430061006d0065007200610200000994000001ed0000013c000000e2fb00000010004b007200430061006d0065007200610300000962000001eb0000013c000000e6fb000000260057006100790070006f0069006e00740020004e0061007600690067006100740069006f006e01000002e3000000db000000d400ffffff000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000396000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000074f0000003efc0100000002fb0000000800540069006d006501000000000000074f000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000004f80000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 149 | Selection: 150 | collapsed: false 151 | Time: 152 | collapsed: false 153 | Tool Properties: 154 | collapsed: false 155 | Views: 156 | collapsed: false 157 | Waypoint Navigation: 158 | collapsed: false 159 | Width: 1871 160 | X: 1969 161 | Y: 24 162 | -------------------------------------------------------------------------------- /ui/WaypointNavigation.ui: -------------------------------------------------------------------------------- 1 | 2 | 3 | WaypointNavigationWidget 4 | 5 | 6 | 7 | 0 8 | 0 9 | 469 10 | 175 11 | 12 | 13 | 14 | Quadrotor Steering 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | Topic 23 | 24 | 25 | 26 | 27 | 28 | 29 | /waypoints 30 | 31 | 32 | 33 | 34 | 35 | 36 | Frame 37 | 38 | 39 | 40 | 41 | 42 | 43 | map 44 | 45 | 46 | 47 | 48 | 49 | 50 | 6D 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | Default Height 62 | 63 | 64 | 65 | 66 | 67 | 68 | -5.000000000000000 69 | 70 | 71 | 0.100000000000000 72 | 73 | 74 | 75 | 76 | 77 | 78 | Total Waypoints: 79 | 80 | 81 | 82 | 83 | 84 | 85 | Selected wp: 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | Load Waypoints 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | X: 111 | 112 | 113 | 114 | 115 | 116 | 117 | -1000.000000000000000 118 | 119 | 120 | 1000.000000000000000 121 | 122 | 123 | 0.500000000000000 124 | 125 | 126 | 127 | 128 | 129 | 130 | Qt::Horizontal 131 | 132 | 133 | 134 | 40 135 | 20 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | Y: 144 | 145 | 146 | 147 | 148 | 149 | 150 | -1000.000000000000000 151 | 152 | 153 | 1000.000000000000000 154 | 155 | 156 | 0.500000000000000 157 | 158 | 159 | 160 | 161 | 162 | 163 | Qt::Horizontal 164 | 165 | 166 | 167 | 40 168 | 20 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | Z: 177 | 178 | 179 | 180 | 181 | 182 | 183 | -1000.000000000000000 184 | 185 | 186 | 1000.000000000000000 187 | 188 | 189 | 0.500000000000000 190 | 191 | 192 | 193 | 194 | 195 | 196 | Qt::Horizontal 197 | 198 | 199 | 200 | 40 201 | 20 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | Yaw: 210 | 211 | 212 | 213 | 214 | 215 | 216 | -3.150000000000000 217 | 218 | 219 | 3.150000000000000 220 | 221 | 222 | 0.100000000000000 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | Clear All 232 | 233 | 234 | 235 | 236 | 237 | 238 | Save Waypoints 239 | 240 | 241 | 242 | 243 | 244 | 245 | Publish Waypoints 246 | 247 | 248 | 249 | 250 | 251 | 252 | 253 | 254 | -------------------------------------------------------------------------------- /src/waypoint_nav_frame.cpp: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2012, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | /* Author: Ioan Sucan */ 36 | /* Author: Dinesh Thakur - Modified for waypoint navigation */ 37 | 38 | #include 39 | #include 40 | #include 41 | #include 42 | #include 43 | #include 44 | 45 | #include "waypoint_nav_tool.h" 46 | 47 | //#include "waypoint_nav_frame.h" 48 | //#include "waypoint_nav_frame.h" 49 | 50 | #include 51 | #include 52 | 53 | #include 54 | 55 | #include 56 | #define foreach BOOST_FOREACH 57 | 58 | namespace waypoint_nav_plugin 59 | { 60 | 61 | struct MissionKeywords { 62 | inline static const std::string kPosition = "position"; 63 | }; 64 | 65 | WaypointFrame::WaypointFrame(rviz::DisplayContext *context, std::map* map_ptr, interactive_markers::InteractiveMarkerServer* server, int* unique_ind, QWidget *parent, WaypointNavTool* wp_tool) 66 | : QWidget(parent) 67 | , context_(context) 68 | , ui_(new Ui::WaypointNavigationWidget()) 69 | , sn_map_ptr_(map_ptr) 70 | , unique_ind_(unique_ind) 71 | , server_(server) 72 | , frame_id_("map") 73 | , default_height_(0.0) 74 | , selected_marker_name_(std::string(g_wp_name_prefix) + "1") 75 | , wp_nav_tool_(wp_tool) 76 | { 77 | scene_manager_ = context_->getSceneManager(); 78 | 79 | // set up the GUI 80 | ui_->setupUi(this); 81 | 82 | wp_pub_ = nh_.advertise("waypoints", 1); 83 | 84 | //connect the Qt signals and slots 85 | connect(ui_->publish_wp_button, SIGNAL(clicked()), this, SLOT(publishButtonClicked())); 86 | connect(ui_->topic_line_edit, SIGNAL(editingFinished()), this, SLOT(topicChanged())); 87 | connect(ui_->frame_line_edit, SIGNAL(editingFinished()), this, SLOT(frameChanged())); 88 | connect(ui_->wp_height_doubleSpinBox, SIGNAL(valueChanged(double)), this, SLOT(heightChanged(double))); 89 | connect(ui_->clear_all_button, SIGNAL(clicked()), this, SLOT(clearAllWaypoints())); 90 | 91 | connect(ui_->x_doubleSpinBox, SIGNAL(valueChanged(double)), this, SLOT(poseChanged(double))); 92 | connect(ui_->y_doubleSpinBox, SIGNAL(valueChanged(double)), this, SLOT(poseChanged(double))); 93 | connect(ui_->z_doubleSpinBox, SIGNAL(valueChanged(double)), this, SLOT(poseChanged(double))); 94 | connect(ui_->yaw_doubleSpinBox, SIGNAL(valueChanged(double)), this, SLOT(poseChanged(double))); 95 | 96 | connect(ui_->save_wp_button, SIGNAL(clicked()), this, SLOT(saveButtonClicked())); 97 | connect(ui_->load_wp_button, SIGNAL(clicked()), this, SLOT(loadButtonClicked())); 98 | 99 | } 100 | 101 | WaypointFrame::~WaypointFrame() 102 | { 103 | delete ui_; 104 | sn_map_ptr_ = NULL; 105 | } 106 | 107 | void WaypointFrame::enable() 108 | { 109 | // activate the frame 110 | show(); 111 | } 112 | 113 | void WaypointFrame::disable() 114 | { 115 | wp_pub_.shutdown(); 116 | hide(); 117 | } 118 | 119 | void WaypointFrame::saveButtonClicked() 120 | { 121 | QString filename = 122 | QFileDialog::getSaveFileName(0, tr("Save Mission"), "waypoints", 123 | tr("Mission Files (*.bag *.yaml *.json)")); 124 | 125 | if (filename.isEmpty()) { 126 | ROS_ERROR("No mission filename selected"); 127 | return; 128 | } 129 | 130 | const std::string filename_str = filename.toStdString(); 131 | ROS_INFO_STREAM("saving waypoints to " << filename_str); 132 | if (filename.endsWith(".bag")) { 133 | saveToBag(filename_str); 134 | } else if (filename.endsWith(".yaml")) { 135 | saveToYaml(filename_str); 136 | } else if (filename.endsWith(".json")) { 137 | saveToJson(filename_str); 138 | } else { 139 | ROS_INFO_STREAM("Invalid mission file format: " << filename_str); 140 | } 141 | } 142 | 143 | void WaypointFrame::saveToBag(const std::string &filename) 144 | { 145 | rosbag::Bag bag; 146 | try { 147 | bag.open(filename, rosbag::bagmode::Write); 148 | } catch (const rosbag::BagIOException &e) { 149 | ROS_ERROR("could not open bag %s", filename.c_str()); 150 | return; 151 | } 152 | 153 | nav_msgs::Path path; 154 | 155 | std::map::iterator sn_it; 156 | for (sn_it = sn_map_ptr_->begin(); sn_it != sn_map_ptr_->end(); ++sn_it) 157 | { 158 | Ogre::Vector3 position; 159 | position = sn_it->second->getPosition(); 160 | 161 | geometry_msgs::PoseStamped pos; 162 | pos.pose.position.x = position.x; 163 | pos.pose.position.y = position.y; 164 | pos.pose.position.z = position.z; 165 | 166 | Ogre::Quaternion quat; 167 | quat = sn_it->second->getOrientation(); 168 | pos.pose.orientation.x = quat.x; 169 | pos.pose.orientation.y = quat.y; 170 | pos.pose.orientation.z = quat.z; 171 | pos.pose.orientation.w = quat.w; 172 | 173 | path.poses.push_back(pos); 174 | } 175 | 176 | path.header.frame_id = frame_id_.toStdString(); 177 | 178 | bag.write("waypoints", ros::Time::now(), path); 179 | bag.close(); 180 | } 181 | 182 | void WaypointFrame::saveToYaml(const std::string &filename) { 183 | YAML::Emitter out; 184 | std::map::iterator sn_it; 185 | out << YAML::BeginSeq; 186 | for (sn_it = sn_map_ptr_->begin(); sn_it != sn_map_ptr_->end(); ++sn_it) { 187 | const Ogre::Vector3 position = sn_it->second->getPosition(); 188 | 189 | out << YAML::BeginMap; 190 | out << YAML::Key << MissionKeywords::kPosition; 191 | out << YAML::Value; 192 | out << YAML::Flow; 193 | out << YAML::BeginSeq; 194 | out << position.x << position.y << position.z; 195 | out << YAML::EndSeq; 196 | out << YAML::EndMap; 197 | } 198 | out << YAML::EndSeq; 199 | 200 | std::ofstream fout(filename); 201 | fout << out.c_str(); 202 | } 203 | 204 | void WaypointFrame::saveToJson(const std::string &filename) {} 205 | 206 | void WaypointFrame::loadButtonClicked() { 207 | const QString filename = QFileDialog::getOpenFileName( 208 | 0, tr("Load Mission"), "~/", tr("Mission Files (*.bag *.yaml *.json)")); 209 | 210 | if (filename.isEmpty()) { 211 | ROS_ERROR("No mission file selected"); 212 | return; 213 | } 214 | 215 | const std::string filename_str = filename.toStdString(); 216 | ROS_INFO("loading waypoints from %s", filename_str.c_str()); 217 | if (filename.endsWith(".bag")) { 218 | loadFromBag(filename_str); 219 | } else if (filename.endsWith(".yaml")) { 220 | loadFromYaml(filename_str); 221 | } else if (filename.endsWith(".json")) { 222 | loadFromJson(filename_str); 223 | } else { 224 | ROS_INFO_STREAM("Invalid mission file format: " << filename_str); 225 | } 226 | } 227 | 228 | void WaypointFrame::loadFromBag(const std::string &filename) { 229 | rosbag::Bag bag; 230 | try { 231 | bag.open(filename, rosbag::bagmode::Read); 232 | } catch (const rosbag::BagIOException &e) { 233 | ROS_ERROR("could not open bag %s", filename.c_str()); 234 | return; 235 | } 236 | 237 | std::vector topics; 238 | topics.push_back(std::string("waypoints")); 239 | rosbag::View view(bag, rosbag::TopicQuery(topics)); 240 | 241 | BOOST_FOREACH (rosbag::MessageInstance const m, view) { 242 | nav_msgs::Path::ConstPtr p = m.instantiate(); 243 | if (p == nullptr) continue; 244 | ROS_INFO("n waypoints %zu", p->poses.size()); 245 | 246 | for (size_t i = 0; i < p->poses.size(); i++) { 247 | geometry_msgs::PoseStamped pos = p->poses[i]; 248 | Ogre::Vector3 position; 249 | position.x = pos.pose.position.x; 250 | position.y = pos.pose.position.y; 251 | position.z = pos.pose.position.z; 252 | 253 | Ogre::Quaternion quat; 254 | quat.x = pos.pose.orientation.x; 255 | quat.y = pos.pose.orientation.y; 256 | quat.z = pos.pose.orientation.z; 257 | quat.w = pos.pose.orientation.w; 258 | 259 | wp_nav_tool_->makeIm(position, quat, 260 | ui_->sixDcheckBox->checkState() == Qt::Checked); 261 | } 262 | } 263 | } 264 | 265 | void WaypointFrame::loadFromYaml(const std::string &filename) { 266 | YAML::Node root_node = YAML::LoadFile(filename); 267 | 268 | // Iterate over each waypoint 269 | for (auto it_wpt = root_node.begin(); it_wpt != root_node.end(); ++it_wpt) { 270 | // Get waypoint node, which is a list of key-value pairs 271 | YAML::Node wpt_node = *it_wpt; 272 | // IMPORTANT UPDATES: publish one set of waypoints, instead of iterating and 273 | // publishing multiple duplicate sets (thus, adding the last line of this 274 | // function) 275 | for (auto it_map = wpt_node.begin(); it_map != wpt_node.end(); ++it_map) { 276 | // Do stuff depends on the key 277 | const std::string key = it_map->first.as(); 278 | if (key == MissionKeywords::kPosition) { 279 | YAML::Node pos_node = it_map->second; 280 | 281 | Ogre::Vector3 position; 282 | position.x = pos_node[0].as(); 283 | position.y = pos_node[1].as(); 284 | position.z = pos_node[2].as(); 285 | ROS_WARN_STREAM("add waypoint whose x y z are: " << position.x << ", " 286 | << position.y << ", " 287 | << position.z); 288 | Ogre::Quaternion quat; 289 | wp_nav_tool_->makeIm(position, quat, 290 | ui_->sixDcheckBox->checkState() == Qt::Checked); 291 | } 292 | } 293 | } 294 | publishButtonClicked(); 295 | } 296 | 297 | void WaypointFrame::publishButtonClicked() 298 | { 299 | nav_msgs::Path path; 300 | 301 | std::map::iterator sn_it; 302 | for (sn_it = sn_map_ptr_->begin(); sn_it != sn_map_ptr_->end(); sn_it++) 303 | { 304 | Ogre::Vector3 position; 305 | position = sn_it->second->getPosition(); 306 | 307 | geometry_msgs::PoseStamped pos; 308 | pos.pose.position.x = position.x; 309 | pos.pose.position.y = position.y; 310 | pos.pose.position.z = position.z; 311 | 312 | Ogre::Quaternion quat; 313 | quat = sn_it->second->getOrientation(); 314 | pos.pose.orientation.x = quat.x; 315 | pos.pose.orientation.y = quat.y; 316 | pos.pose.orientation.z = quat.z; 317 | pos.pose.orientation.w = quat.w; 318 | 319 | path.poses.push_back(pos); 320 | } 321 | 322 | path.header.frame_id = frame_id_.toStdString(); 323 | wp_pub_.publish(path); 324 | } 325 | 326 | void WaypointFrame::clearAllWaypoints() 327 | { 328 | //destroy the ogre scene nodes 329 | std::map::iterator sn_it; 330 | for (sn_it = sn_map_ptr_->begin(); sn_it != sn_map_ptr_->end(); sn_it++) 331 | { 332 | scene_manager_->destroySceneNode(sn_it->second); 333 | } 334 | 335 | //clear the waypoint map and reset index 336 | sn_map_ptr_->clear(); 337 | *unique_ind_=0; 338 | 339 | //clear the interactive markers 340 | server_->clear(); 341 | server_->applyChanges(); 342 | } 343 | 344 | void WaypointFrame::heightChanged(double h) 345 | { 346 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 347 | default_height_ = h; 348 | } 349 | 350 | void WaypointFrame::setSelectedMarkerName(std::string name) 351 | { 352 | selected_marker_name_ = name; 353 | } 354 | 355 | void WaypointFrame::poseChanged(double val) { 356 | auto sn_entry = sn_map_ptr_->end(); 357 | try { 358 | const int selected_marker_idx = 359 | std::stoi(selected_marker_name_.substr(strlen(g_wp_name_prefix))); 360 | sn_entry = sn_map_ptr_->find(selected_marker_idx); 361 | } catch (const std::logic_error &e) { 362 | ROS_ERROR_STREAM(e.what()); 363 | return; 364 | } 365 | 366 | if (sn_entry == sn_map_ptr_->end()) 367 | ROS_ERROR("%s not found in map", selected_marker_name_.c_str()); 368 | else 369 | { 370 | Ogre::Vector3 position; 371 | Ogre::Quaternion quat; 372 | getPose(position, quat); 373 | 374 | sn_entry->second->setPosition(position); 375 | sn_entry->second->setOrientation(quat); 376 | 377 | std::stringstream wp_name; 378 | wp_name << g_wp_name_prefix << sn_entry->first; 379 | std::string wp_name_str(wp_name.str()); 380 | 381 | visualization_msgs::InteractiveMarker int_marker; 382 | if(server_->get(wp_name_str, int_marker)) 383 | { 384 | int_marker.pose.position.x = position.x; 385 | int_marker.pose.position.y = position.y; 386 | int_marker.pose.position.z = position.z; 387 | 388 | int_marker.pose.orientation.x = quat.x; 389 | int_marker.pose.orientation.y = quat.y; 390 | int_marker.pose.orientation.z = quat.z; 391 | int_marker.pose.orientation.w = quat.w; 392 | 393 | server_->setPose(wp_name_str, int_marker.pose, int_marker.header); 394 | } 395 | server_->applyChanges(); 396 | } 397 | } 398 | 399 | void WaypointFrame::frameChanged() 400 | { 401 | 402 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 403 | QString new_frame = ui_->frame_line_edit->text(); 404 | 405 | // Only take action if the frame has changed. 406 | if((new_frame != frame_id_) && (new_frame != "")) 407 | { 408 | frame_id_ = new_frame; 409 | ROS_INFO("new frame: %s", frame_id_.toStdString().c_str()); 410 | 411 | // update the frames for all interactive markers 412 | std::map::iterator sn_it; 413 | for (sn_it = sn_map_ptr_->begin(); sn_it != sn_map_ptr_->end(); sn_it++) 414 | { 415 | std::stringstream wp_name; 416 | wp_name << "waypoint" << sn_it->first; 417 | std::string wp_name_str(wp_name.str()); 418 | 419 | visualization_msgs::InteractiveMarker int_marker; 420 | if(server_->get(wp_name_str, int_marker)) 421 | { 422 | int_marker.header.frame_id = new_frame.toStdString(); 423 | server_->setPose(wp_name_str, int_marker.pose, int_marker.header); 424 | } 425 | } 426 | server_->applyChanges(); 427 | } 428 | } 429 | 430 | void WaypointFrame::topicChanged() 431 | { 432 | QString new_topic = ui_->topic_line_edit->text(); 433 | 434 | // Only take action if the name has changed. 435 | if(new_topic != output_topic_) 436 | { 437 | wp_pub_.shutdown(); 438 | output_topic_ = new_topic; 439 | 440 | if((output_topic_ != "") && (output_topic_ != "/")) 441 | { 442 | wp_pub_ = nh_.advertise(output_topic_.toStdString(), 1); 443 | } 444 | } 445 | } 446 | 447 | void WaypointFrame::setWpCount(int size) 448 | { 449 | std::ostringstream stringStream; 450 | stringStream << "Total Wp: " << size; 451 | std::string st = stringStream.str(); 452 | 453 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 454 | ui_->waypoint_count_label->setText(QString::fromStdString(st)); 455 | } 456 | 457 | void WaypointFrame::setConfig(QString topic, QString frame, float height) 458 | { 459 | { 460 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 461 | ui_->topic_line_edit->blockSignals(true); 462 | ui_->frame_line_edit->blockSignals(true); 463 | ui_->wp_height_doubleSpinBox->blockSignals(true); 464 | 465 | ui_->topic_line_edit->setText(topic); 466 | ui_->frame_line_edit->setText(frame); 467 | ui_->wp_height_doubleSpinBox->setValue(height); 468 | 469 | ui_->topic_line_edit->blockSignals(false); 470 | ui_->frame_line_edit->blockSignals(false); 471 | ui_->wp_height_doubleSpinBox->blockSignals(false); 472 | 473 | } 474 | topicChanged(); 475 | frameChanged(); 476 | heightChanged(height); 477 | } 478 | 479 | void WaypointFrame::getPose(Ogre::Vector3& position, Ogre::Quaternion& quat) 480 | { 481 | { 482 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 483 | position.x = ui_->x_doubleSpinBox->value(); 484 | position.y = ui_->y_doubleSpinBox->value(); 485 | position.z = ui_->z_doubleSpinBox->value(); 486 | double yaw = ui_->yaw_doubleSpinBox->value(); 487 | 488 | tf::Quaternion qt = tf::createQuaternionFromYaw(yaw); 489 | quat.x = qt.x(); 490 | quat.y = qt.y(); 491 | quat.z = qt.z(); 492 | quat.w = qt.w(); 493 | 494 | } 495 | } 496 | 497 | void WaypointFrame::setPose(const Ogre::Vector3& position, const Ogre::Quaternion& quat) 498 | { 499 | { 500 | //boost::mutex::scoped_lock lock(frame_updates_mutex_); 501 | //block spinbox signals 502 | ui_->x_doubleSpinBox->blockSignals(true); 503 | ui_->y_doubleSpinBox->blockSignals(true); 504 | ui_->z_doubleSpinBox->blockSignals(true); 505 | ui_->yaw_doubleSpinBox->blockSignals(true); 506 | 507 | ui_->x_doubleSpinBox->setValue(position.x); 508 | ui_->y_doubleSpinBox->setValue(position.y); 509 | ui_->z_doubleSpinBox->setValue(position.z); 510 | 511 | tf::Quaternion qt(quat.x, quat.y, quat.z, quat.w); 512 | ui_->yaw_doubleSpinBox->setValue(tf::getYaw(qt)); 513 | 514 | //enable the signals 515 | ui_->x_doubleSpinBox->blockSignals(false); 516 | ui_->y_doubleSpinBox->blockSignals(false); 517 | ui_->z_doubleSpinBox->blockSignals(false); 518 | ui_->yaw_doubleSpinBox->blockSignals(false); 519 | 520 | } 521 | } 522 | 523 | void WaypointFrame::setWpLabel(Ogre::Vector3 position) 524 | { 525 | { 526 | //boost::mutex::scoped_lock lock(frame_updates_mutex_); 527 | std::ostringstream stringStream; 528 | stringStream.precision(2); 529 | stringStream << selected_marker_name_; 530 | //stringStream << " x: " << position.x << " y: " << position.y << " z: " << position.z; 531 | std::string label = stringStream.str(); 532 | 533 | ui_->sel_wp_label->setText(QString::fromStdString(label)); 534 | } 535 | } 536 | 537 | double WaypointFrame::getDefaultHeight() 538 | { 539 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 540 | return default_height_; 541 | } 542 | 543 | QString WaypointFrame::getFrameId() 544 | { 545 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 546 | return frame_id_; 547 | } 548 | 549 | QString WaypointFrame::getOutputTopic() 550 | { 551 | boost::mutex::scoped_lock lock(frame_updates_mutex_); 552 | return output_topic_; 553 | } 554 | } // namespace 555 | -------------------------------------------------------------------------------- /src/waypoint_nav_tool.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2011, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | */ 29 | 30 | /* Author: Dinesh Thakur - Modified for waypoint navigation */ 31 | 32 | #include 33 | #include 34 | #include 35 | 36 | #include 37 | #include 38 | #include 39 | #include 40 | #include 41 | #include 42 | #include 43 | #include 44 | #include 45 | #include 46 | 47 | #include "waypoint_nav_tool.h" 48 | 49 | namespace waypoint_nav_plugin 50 | { 51 | 52 | WaypointNavTool::WaypointNavTool() 53 | : moving_flag_node_(NULL) 54 | , frame_dock_(NULL) 55 | , frame_(NULL) 56 | , server_("waypoint_nav", "", false) 57 | , unique_ind_(0) 58 | { 59 | shortcut_key_ = 'l'; 60 | } 61 | 62 | WaypointNavTool::~WaypointNavTool() 63 | { 64 | M_StringToSNPtr::iterator sn_it; 65 | for(sn_it = sn_map_.begin(); sn_it != sn_map_.end(); sn_it++) 66 | { 67 | scene_manager_->destroySceneNode(sn_it->second); 68 | } 69 | 70 | delete frame_; 71 | delete frame_dock_; 72 | } 73 | 74 | void WaypointNavTool::onInitialize() 75 | { 76 | flag_resource_ = "package://waypoint_navigation_plugin/media/flag.dae"; 77 | 78 | if(rviz::loadMeshFromResource(flag_resource_).isNull()) 79 | { 80 | ROS_ERROR("WaypointNavTool: failed to load model resource '%s'.", flag_resource_.c_str()); 81 | return; 82 | } 83 | 84 | moving_flag_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); 85 | Ogre::Entity* entity = scene_manager_->createEntity(flag_resource_); 86 | moving_flag_node_->attachObject(entity); 87 | moving_flag_node_->setVisible(false); 88 | 89 | rviz::WindowManagerInterface* window_context = context_->getWindowManager(); 90 | frame_ = new WaypointFrame(context_, &sn_map_, &server_, &unique_ind_, NULL, this); 91 | 92 | if (window_context) 93 | frame_dock_ = window_context->addPane("Waypoint Navigation", frame_); 94 | 95 | frame_->enable(); 96 | 97 | //add Delete menu for interactive marker 98 | menu_handler_.insert("Delete", boost::bind(&WaypointNavTool::processFeedback, this, _1)); 99 | menu_handler_.insert("Set Manual", boost::bind(&WaypointNavTool::processFeedback, this, _1)); 100 | } 101 | 102 | // Activation and deactivation 103 | // ^^^^^^^^^^^^^^^^^^^^^^^^^^^ 104 | // 105 | // activate() is called when the tool is started by the user, either 106 | // by clicking on its button in the toolbar or by pressing its hotkey. 107 | // 108 | // First we set the moving flag node to be visible, then we create an 109 | // rviz::VectorProperty to show the user the position of the flag. 110 | // Unlike rviz::Display, rviz::Tool is not a subclass of 111 | // rviz::Property, so when we want to add a tool property we need to 112 | // get the parent container with getPropertyContainer() and add it to 113 | // that. 114 | // 115 | // We wouldn't have to set current_flag_property_ to be read-only, but 116 | // if it were writable the flag should really change position when the 117 | // user edits the property. This is a fine idea, and is possible, but 118 | // is left as an exercise for the reader. 119 | void WaypointNavTool::activate() 120 | { 121 | if(moving_flag_node_) 122 | { 123 | moving_flag_node_->setVisible(true); 124 | } 125 | } 126 | 127 | // deactivate() is called when the tool is being turned off because 128 | // another tool has been chosen. 129 | // 130 | // We make the moving flag invisible, then delete the current flag 131 | // property. Deleting a property also removes it from its parent 132 | // property, so that doesn't need to be done in a separate step. If 133 | // we didn't delete it here, it would stay in the list of waypoints when 134 | // we switch to another tool. 135 | void WaypointNavTool::deactivate() 136 | { 137 | if(moving_flag_node_) 138 | { 139 | moving_flag_node_->setVisible(false); 140 | } 141 | } 142 | 143 | // Handling mouse events 144 | 145 | int WaypointNavTool::processMouseEvent(rviz::ViewportMouseEvent& event) 146 | { 147 | if(!moving_flag_node_) 148 | { 149 | return Render; 150 | } 151 | 152 | double height = frame_->getDefaultHeight(); 153 | Ogre::Vector3 intersection; 154 | Ogre::Quaternion quat; 155 | Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, height); 156 | if(rviz::getPointOnPlaneFromWindowXY(event.viewport, 157 | ground_plane, 158 | event.x, event.y, intersection)) 159 | { 160 | moving_flag_node_->setVisible(true); 161 | moving_flag_node_->setPosition(intersection); 162 | 163 | frame_->setWpLabel(intersection); 164 | 165 | //check if mouse pointer is near existing waypoint 166 | M_StringToSNPtr::iterator sn_it; 167 | for(sn_it = sn_map_.begin(); sn_it != sn_map_.end(); sn_it++) 168 | { 169 | Ogre::Vector3 stored_pos = sn_it->second->getPosition(); 170 | double distance = std::sqrt(pow(stored_pos.x - intersection.x,2) + pow(stored_pos.y - intersection.y,2)); 171 | 172 | if(distance < 0.4) 173 | { 174 | moving_flag_node_->setVisible(false); 175 | 176 | //delete the waypoint if right clicked 177 | if(event.rightDown()) 178 | { 179 | sn_it->second->detachAllObjects(); 180 | std::stringstream wp_name; 181 | wp_name << g_wp_name_prefix << sn_it->first; 182 | std::string wp_name_str(wp_name.str()); 183 | server_.erase(wp_name_str); 184 | server_.applyChanges(); 185 | sn_map_.erase(sn_it); 186 | 187 | moving_flag_node_->setVisible(true); 188 | return Render | Finished; 189 | } 190 | } 191 | } 192 | 193 | //add a waypoint 194 | if(event.leftDown()) 195 | { 196 | makeIm(intersection, quat, frame_->ui_->sixDcheckBox->checkState() == Qt::Checked); 197 | return Render | Finished; 198 | } 199 | } 200 | else 201 | { 202 | moving_flag_node_->setVisible(false); // If the mouse is not pointing at the ground plane, don't show the flag. 203 | } 204 | return Render; 205 | } 206 | 207 | void WaypointNavTool::makeIm(const Ogre::Vector3 &position, 208 | const Ogre::Quaternion &quat, bool full_dof) 209 | { 210 | unique_ind_++; // increment the index for unique marker names 211 | 212 | std::stringstream wp_name; 213 | wp_name << g_wp_name_prefix << unique_ind_; 214 | std::string wp_name_str(wp_name.str()); 215 | 216 | if(rviz::loadMeshFromResource(flag_resource_).isNull()) 217 | { 218 | ROS_ERROR("WaypointNavTool: failed to load model resource '%s'.", flag_resource_.c_str()); 219 | return; 220 | } 221 | 222 | // create a new flag in the Ogre scene and save it in a std::map. 223 | Ogre::SceneNode* sn_ptr = scene_manager_->getRootSceneNode()->createChildSceneNode(); 224 | Ogre::Entity* entity = scene_manager_->createEntity(flag_resource_); 225 | sn_ptr->attachObject(entity); 226 | sn_ptr->setVisible(true); 227 | sn_ptr->setPosition(position); 228 | sn_ptr->setOrientation(quat); 229 | 230 | M_StringToSNPtr::iterator sn_entry = sn_map_.find(unique_ind_); 231 | 232 | if (sn_entry == sn_map_.end()) 233 | sn_map_.insert(std::make_pair(unique_ind_, sn_ptr)); 234 | else{ 235 | ROS_WARN("%s already in map", wp_name_str.c_str()); 236 | return; 237 | } 238 | 239 | int num_wp = sn_map_.size(); 240 | 241 | geometry_msgs::PoseStamped pos; 242 | pos.pose.position.x = position.x; 243 | pos.pose.position.y = position.y; 244 | pos.pose.position.z = position.z; 245 | pos.pose.orientation.x = quat.x; 246 | pos.pose.orientation.y = quat.y; 247 | pos.pose.orientation.z = quat.z; 248 | pos.pose.orientation.w = quat.w; 249 | 250 | frame_->setWpCount(num_wp); 251 | 252 | visualization_msgs::InteractiveMarker int_marker; 253 | int_marker.header.stamp = ros::Time::now(); 254 | int_marker.header.frame_id = frame_->getFrameId().toStdString(); 255 | 256 | int_marker.pose = pos.pose; 257 | int_marker.scale = 2; 258 | int_marker.name = wp_name_str; 259 | //int_marker.description = wp_name_str; 260 | 261 | // create a cylinder marker 262 | visualization_msgs::Marker cyn_marker; 263 | cyn_marker.type = visualization_msgs::Marker::CYLINDER; 264 | cyn_marker.scale.x = 2.0; 265 | cyn_marker.scale.y = 2.0; 266 | cyn_marker.scale.z = 0.2; 267 | cyn_marker.color.r = 0.5; 268 | cyn_marker.color.g = 0.5; 269 | cyn_marker.color.b = 0.5; 270 | cyn_marker.color.a = 0.5; 271 | 272 | // create a non-interactive control which contains the marker 273 | visualization_msgs::InteractiveMarkerControl cyn_control; 274 | cyn_control.always_visible = true; 275 | cyn_control.markers.push_back(cyn_marker); 276 | 277 | // add the control to the interactive marker 278 | int_marker.controls.push_back(cyn_control); 279 | 280 | visualization_msgs::InteractiveMarkerControl control; 281 | control.orientation.w = 0.707106781; 282 | control.orientation.x = 0; 283 | control.orientation.y = 0.707106781; 284 | control.orientation.z = 0; 285 | control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE; 286 | int_marker.controls.push_back(control); 287 | control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS; 288 | int_marker.controls.push_back(control); 289 | 290 | if (full_dof) { 291 | control.orientation.w = 0.707106781; 292 | control.orientation.x = 0.707106781; 293 | control.orientation.y = 0; 294 | control.orientation.z = 0; 295 | control.interaction_mode = 296 | visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE; 297 | int_marker.controls.push_back(control); 298 | control.interaction_mode = 299 | visualization_msgs::InteractiveMarkerControl::MOVE_AXIS; 300 | int_marker.controls.push_back(control); 301 | control.orientation.w = 0.707106781; 302 | control.orientation.x = 0; 303 | control.orientation.y = 0; 304 | control.orientation.z = 0.707106781; 305 | control.interaction_mode = 306 | visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE; 307 | int_marker.controls.push_back(control); 308 | control.interaction_mode = 309 | visualization_msgs::InteractiveMarkerControl::MOVE_AXIS; 310 | int_marker.controls.push_back(control); 311 | } 312 | control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MENU; 313 | control.name = "menu_delete"; 314 | control.description = wp_name_str; 315 | int_marker.controls.push_back(control); 316 | 317 | server_.insert(int_marker); 318 | server_.setCallback(int_marker.name, boost::bind(&WaypointNavTool::processFeedback, this, _1)); 319 | menu_handler_.apply(server_, int_marker.name); 320 | 321 | //Set the current marker as selected 322 | Ogre::Vector3 p = position; 323 | Ogre::Quaternion q = quat; 324 | frame_->setSelectedMarkerName(wp_name_str); 325 | frame_->setWpLabel(p); 326 | frame_->setPose(p, q); 327 | 328 | server_.applyChanges(); 329 | } 330 | 331 | void WaypointNavTool::processFeedback( 332 | const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) 333 | { 334 | switch (feedback->event_type) 335 | { 336 | case visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT: 337 | { 338 | 339 | M_StringToSNPtr::iterator sn_entry = 340 | sn_map_.find(std::stoi(feedback->marker_name.substr(strlen(g_wp_name_prefix)))); 341 | if (sn_entry == sn_map_.end()) 342 | ROS_ERROR("%s not found in map", feedback->marker_name.c_str()); 343 | else 344 | { 345 | 346 | if(feedback->menu_entry_id == 1) 347 | { 348 | //Delete selected waypoint 349 | std::stringstream wp_name; 350 | wp_name << g_wp_name_prefix << sn_entry->first; 351 | std::string wp_name_str(wp_name.str()); 352 | server_.erase(wp_name_str); 353 | 354 | menu_handler_.reApply(server_); 355 | server_.applyChanges(); 356 | sn_entry->second->detachAllObjects(); 357 | sn_map_.erase(sn_entry); 358 | 359 | int num_wp = sn_map_.size(); 360 | frame_->setWpCount(num_wp); 361 | 362 | } 363 | else 364 | { 365 | //Set the pose manually from the line edits 366 | Ogre::Vector3 position; 367 | Ogre::Quaternion quat; 368 | 369 | frame_->getPose(position, quat); 370 | 371 | geometry_msgs::Pose pos; 372 | pos.position.x = position.x; 373 | pos.position.y = position.y; 374 | pos.position.z = position.z; 375 | 376 | pos.orientation.x = quat.x; 377 | pos.orientation.y = quat.y; 378 | pos.orientation.z = quat.z; 379 | pos.orientation.w = quat.w; 380 | 381 | sn_entry->second->setPosition(position); 382 | sn_entry->second->setOrientation(quat); 383 | 384 | frame_->setWpLabel(position); 385 | 386 | server_.setPose(feedback->marker_name, pos); 387 | server_.applyChanges(); 388 | } 389 | } 390 | } 391 | break; 392 | case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE: 393 | { 394 | M_StringToSNPtr::iterator sn_entry = sn_map_.find(std::stoi(feedback->marker_name.substr(strlen(g_wp_name_prefix)))); 395 | 396 | if (sn_entry == sn_map_.end()) 397 | ROS_ERROR("%s not found in map", feedback->marker_name.c_str()); 398 | else 399 | { 400 | geometry_msgs::PoseStamped pos; 401 | pos.pose = feedback->pose; 402 | 403 | Ogre::Vector3 position; 404 | position.x = pos.pose.position.x; 405 | position.y = pos.pose.position.y; 406 | position.z = pos.pose.position.z; 407 | 408 | sn_entry->second->setPosition(position); 409 | 410 | Ogre::Quaternion quat; 411 | quat.x = pos.pose.orientation.x; 412 | quat.y = pos.pose.orientation.y; 413 | quat.z = pos.pose.orientation.z; 414 | quat.w = pos.pose.orientation.w; 415 | 416 | sn_entry->second->setOrientation(quat); 417 | 418 | frame_->setWpLabel(position); 419 | frame_->setPose(position, quat); 420 | frame_->setSelectedMarkerName(feedback->marker_name); 421 | 422 | } 423 | } 424 | break; 425 | } 426 | } 427 | 428 | void WaypointNavTool::getMarkerPoses() 429 | { 430 | M_StringToSNPtr::iterator sn_it; 431 | for (sn_it = sn_map_.begin(); sn_it != sn_map_.end(); sn_it++) 432 | { 433 | visualization_msgs::InteractiveMarker int_marker; 434 | 435 | std::stringstream wp_name; 436 | wp_name << g_wp_name_prefix << sn_it->first; 437 | std::string wp_name_str(wp_name.str()); 438 | server_.get(wp_name_str, int_marker); 439 | 440 | ROS_ERROR("pos: %g %g %g", int_marker.pose.position.x, 441 | int_marker.pose.position.y, 442 | int_marker.pose.position.z); 443 | } 444 | } 445 | 446 | void WaypointNavTool::clearAllWaypoints() 447 | { 448 | M_StringToSNPtr::iterator sn_it; 449 | for (sn_it = sn_map_.begin(); sn_it != sn_map_.end(); sn_it++) 450 | { 451 | scene_manager_->destroySceneNode(sn_it->second); 452 | } 453 | sn_map_.clear(); 454 | unique_ind_ = 0; 455 | } 456 | 457 | // Loading and saving the waypoints 458 | // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 459 | // 460 | // Tools with a fixed set of Property objects representing adjustable 461 | // parameters are typically just created in the tool's constructor and 462 | // added to the Property container (getPropertyContainer()). In that 463 | // case, the Tool subclass does not need to override load() and save() 464 | // because the default behavior is to read all the Properties in the 465 | // container from the Config object. 466 | // 467 | // Here however, we have a list of named waypoint positions of unknown 468 | // length, so we need to implement save() and load() ourselves. 469 | // 470 | // We first save the class ID to the config object so the 471 | // rviz::ToolManager will know what to instantiate when the config 472 | // file is read back in. 473 | void WaypointNavTool::save(rviz::Config config) const 474 | { 475 | config.mapSetValue("Class", getClassId()); 476 | //rviz::Config waypoints_config = config.mapMakeChild("Waypoints"); 477 | 478 | rviz::Config waypoints_config = config.mapMakeChild("WaypointsTool"); 479 | 480 | waypoints_config.mapSetValue("topic", frame_->getOutputTopic()); 481 | waypoints_config.mapSetValue("frame_id", frame_->getFrameId()); 482 | waypoints_config.mapSetValue("default_height", frame_->getDefaultHeight()); 483 | 484 | /* 485 | // The top level of this tool's Config is a map, but our waypoints 486 | // should go in a list, since they may or may not have unique keys. 487 | // Therefore we make a child of the map (``waypoints_config``) to store 488 | // the list. 489 | rviz::Config waypoints_config = config.mapMakeChild("Waypoints"); 490 | 491 | // To read the positions and names of the waypoints, we loop over the 492 | // the children of our Property container: 493 | rviz::Property* container = getPropertyContainer(); 494 | int num_children = container->numChildren(); 495 | for(int i = 0; i < num_children; i++) 496 | { 497 | rviz::Property* position_prop = container->childAt(i); 498 | // For each Property, we create a new Config object representing a 499 | // single waypoint and append it to the Config list. 500 | rviz::Config waypoint_config = waypoints_config.listAppendNew(); 501 | // Into the waypoint's config we store its name: 502 | waypoint_config.mapSetValue("Name", position_prop->getName()); 503 | // ... and its position. 504 | position_prop->save(waypoint_config); 505 | } 506 | */ 507 | } 508 | 509 | // In a tool's load() function, we don't need to read its class 510 | // because that has already been read and used to instantiate the 511 | // object before this can have been called. 512 | void WaypointNavTool::load(const rviz::Config& config) 513 | { 514 | rviz::Config waypoints_config = config.mapGetChild("WaypointsTool"); 515 | 516 | QString topic, frame; 517 | float height; 518 | if(!waypoints_config.mapGetString("topic", &topic)) 519 | topic = "/waypoints"; 520 | 521 | if(!waypoints_config.mapGetString("frame_id", &frame)) 522 | frame = "map"; 523 | 524 | waypoints_config.mapGetFloat("default_height", &height); 525 | 526 | frame_->setConfig(topic, frame, height); 527 | 528 | /* 529 | // Here we get the "waypoints" sub-config from the tool config and loop over its entries: 530 | rviz::Config waypoints_config = config.mapGetChild("waypoints"); 531 | int num_waypoints = waypoints_config.listLength(); 532 | for(int i = 0; i < num_waypoints; i++) 533 | { 534 | rviz::Config waypoint_config = waypoints_config.listChildAt(i); 535 | // At this point each ``waypoint_config`` represents a single waypoint. 536 | // 537 | // Here we provide a default name in case the name is not in the config file for some reason: 538 | QString name = "waypoint " + QString::number(i + 1); 539 | // Then we use the convenience function mapGetString() to read the 540 | // name from ``waypoint_config`` if it is there. (If no "Name" entry 541 | // were present it would return false, but we don't care about 542 | // that because we have already set a default.) 543 | waypoint_config.mapGetString("Name", &name); 544 | // Given the name we can create an rviz::VectorProperty to display the position: 545 | rviz::VectorProperty* prop = new rviz::VectorProperty(name); 546 | // Then we just tell the property to read its contents from the config, and we've read all the data. 547 | prop->load(waypoint_config); 548 | // We finish each waypoint by marking it read-only (as discussed 549 | // above), adding it to the property container, and finally making 550 | // an actual visible waypoint object in the 3D scene at the correct 551 | // position. 552 | prop->setReadOnly(true); 553 | getPropertyContainer()->addChild(prop); 554 | //makewaypoint(prop->getVector()); 555 | }*/ 556 | } 557 | 558 | } // end namespace 559 | 560 | #include 561 | PLUGINLIB_EXPORT_CLASS(waypoint_nav_plugin::WaypointNavTool,rviz::Tool) 562 | 563 | -------------------------------------------------------------------------------- /media/flag.dae: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | Blender User 6 | Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b 7 | 8 | 2015-12-08T00:53:53 9 | 2015-12-08T00:53:53 10 | 11 | Z_UP 12 | 13 | 14 | 15 | 16 | 17 | 18 | 49.13434 19 | 1.777778 20 | 0.1 21 | 100 22 | 23 | 24 | 25 | 26 | 27 | 0 28 | 0 29 | 0 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 1 1 1 39 | 1 40 | 0 41 | 0.00111109 42 | 43 | 44 | 45 | 46 | 0.000999987 47 | 1 48 | 0.1 49 | 0.1 50 | 1 51 | 1 52 | 1 53 | 2 54 | 0 55 | 1 56 | 1 57 | 1 58 | 1 59 | 1 60 | 0 61 | 2880 62 | 2 63 | 30.002 64 | 1.000799 65 | 0.04999995 66 | 29.99998 67 | 1 68 | 2 69 | 0 70 | 0 71 | 1 72 | 1 73 | 1 74 | 1 75 | 8192 76 | 1 77 | 1 78 | 0 79 | 1 80 | 1 81 | 1 82 | 3 83 | 0 84 | 0 85 | 0 86 | 0 87 | 0 88 | 1 89 | 1 90 | 1 91 | 3 92 | 0.15 93 | 75 94 | 1 95 | 1 96 | 0 97 | 1 98 | 1 99 | 0 100 | 101 | 102 | 103 | 104 | 105 | 106 | 1 1 1 107 | 108 | 109 | 110 | 111 | 0.000999987 112 | 0 113 | 0.1 114 | 0.1 115 | 0.1 116 | 1 117 | 1 118 | 2 119 | 0 120 | 1 121 | 1 122 | 1 123 | 1 124 | 1 125 | 0 126 | 512 127 | 2 128 | 40 129 | 0.5 130 | 0.04999995 131 | 2500 132 | 1 133 | 2 134 | 0 135 | 0 136 | 1 137 | 1 138 | 1 139 | 1 140 | 4097 141 | 1 142 | 1 143 | 0 144 | 1 145 | 1 146 | 1 147 | 3 148 | 0 149 | 0 150 | 0 151 | 0 152 | 2 153 | 1 154 | 1 155 | 1 156 | 3 157 | 0.15 158 | 45 159 | 1 160 | 1 161 | 0 162 | 1 163 | 1 164 | 1 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 0 0 0 1 177 | 178 | 179 | 0 0 0 1 180 | 181 | 182 | 0.8 0 0 1 183 | 184 | 185 | 0.25 0.25 0.25 1 186 | 187 | 188 | 12 189 | 190 | 191 | 1 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 0 0 0 1 203 | 204 | 205 | 0 0 0 1 206 | 207 | 208 | 0.8 0.2408161 0.6526382 1 209 | 210 | 211 | 0.25 0.25 0.25 1 212 | 213 | 214 | 12 215 | 216 | 217 | 1 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | 232 | 233 | 234 | 235 | 236 | 1 0 0.006209969 -1 0 -0.99379 -1 0 1.00621 -1 0.05589997 1.00621 -1 0.05589997 -0.99379 1 0.05589997 0.006209969 237 | 238 | 239 | 240 | 241 | 242 | 243 | 244 | 245 | 246 | 0 -1 0 0.4472136 0 -0.8944272 0.4472136 0 -0.8944272 -1 0 0 -1 0 0 0.4472135 0 0.8944272 0.4472135 0 0.8944272 0 1 0 247 | 248 | 249 | 250 | 251 | 252 | 253 | 254 | 255 | 256 | 257 | 258 | 259 | 260 | 261 | 3 3 3 3 3 3 3 3 262 |

1 0 0 0 2 0 0 1 1 1 4 1 4 2 5 2 0 2 1 3 2 3 3 3 3 4 4 4 1 4 2 5 0 5 5 5 5 6 3 6 2 6 3 7 5 7 4 7

263 |
264 |
265 |
266 | 267 | 268 | 269 | 0.03535997 0.03535997 -1 0.04156994 0.02777999 -1 0.04618996 0.01912999 -1 0.04903995 0.009749948 -1 0.04999995 0 -1 0.04903995 -0.009749948 -1 0.04618996 -0.01912999 -1 0.04156994 -0.02777999 -1 0.03535997 -0.03535997 -1 0.02777999 -0.04156994 -1 0.01912999 -0.04618996 -1 0.009749948 -0.04903995 -1 0 -0.04999995 -1 -0.009749948 -0.04903995 -1 -0.01912999 -0.04618996 -1 -0.02777999 -0.04156994 -1 -0.03535997 -0.03535997 -1 -0.04156994 -0.02777999 -1 -0.04618996 -0.01912999 -1 -0.04903995 -0.009749948 -1 -0.04999995 0 -1 -0.04903995 0.009749948 -1 -0.04618996 0.01912999 -1 -0.04156994 0.02777999 -1 -0.03535997 0.03535997 -1 -0.02777999 0.04156994 -1 -0.01912999 0.04618996 -1 -0.009749948 0.04903995 -1 0 0.04999995 -1 0.009749948 0.04903995 -1 0.01912999 0.04618996 -1 0.02777999 0.04156994 -1 0.03535997 0.03535997 1 0.04156994 0.02777999 1 0.04618996 0.01912999 1 0.04903995 0.009749948 1 0.04999995 0 1 0.04903995 -0.009749948 1 0.04618996 -0.01912999 1 0.04156994 -0.02777999 1 0.03535997 -0.03535997 1 0.02777999 -0.04156994 1 0.01912999 -0.04618996 1 0.009749948 -0.04903995 1 0 -0.04999995 1 -0.009749948 -0.04903995 1 -0.01912999 -0.04618996 1 -0.02777999 -0.04156994 1 -0.03535997 -0.03535997 1 -0.04156994 -0.02777999 1 -0.04618996 -0.01912999 1 -0.04903995 -0.009749948 1 -0.04999995 0 1 -0.04903995 0.009749948 1 -0.04618996 0.01912999 1 -0.04156994 0.02777999 1 -0.03535997 0.03535997 1 -0.02777999 0.04156994 1 -0.01912999 0.04618996 1 -0.009749948 0.04903995 1 0 0.04999995 1 0.009749948 0.04903995 1 0.01912999 0.04618996 1 0.02777999 0.04156994 1 0 0 -1 0 0 1 270 | 271 | 272 | 273 | 274 | 275 | 276 | 277 | 278 | 279 | 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0.773548 0.6337377 0 0.773548 0.6337377 0 0.8820705 0.4711175 0 0.8820705 0.4711175 0 0.9568096 0.290715 0 0.9568096 0.290715 0 0.9951876 0.09798765 0 0.9951876 0.09798765 0 0.9951876 -0.09798765 0 0.9951876 -0.09798765 0 0.9568096 -0.290715 0 0.9568096 -0.290715 0 0.8820705 -0.4711175 0 0.8820705 -0.4711175 0 0.773548 -0.6337377 0 0.773548 -0.6337377 0 0.6337377 -0.773548 0 0.6337377 -0.773548 0 0.4711175 -0.8820705 0 0.4711175 -0.8820705 0 0.290715 -0.9568096 0 0.290715 -0.9568096 0 0.09798765 -0.9951876 0 0.09798765 -0.9951876 0 -0.09798765 -0.9951876 0 -0.09798765 -0.9951876 0 -0.290715 -0.9568096 0 -0.290715 -0.9568096 0 -0.4711175 -0.8820705 0 -0.4711175 -0.8820705 0 -0.6337377 -0.773548 0 -0.6337377 -0.773548 0 -0.773548 -0.6337377 0 -0.773548 -0.6337377 0 -0.8820705 -0.4711175 0 -0.8820705 -0.4711175 0 -0.9568096 -0.290715 0 -0.9568096 -0.290715 0 -0.9951876 -0.09798765 0 -0.9951876 -0.09798765 0 -0.9951876 0.09798765 0 -0.9951876 0.09798765 0 -0.9568096 0.290715 0 -0.9568096 0.290715 0 -0.8820705 0.4711175 0 -0.8820705 0.4711175 0 -0.773548 0.6337377 0 -0.773548 0.6337377 0 -0.6337377 0.773548 0 -0.6337377 0.773548 0 -0.4711175 0.8820705 0 -0.4711175 0.8820705 0 -0.290715 0.9568096 0 -0.290715 0.9568096 0 -0.09798765 0.9951876 0 -0.09798765 0.9951876 0 0.09798765 0.9951876 0 0.09798765 0.9951876 0 0.290715 0.9568096 0 0.290715 0.9568096 0 0.4711175 0.8820705 0 0.4711175 0.8820705 0 0.6337377 0.773548 0 0.6337377 0.773548 0 280 | 281 | 282 | 283 | 284 | 285 | 286 | 287 | 288 | 289 | 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 0 0 1 0 1 1 1 1 0 1 0 0 290 | 291 | 292 | 293 | 294 | 295 | 296 | 297 | 298 | 299 | 300 | 301 | 302 | 303 | 304 | 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 305 |

64 0 0 0 0 1 1 0 2 65 1 3 33 1 4 32 1 5 64 2 6 1 2 7 2 2 8 65 3 9 34 3 10 33 3 11 64 4 12 2 4 13 3 4 14 65 5 15 35 5 16 34 5 17 64 6 18 3 6 19 4 6 20 65 7 21 36 7 22 35 7 23 64 8 24 4 8 25 5 8 26 65 9 27 37 9 28 36 9 29 64 10 30 5 10 31 6 10 32 65 11 33 38 11 34 37 11 35 64 12 36 6 12 37 7 12 38 65 13 39 39 13 40 38 13 41 64 14 42 7 14 43 8 14 44 65 15 45 40 15 46 39 15 47 64 16 48 8 16 49 9 16 50 65 17 51 41 17 52 40 17 53 64 18 54 9 18 55 10 18 56 65 19 57 42 19 58 41 19 59 64 20 60 10 20 61 11 20 62 65 21 63 43 21 64 42 21 65 64 22 66 11 22 67 12 22 68 65 23 69 44 23 70 43 23 71 64 24 72 12 24 73 13 24 74 65 25 75 45 25 76 44 25 77 64 26 78 13 26 79 14 26 80 65 27 81 46 27 82 45 27 83 64 28 84 14 28 85 15 28 86 65 29 87 47 29 88 46 29 89 64 30 90 15 30 91 16 30 92 65 31 93 48 31 94 47 31 95 64 32 96 16 32 97 17 32 98 65 33 99 49 33 100 48 33 101 64 34 102 17 34 103 18 34 104 65 35 105 50 35 106 49 35 107 64 36 108 18 36 109 19 36 110 65 37 111 51 37 112 50 37 113 64 38 114 19 38 115 20 38 116 65 39 117 52 39 118 51 39 119 64 40 120 20 40 121 21 40 122 65 41 123 53 41 124 52 41 125 64 42 126 21 42 127 22 42 128 65 43 129 54 43 130 53 43 131 64 44 132 22 44 133 23 44 134 65 45 135 55 45 136 54 45 137 64 46 138 23 46 139 24 46 140 65 47 141 56 47 142 55 47 143 64 48 144 24 48 145 25 48 146 65 49 147 57 49 148 56 49 149 64 50 150 25 50 151 26 50 152 65 51 153 58 51 154 57 51 155 64 52 156 26 52 157 27 52 158 65 53 159 59 53 160 58 53 161 64 54 162 27 54 163 28 54 164 65 55 165 60 55 166 59 55 167 64 56 168 28 56 169 29 56 170 65 57 171 61 57 172 60 57 173 64 58 174 29 58 175 30 58 176 65 59 177 62 59 178 61 59 179 64 60 180 30 60 181 31 60 182 65 61 183 63 61 184 62 61 185 31 62 186 0 62 187 64 62 188 65 63 189 32 63 190 63 63 191 0 64 192 32 64 193 33 64 194 33 65 195 1 65 196 0 65 197 1 66 198 33 66 199 34 66 200 34 67 201 2 67 202 1 67 203 2 68 204 34 68 205 35 68 206 35 69 207 3 69 208 2 69 209 3 70 210 35 70 211 36 70 212 36 71 213 4 71 214 3 71 215 4 72 216 36 72 217 37 72 218 37 73 219 5 73 220 4 73 221 5 74 222 37 74 223 38 74 224 38 75 225 6 75 226 5 75 227 6 76 228 38 76 229 39 76 230 39 77 231 7 77 232 6 77 233 7 78 234 39 78 235 40 78 236 40 79 237 8 79 238 7 79 239 8 80 240 40 80 241 41 80 242 41 81 243 9 81 244 8 81 245 9 82 246 41 82 247 42 82 248 42 83 249 10 83 250 9 83 251 10 84 252 42 84 253 43 84 254 43 85 255 11 85 256 10 85 257 11 86 258 43 86 259 44 86 260 44 87 261 12 87 262 11 87 263 12 88 264 44 88 265 45 88 266 45 89 267 13 89 268 12 89 269 13 90 270 45 90 271 46 90 272 46 91 273 14 91 274 13 91 275 14 92 276 46 92 277 47 92 278 47 93 279 15 93 280 14 93 281 15 94 282 47 94 283 48 94 284 48 95 285 16 95 286 15 95 287 16 96 288 48 96 289 49 96 290 49 97 291 17 97 292 16 97 293 17 98 294 49 98 295 50 98 296 50 99 297 18 99 298 17 99 299 18 100 300 50 100 301 51 100 302 51 101 303 19 101 304 18 101 305 19 102 306 51 102 307 52 102 308 52 103 309 20 103 310 19 103 311 20 104 312 52 104 313 53 104 314 53 105 315 21 105 316 20 105 317 21 106 318 53 106 319 54 106 320 54 107 321 22 107 322 21 107 323 22 108 324 54 108 325 55 108 326 55 109 327 23 109 328 22 109 329 23 110 330 55 110 331 56 110 332 56 111 333 24 111 334 23 111 335 24 112 336 56 112 337 57 112 338 57 113 339 25 113 340 24 113 341 25 114 342 57 114 343 58 114 344 58 115 345 26 115 346 25 115 347 26 116 348 58 116 349 59 116 350 59 117 351 27 117 352 26 117 353 27 118 354 59 118 355 60 118 356 60 119 357 28 119 358 27 119 359 28 120 360 60 120 361 61 120 362 61 121 363 29 121 364 28 121 365 29 122 366 61 122 367 62 122 368 62 123 369 30 123 370 29 123 371 30 124 372 62 124 373 63 124 374 63 125 375 31 125 376 30 125 377 32 126 378 0 126 379 31 126 380 31 127 381 63 127 382 32 127 383

306 |
307 |
308 |
309 |
310 | 311 | 312 | 313 | 314 | 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 315 | 316 | 317 | 318 | -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 319 | 320 | 321 | 322 | 0.01 0 0 -0.0029478 0 0.01 0 -0.0199835 0 0 0.01 0.0270248 0 0 0 1 323 | 324 | 325 | 326 | 0.0018803 0 0 0.0022856 0 0.0018803 0 3.72e-5 0 0 0.0018803 0.0180362 0 0 0 1 327 | 328 | 329 | 330 | 331 | 332 | 333 | 334 | 335 | 336 | 0.01 0 0 5.8e-5 0 0.01 0 1.041e-4 0 0 0.01 0.0099794 0 0 0 1 337 | 338 | 339 | 340 | 341 | 342 | 343 | 344 | 345 | 346 | 347 | 348 | 349 | 350 |
-------------------------------------------------------------------------------- /media/flag.dae.bak: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com 6 | Blender v:249 - Illusoft Collada Exporter v:0.3.162 7 | 8 | 9 | file:///u/hersh/flag.blend 10 | 11 | 2011-03-16T15:32:31.374173 12 | 2011-03-16T15:32:31.374204 13 | Z_UP 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 0.00000 0.00000 0.00000 1 22 | 23 | 24 | 0.04706 0.37059 0.44706 1 25 | 26 | 27 | 0.09412 0.74118 0.89412 1 28 | 29 | 30 | 0.50000 0.50000 0.50000 1 31 | 32 | 33 | 12.5 34 | 35 | 36 | 1.00000 1.00000 1.00000 1 37 | 38 | 39 | 0.0 40 | 41 | 42 | 1 1 1 1 43 | 44 | 45 | 0.5 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 0.00000 0.00000 0.00000 1 57 | 58 | 59 | 0.50000 0.00000 0.00000 1 60 | 61 | 62 | 1.00000 0.00000 0.00000 1 63 | 64 | 65 | 0.50000 0.50000 0.50000 1 66 | 67 | 68 | 12.5 69 | 70 | 71 | 1.00000 1.00000 1.00000 1 72 | 73 | 74 | 0.0 75 | 76 | 77 | 1 1 1 1 78 | 79 | 80 | 0.0 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 0.00000 0.00000 0.00000 1 92 | 93 | 94 | 0.50000 0.50000 0.50000 1 95 | 96 | 97 | 1.00000 1.00000 1.00000 1 98 | 99 | 100 | 0.50000 0.50000 0.50000 1 101 | 102 | 103 | 12.5 104 | 105 | 106 | 1.00000 1.00000 1.00000 1 107 | 108 | 109 | 0.0 110 | 111 | 112 | 1 1 1 1 113 | 114 | 115 | 0.0 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 1.00000 1.00000 1.00000 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 0.70711 0.70711 -0.01000 0.83147 0.55557 -0.01000 0.92388 0.38268 -0.01000 0.98079 0.19509 -0.01000 1.00000 0.00000 -0.01000 0.98079 -0.19509 -0.01000 0.92388 -0.38268 -0.01000 0.83147 -0.55557 -0.01000 0.70711 -0.70711 -0.01000 0.55557 -0.83147 -0.01000 0.38268 -0.92388 -0.01000 0.19509 -0.98079 -0.01000 -0.00000 -1.00000 -0.01000 -0.19509 -0.98079 -0.01000 -0.38268 -0.92388 -0.01000 -0.55557 -0.83147 -0.01000 -0.70711 -0.70711 -0.01000 -0.83147 -0.55557 -0.01000 -0.92388 -0.38268 -0.01000 -0.98079 -0.19509 -0.01000 -1.00000 0.00000 -0.01000 -0.98079 0.19509 -0.01000 -0.92388 0.38268 -0.01000 -0.83147 0.55557 -0.01000 -0.70711 0.70711 -0.01000 -0.55557 0.83147 -0.01000 -0.38268 0.92388 -0.01000 -0.19509 0.98079 -0.01000 0.00000 1.00000 -0.01000 0.19509 0.98078 -0.01000 0.38269 0.92388 -0.01000 0.55557 0.83147 -0.01000 0.70711 0.70711 0.01000 0.83147 0.55557 0.01000 0.92388 0.38268 0.01000 0.98079 0.19509 0.01000 1.00000 -0.00000 0.01000 0.98078 -0.19509 0.01000 0.92388 -0.38268 0.01000 0.83147 -0.55557 0.01000 0.70711 -0.70711 0.01000 0.55557 -0.83147 0.01000 0.38268 -0.92388 0.01000 0.19509 -0.98079 0.01000 0.00000 -1.00000 0.01000 -0.19509 -0.98079 0.01000 -0.38268 -0.92388 0.01000 -0.55557 -0.83147 0.01000 -0.70710 -0.70711 0.01000 -0.83147 -0.55557 0.01000 -0.92388 -0.38269 0.01000 -0.98078 -0.19509 0.01000 -1.00000 -0.00000 0.01000 -0.98079 0.19509 0.01000 -0.92388 0.38268 0.01000 -0.83147 0.55557 0.01000 -0.70711 0.70710 0.01000 -0.55558 0.83147 0.01000 -0.38269 0.92388 0.01000 -0.19510 0.98078 0.01000 -0.00001 1.00000 0.01000 0.19508 0.98079 0.01000 0.38268 0.92388 0.01000 0.55556 0.83147 0.01000 0.00000 0.00000 -0.01000 0.00000 0.00000 0.01000 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.77301 0.63439 0.00000 0.88192 0.47140 -0.00000 0.95694 0.29028 -0.00000 0.99518 0.09802 -0.00000 0.99518 -0.09802 -0.00000 0.95694 -0.29029 -0.00000 0.88192 -0.47140 -0.00000 0.77301 -0.63439 -0.00000 0.63439 -0.77301 -0.00000 0.47140 -0.88192 -0.00000 0.29028 -0.95694 -0.00000 0.09802 -0.99518 -0.00000 -0.09802 -0.99518 -0.00000 -0.29028 -0.95694 -0.00000 -0.47140 -0.88192 -0.00000 -0.63439 -0.77301 0.00000 -0.77301 -0.63439 0.00000 -0.88192 -0.47140 0.00000 -0.95694 -0.29029 -0.00000 -0.99518 -0.09802 -0.00000 -0.99518 0.09802 -0.00000 -0.95694 0.29028 -0.00000 -0.88192 0.47139 -0.00000 -0.77301 0.63439 -0.00000 -0.63440 0.77301 -0.00000 -0.47140 0.88192 -0.00000 -0.29029 0.95694 -0.00000 -0.09802 0.99518 -0.00000 0.09801 0.99519 -0.00000 0.29028 0.95694 -0.00000 0.47139 0.88192 -0.00000 0.63439 0.77301 0.00003 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 |

64 0 0 0 0 1 1 0 2 65 1 3 33 1 4 32 1 5 64 2 6 1 2 7 2 2 8 65 3 9 34 3 10 33 3 11 64 4 12 2 4 13 3 4 14 65 5 15 35 5 16 34 5 17 64 6 18 3 6 19 4 6 20 65 7 21 36 7 22 35 7 23 64 8 24 4 8 25 5 8 26 65 9 27 37 9 28 36 9 29 64 10 30 5 10 31 6 10 32 65 11 33 38 11 34 37 11 35 64 12 36 6 12 37 7 12 38 65 13 39 39 13 40 38 13 41 64 14 42 7 14 43 8 14 44 65 15 45 40 15 46 39 15 47 64 16 48 8 16 49 9 16 50 65 17 51 41 17 52 40 17 53 64 18 54 9 18 55 10 18 56 65 19 57 42 19 58 41 19 59 64 20 60 10 20 61 11 20 62 65 21 63 43 21 64 42 21 65 64 22 66 11 22 67 12 22 68 65 23 69 44 23 70 43 23 71 64 24 72 12 24 73 13 24 74 65 25 75 45 25 76 44 25 77 64 26 78 13 26 79 14 26 80 65 27 81 46 27 82 45 27 83 64 28 84 14 28 85 15 28 86 65 29 87 47 29 88 46 29 89 64 30 90 15 30 91 16 30 92 65 31 93 48 31 94 47 31 95 64 32 96 16 32 97 17 32 98 65 33 99 49 33 100 48 33 101 64 34 102 17 34 103 18 34 104 65 35 105 50 35 106 49 35 107 64 36 108 18 36 109 19 36 110 65 37 111 51 37 112 50 37 113 64 38 114 19 38 115 20 38 116 65 39 117 52 39 118 51 39 119 64 40 120 20 40 121 21 40 122 65 41 123 53 41 124 52 41 125 64 42 126 21 42 127 22 42 128 65 43 129 54 43 130 53 43 131 64 44 132 22 44 133 23 44 134 65 45 135 55 45 136 54 45 137 64 46 138 23 46 139 24 46 140 65 47 141 56 47 142 55 47 143 64 48 144 24 48 145 25 48 146 65 49 147 57 49 148 56 49 149 64 50 150 25 50 151 26 50 152 65 51 153 58 51 154 57 51 155 64 52 156 26 52 157 27 52 158 65 53 159 59 53 160 58 53 161 64 54 162 27 54 163 28 54 164 65 55 165 60 55 166 59 55 167 64 56 168 28 56 169 29 56 170 65 57 171 61 57 172 60 57 173 64 58 174 29 58 175 30 58 176 65 59 177 62 59 178 61 59 179 64 60 180 30 60 181 31 60 182 65 61 183 63 61 184 62 61 185 31 62 186 0 62 187 64 62 188 65 63 189 32 63 190 63 63 191 0 64 192 32 64 193 33 64 194 33 64 195 1 64 196 0 64 197 1 65 198 33 65 199 34 65 200 34 65 201 2 65 202 1 65 203 2 66 204 34 66 205 35 66 206 35 66 207 3 66 208 2 66 209 3 67 210 35 67 211 36 67 212 36 67 213 4 67 214 3 67 215 4 68 216 36 68 217 37 68 218 37 68 219 5 68 220 4 68 221 5 69 222 37 69 223 38 69 224 38 69 225 6 69 226 5 69 227 6 70 228 38 70 229 39 70 230 39 70 231 7 70 232 6 70 233 7 71 234 39 71 235 40 71 236 40 71 237 8 71 238 7 71 239 8 72 240 40 72 241 41 72 242 41 72 243 9 72 244 8 72 245 9 73 246 41 73 247 42 73 248 42 73 249 10 73 250 9 73 251 10 74 252 42 74 253 43 74 254 43 74 255 11 74 256 10 74 257 11 75 258 43 75 259 44 75 260 44 75 261 12 75 262 11 75 263 12 76 264 44 76 265 45 76 266 45 76 267 13 76 268 12 76 269 13 77 270 45 77 271 46 77 272 46 77 273 14 77 274 13 77 275 14 78 276 46 78 277 47 78 278 47 78 279 15 78 280 14 78 281 15 79 282 47 79 283 48 79 284 48 79 285 16 79 286 15 79 287 16 80 288 48 80 289 49 80 290 49 80 291 17 80 292 16 80 293 17 81 294 49 81 295 50 81 296 50 81 297 18 81 298 17 81 299 18 82 300 50 82 301 51 82 302 51 82 303 19 82 304 18 82 305 19 83 306 51 83 307 52 83 308 52 83 309 20 83 310 19 83 311 20 84 312 52 84 313 53 84 314 53 84 315 21 84 316 20 84 317 21 85 318 53 85 319 54 85 320 54 85 321 22 85 322 21 85 323 22 86 324 54 86 325 55 86 326 55 86 327 23 86 328 22 86 329 23 87 330 55 87 331 56 87 332 56 87 333 24 87 334 23 87 335 24 88 336 56 88 337 57 88 338 57 88 339 25 88 340 24 88 341 25 89 342 57 89 343 58 89 344 58 89 345 26 89 346 25 89 347 26 90 348 58 90 349 59 90 350 59 90 351 27 90 352 26 90 353 27 91 354 59 91 355 60 91 356 60 91 357 28 91 358 27 91 359 28 92 360 60 92 361 61 92 362 61 92 363 29 92 364 28 92 365 29 93 366 61 93 367 62 93 368 62 93 369 30 93 370 29 93 371 30 94 372 62 94 373 63 94 374 63 94 375 31 94 376 30 94 377 32 95 378 0 95 379 31 95 380 31 95 381 63 95 382 32 95 383

182 |
183 |
184 |
185 | 186 | 187 | 188 | 1.00000 0.00000 0.00621 -1.00000 -0.00000 -0.99379 -1.00000 0.00000 1.00621 -1.00000 0.05590 1.00621 -1.00000 0.05590 -0.99379 1.00000 0.05590 0.00621 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 0.00000 -1.00000 0.00000 0.44721 0.00000 -0.89443 -1.00000 0.00000 0.00000 0.44721 0.00000 0.89443 -0.00000 1.00000 -0.00000 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 |

1 0 0 0 2 0 0 1 1 1 4 1 4 1 5 1 0 1 1 2 2 2 3 2 3 2 4 2 1 2 2 3 0 3 5 3 5 3 3 3 2 3 3 4 5 4 4 4

214 |
215 |
216 |
217 | 218 | 219 | 220 | 0.03536 0.03536 -1.00000 0.04157 0.02778 -1.00000 0.04619 0.01913 -1.00000 0.04904 0.00975 -1.00000 0.05000 0.00000 -1.00000 0.04904 -0.00975 -1.00000 0.04619 -0.01913 -1.00000 0.04157 -0.02778 -1.00000 0.03536 -0.03536 -1.00000 0.02778 -0.04157 -1.00000 0.01913 -0.04619 -1.00000 0.00975 -0.04904 -1.00000 -0.00000 -0.05000 -1.00000 -0.00975 -0.04904 -1.00000 -0.01913 -0.04619 -1.00000 -0.02778 -0.04157 -1.00000 -0.03536 -0.03536 -1.00000 -0.04157 -0.02778 -1.00000 -0.04619 -0.01913 -1.00000 -0.04904 -0.00975 -1.00000 -0.05000 0.00000 -1.00000 -0.04904 0.00975 -1.00000 -0.04619 0.01913 -1.00000 -0.04157 0.02778 -1.00000 -0.03536 0.03536 -1.00000 -0.02778 0.04157 -1.00000 -0.01913 0.04619 -1.00000 -0.00975 0.04904 -1.00000 0.00000 0.05000 -1.00000 0.00975 0.04904 -1.00000 0.01913 0.04619 -1.00000 0.02778 0.04157 -1.00000 0.03536 0.03536 1.00000 0.04157 0.02778 1.00000 0.04619 0.01913 1.00000 0.04904 0.00975 1.00000 0.05000 -0.00000 1.00000 0.04904 -0.00975 1.00000 0.04619 -0.01913 1.00000 0.04157 -0.02778 1.00000 0.03536 -0.03536 1.00000 0.02778 -0.04157 1.00000 0.01913 -0.04619 1.00000 0.00975 -0.04904 1.00000 0.00000 -0.05000 1.00000 -0.00975 -0.04904 1.00000 -0.01913 -0.04619 1.00000 -0.02778 -0.04157 1.00000 -0.03536 -0.03536 1.00000 -0.04157 -0.02778 1.00000 -0.04619 -0.01913 1.00000 -0.04904 -0.00975 1.00000 -0.05000 -0.00000 1.00000 -0.04904 0.00975 1.00000 -0.04619 0.01913 1.00000 -0.04157 0.02778 1.00000 -0.03536 0.03536 1.00000 -0.02778 0.04157 1.00000 -0.01913 0.04619 1.00000 -0.00975 0.04904 1.00000 -0.00000 0.05000 1.00000 0.00975 0.04904 1.00000 0.01913 0.04619 1.00000 0.02778 0.04157 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.77301 0.63439 0.00000 0.88192 0.47140 0.00000 0.95694 0.29028 -0.00000 0.99518 0.09802 -0.00000 0.99518 -0.09802 -0.00000 0.95694 -0.29029 -0.00000 0.88192 -0.47140 -0.00000 0.77301 -0.63439 -0.00000 0.63439 -0.77301 0.00000 0.47140 -0.88192 -0.00000 0.29028 -0.95694 -0.00000 0.09802 -0.99518 -0.00000 -0.09802 -0.99518 -0.00000 -0.29028 -0.95694 -0.00000 -0.47140 -0.88192 -0.00000 -0.63439 -0.77301 -0.00000 -0.77301 -0.63439 -0.00000 -0.88192 -0.47140 0.00000 -0.95694 -0.29029 0.00000 -0.99518 -0.09802 -0.00000 -0.99518 0.09802 -0.00000 -0.95694 0.29028 -0.00000 -0.88192 0.47140 -0.00000 -0.77301 0.63439 -0.00000 -0.63440 0.77301 -0.00000 -0.47140 0.88192 0.00000 -0.29029 0.95694 -0.00000 -0.09802 0.99518 -0.00000 0.09801 0.99519 -0.00000 0.29028 0.95694 -0.00000 0.47139 0.88192 -0.00000 0.63439 0.77301 0.00000 231 | 232 | 233 | 234 | 235 | 236 | 237 | 238 | 239 | 240 | 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 241 | 242 | 243 | 244 | 245 | 246 | 247 | 248 | 249 | 250 | 251 | 252 | 253 | 254 | 255 |

64 0 0 0 0 1 1 0 2 65 1 3 33 1 4 32 1 5 64 2 6 1 2 7 2 2 8 65 3 9 34 3 10 33 3 11 64 4 12 2 4 13 3 4 14 65 5 15 35 5 16 34 5 17 64 6 18 3 6 19 4 6 20 65 7 21 36 7 22 35 7 23 64 8 24 4 8 25 5 8 26 65 9 27 37 9 28 36 9 29 64 10 30 5 10 31 6 10 32 65 11 33 38 11 34 37 11 35 64 12 36 6 12 37 7 12 38 65 13 39 39 13 40 38 13 41 64 14 42 7 14 43 8 14 44 65 15 45 40 15 46 39 15 47 64 16 48 8 16 49 9 16 50 65 17 51 41 17 52 40 17 53 64 18 54 9 18 55 10 18 56 65 19 57 42 19 58 41 19 59 64 20 60 10 20 61 11 20 62 65 21 63 43 21 64 42 21 65 64 22 66 11 22 67 12 22 68 65 23 69 44 23 70 43 23 71 64 24 72 12 24 73 13 24 74 65 25 75 45 25 76 44 25 77 64 26 78 13 26 79 14 26 80 65 27 81 46 27 82 45 27 83 64 28 84 14 28 85 15 28 86 65 29 87 47 29 88 46 29 89 64 30 90 15 30 91 16 30 92 65 31 93 48 31 94 47 31 95 64 32 96 16 32 97 17 32 98 65 33 99 49 33 100 48 33 101 64 34 102 17 34 103 18 34 104 65 35 105 50 35 106 49 35 107 64 36 108 18 36 109 19 36 110 65 37 111 51 37 112 50 37 113 64 38 114 19 38 115 20 38 116 65 39 117 52 39 118 51 39 119 64 40 120 20 40 121 21 40 122 65 41 123 53 41 124 52 41 125 64 42 126 21 42 127 22 42 128 65 43 129 54 43 130 53 43 131 64 44 132 22 44 133 23 44 134 65 45 135 55 45 136 54 45 137 64 46 138 23 46 139 24 46 140 65 47 141 56 47 142 55 47 143 64 48 144 24 48 145 25 48 146 65 49 147 57 49 148 56 49 149 64 50 150 25 50 151 26 50 152 65 51 153 58 51 154 57 51 155 64 52 156 26 52 157 27 52 158 65 53 159 59 53 160 58 53 161 64 54 162 27 54 163 28 54 164 65 55 165 60 55 166 59 55 167 64 56 168 28 56 169 29 56 170 65 57 171 61 57 172 60 57 173 64 58 174 29 58 175 30 58 176 65 59 177 62 59 178 61 59 179 64 60 180 30 60 181 31 60 182 65 61 183 63 61 184 62 61 185 31 62 186 0 62 187 64 62 188 65 63 189 32 63 190 63 63 191 0 64 192 32 64 193 33 64 194 33 64 195 1 64 196 0 64 197 1 65 198 33 65 199 34 65 200 34 65 201 2 65 202 1 65 203 2 66 204 34 66 205 35 66 206 35 66 207 3 66 208 2 66 209 3 67 210 35 67 211 36 67 212 36 67 213 4 67 214 3 67 215 4 68 216 36 68 217 37 68 218 37 68 219 5 68 220 4 68 221 5 69 222 37 69 223 38 69 224 38 69 225 6 69 226 5 69 227 6 70 228 38 70 229 39 70 230 39 70 231 7 70 232 6 70 233 7 71 234 39 71 235 40 71 236 40 71 237 8 71 238 7 71 239 8 72 240 40 72 241 41 72 242 41 72 243 9 72 244 8 72 245 9 73 246 41 73 247 42 73 248 42 73 249 10 73 250 9 73 251 10 74 252 42 74 253 43 74 254 43 74 255 11 74 256 10 74 257 11 75 258 43 75 259 44 75 260 44 75 261 12 75 262 11 75 263 12 76 264 44 76 265 45 76 266 45 76 267 13 76 268 12 76 269 13 77 270 45 77 271 46 77 272 46 77 273 14 77 274 13 77 275 14 78 276 46 78 277 47 78 278 47 78 279 15 78 280 14 78 281 15 79 282 47 79 283 48 79 284 48 79 285 16 79 286 15 79 287 16 80 288 48 80 289 49 80 290 49 80 291 17 80 292 16 80 293 17 81 294 49 81 295 50 81 296 50 81 297 18 81 298 17 81 299 18 82 300 50 82 301 51 82 302 51 82 303 19 82 304 18 82 305 19 83 306 51 83 307 52 83 308 52 83 309 20 83 310 19 83 311 20 84 312 52 84 313 53 84 314 53 84 315 21 84 316 20 84 317 21 85 318 53 85 319 54 85 320 54 85 321 22 85 322 21 85 323 22 86 324 54 86 325 55 86 326 55 86 327 23 86 328 22 86 329 23 87 330 55 87 331 56 87 332 56 87 333 24 87 334 23 87 335 24 88 336 56 88 337 57 88 338 57 88 339 25 88 340 24 88 341 25 89 342 57 89 343 58 89 344 58 89 345 26 89 346 25 89 347 26 90 348 58 90 349 59 90 350 59 90 351 27 90 352 26 90 353 27 91 354 59 91 355 60 91 356 60 91 357 28 91 358 27 91 359 28 92 360 60 92 361 61 92 362 61 92 363 29 92 364 28 92 365 29 93 366 61 93 367 62 93 368 62 93 369 30 93 370 29 93 371 30 94 372 62 94 373 63 94 374 63 94 375 31 94 376 30 94 377 32 95 378 0 95 379 31 95 380 31 95 381 63 95 382 32 95 383

256 |
257 |
258 |
259 |
260 | 261 | 262 | 263 | -0.29478 -1.99835 2.70248 264 | 0 0 1 0.00000 265 | 0 1 0 -0.00000 266 | 1 0 0 0.00000 267 | 1.00000 1.00000 1.00000 268 | 269 | 270 | 271 | 0.00334 -0.00071 0.00118 272 | 0 0 1 0.00000 273 | 0 1 0 -0.00000 274 | 1 0 0 0.00000 275 | 1.00000 1.00000 1.00000 276 | 277 | 278 | 279 | 280 | 281 | 282 | 283 | 284 | 285 | 286 | 287 | 0.22856 0.00372 1.80362 288 | 0 0 1 0.00000 289 | 0 1 0 -0.00000 290 | 1 0 0 0.00000 291 | 0.18803 0.18803 0.18803 292 | 293 | 294 | 295 | 296 | 297 | 298 | 299 | 300 | 301 | 302 | 303 | 0.00580 0.01041 0.99794 304 | 0 0 1 0.00000 305 | 0 1 0 -0.00000 306 | 1 0 0 0.00000 307 | 1.00000 1.00000 1.00000 308 | 309 | 310 | 311 | 312 | 313 | 314 | 315 | 316 | 317 | 318 | 319 | 320 | 321 | 322 | 323 |
--------------------------------------------------------------------------------