Go to the documentation of this file.00001
00002
00003 '''
00004 Software License Agreement (MIT License)
00005
00006 @copyright Copyright (c) 2017 DENSO WAVE INCORPORATED
00007
00008 Permission is hereby granted, free of charge, to any person obtaining a copy
00009 of this software and associated documentation files (the "Software"), to deal
00010 in the Software without restriction, including without limitation the rights
00011 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00012 copies of the Software, and to permit persons to whom the Software is
00013 furnished to do so, subject to the following conditions:
00014
00015 The above copyright notice and this permission notice shall be included in
00016 all copies or substantial portions of the Software.
00017
00018 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00019 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00020 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00021 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00022 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00023 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00024 THE SOFTWARE.
00025 '''
00026
00027 import os
00028 import re
00029 import sys
00030 import rospy
00031 import shutil
00032 import roslib.packages
00033
00034 __BRINGUP_TEXT = """<launch>
00035 <!-- the "sim" argument controls whether we connect to a Simulated or Real robot -->
00036 <!-- - if sim=false, a ip_address argument is required -->
00037 <arg name="sim" default="true" />
00038 <arg name="ip_address" default="192.168.0.1" />
00039
00040 <include file=\"$(find denso_robot_bringup)/launch/denso_robot_bringup.launch">
00041 <arg name=\"robot_name\" value=\"{rob_name}\"/>
00042 <arg name=\"sim\" value=\"$(arg sim)\"/>
00043 <arg name=\"ip_address\" value=\"$(arg ip_address)\"/>
00044 </include>
00045 </launch>"""
00046
00047 if __name__ == "__main__":
00048 args = sys.argv
00049
00050
00051 if len(args) < 2:
00052 print("Usage: install_robot_description \"path of description folder\"")
00053 sys.exit()
00054
00055 path_desc = args[1]
00056
00057
00058 m = re.search("([\w\d_]+)_description/?$", path_desc)
00059 if m == None:
00060 print("Invalid path format: it have to be *_description")
00061 sys.exit()
00062
00063 rob_name = m.group(1)
00064
00065
00066 if not os.path.isdir(path_desc):
00067 print(path_desc + " does not exists")
00068 sys.exit()
00069
00070
00071 conf_dir = path_desc
00072 if conf_dir[-1] != "/":
00073 conf_dir += "/"
00074 conf_dir += rob_name + "_config"
00075 if not os.path.isdir(conf_dir):
00076 print(conf_dir + " does not exists")
00077 sys.exit()
00078
00079
00080 try:
00081 descs_pkg = roslib.packages.get_pkg_dir("denso_robot_descriptions")
00082 conf_pkg = roslib.packages.get_pkg_dir("denso_robot_moveit_config")
00083 bringup_pkg = roslib.packages.get_pkg_dir("denso_robot_bringup")
00084 except roslib.packages.InvalidROSPkgException as e:
00085 print(e)
00086 sys.exit()
00087
00088 if os.path.isdir(descs_pkg + "/" + rob_name + "_description"):
00089 print(rob_name + "_description is already in the denso_robot_descriptions package")
00090 sys.exit()
00091
00092 if os.path.isdir(conf_pkg + "/config/" + rob_name + "_config"):
00093 print(rob_name + "_config is already in the denso_robot_moveit_config package")
00094 sys.exit()
00095
00096
00097 shutil.move(conf_dir, conf_pkg + "/config")
00098
00099
00100 shutil.move(path_desc, descs_pkg)
00101
00102
00103 f = open(bringup_pkg + "/launch/" + rob_name + "_bringup.launch", "w")
00104 f.write(__BRINGUP_TEXT.replace("{rob_name}", rob_name))
00105 f.close()