Hot-keys on this page

r m x p   toggle line displays

j k   next/prev highlighted chunk

0   (zero) top of page

1   (one) first highlighted chunk

1

2

3

4

5

6

7

8

9

10

11

12

13

14

15

16

17

18

19

20

21

22

23

24

25

26

27

28

29

30

31

32

33

34

35

36

37

38

39

40

41

42

43

44

45

46

47

48

49

50

51

52

53

54

55

56

57

58

59

60

61

62

63

64

65

66

67

68

69

70

71

72

73

74

75

76

77

78

79

80

81

82

83

84

85

86

87

88

89

90

91

92

93

94

95

96

97

98

99

100

101

102

103

104

105

106

107

108

109

110

111

112

113

114

115

116

117

118

119

120

121

122

123

124

125

126

127

128

129

130

131

132

133

134

135

136

137

138

139

140

141

142

143

144

145

146

147

148

149

150

151

152

153

154

155

156

157

158

159

160

161

162

163

164

165

166

167

168

169

170

171

172

173

174

175

176

177

178

179

180

181

182

183

184

185

186

187

188

189

190

191

192

193

194

195

196

197

198

199

200

201

202

203

204

205

import director 

import os 

import sys 

import argparse 

import json 

 

 

 

class DRCArgParser(object): 

 

    def __init__(self): 

        self._args = None 

        self._parser = None 

        self.strict = False 

 

    def getArgs(self): 

        if self._args is None: 

            self.parseArgs() 

        return self._args 

 

    def getParser(self): 

        if self._parser is None: 

            self._parser = argparse.ArgumentParser() 

            self.addDefaultArgs(self._parser) 

        return self._parser 

 

    def parseArgs(self): 

        parser = self.getParser() 

        sys.argv = [str(v) for v in sys.argv] 

 

        if not self.strict: 

            self._args, unknown = parser.parse_known_args() 

        else: 

            self._args = parser.parse_args() 

 

 

        def flatten(l): 

            return [item for sublist in l for item in sublist] 

 

        # now flatten some list of lists 

        self._args.scripts = flatten(self._args.scripts) 

        self._args.data_files = flatten(self._args.data_files) 

 

 

    def getDefaultBotConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 'software/config/val/robot.cfg') 

 

    def getDefaultDirectorConfigFile(self): 

        return self.getDefaultValkyrieDirectorConfigFile(); 

 

    def getDefaultAtlasV3DirectorConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/atlas_v3/director_config.json') 

 

    def getDefaultAtlasV4DirectorConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/atlas_v4/director_config.json') 

 

    def getDefaultAtlasV5DirectorConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/atlas_v5/director_config.json') 

 

    def getDefaultValkyrieDirectorConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/val_description/director_config.json') 

 

    def getDefaultValkyrieSimpleDirectorConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/val_description/director_config_simple.json') 

 

    def getDefaultKukaLWRConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/lwr_defs/director_config.json') 

 

    def getDefaultHuskyConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/husky_description/director_config.json') 

 

    def getDefaultDualArmHuskyConfigFile(self): 

        return os.path.join(director.getDRCBaseDir(), 

                            'software/models/dual_arm_husky_description/director_config.json') 

 

    def addDirectorConfigShortcuts(self, directorConfig): 

 

        directorConfig.add_argument('-v3', '--atlas_v3', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultAtlasV3DirectorConfigFile(), 

                            help='Use Atlas V3') 

 

        directorConfig.add_argument('-v4', '--atlas_v4', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultAtlasV4DirectorConfigFile(), 

                            help='Use Atlas V4') 

 

        directorConfig.add_argument('-v5', '--atlas_v5', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultAtlasV5DirectorConfigFile(), 

                            help='Use Atlas V5') 

 

        directorConfig.add_argument('-val', '--valkyrie', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultValkyrieDirectorConfigFile(), 

                            help='Use Valkyrie (Default)') 

 

        directorConfig.add_argument('-val_simple', '--valkyrie_simple', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultValkyrieSimpleDirectorConfigFile(), 

                            help='Use Valkyrie (Simple/Primitive Shapes)') 

 

        directorConfig.add_argument('-lwr', '--lwr', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultKukaLWRConfigFile(), 

                            help='Use Kuka LWR') 

 

        directorConfig.add_argument('-husky', '--husky', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultHuskyConfigFile(), 

                            help='Use Husky') 

 

        directorConfig.add_argument('-dual_arm_husky', '--dual_arm_husky', dest='directorConfigFile', 

                            action='store_const', 

                            const=self.getDefaultDualArmHuskyConfigFile(), 

                            help='Use Dual Arm Husky') 

 

    def addDefaultArgs(self, parser): 

 

        parser.add_argument('-c', '--bot-config', '--config_file', dest='config_file', 

                            metavar='filename', type=str, help='Robot cfg file') 

 

        parser.add_argument('--matlab-host', metavar='hostname', type=str, 

                            help='hostname to connect with external matlab server') 

 

        directorConfig = parser.add_mutually_exclusive_group(required=False) 

        directorConfig.add_argument('--director-config', '--director_config', dest='directorConfigFile', 

                                    type=str, default='', metavar='filename', 

                                    help='JSON file specifying which urdfs to use') 

 

        if director.getDRCBaseIsSet(): 

            self.addDirectorConfigShortcuts(directorConfig) 

            parser.set_defaults(directorConfigFile=self.getDefaultDirectorConfigFile(), 

                                config_file=self.getDefaultBotConfigFile()) 

 

        parser.add_argument('data_files', type=str, nargs='*', 

                            default=[], action='append', metavar='filename', 

                            help='data files to load at startup') 

 

        parser.add_argument('--data', type=str, nargs='+', dest='data_files', 

                            default=[], action='append', metavar='filename', 

                            help='data files to load at startup') 

 

        parser.add_argument('--script', '--startup', type=str, nargs='+', dest='scripts', 

                            default=[], action='append', metavar='filename', 

                            help='python scripts to run at startup') 

 

 

_argParser = None 

def getGlobalArgParser(): 

    global _argParser 

    if not _argParser: 

        _argParser = DRCArgParser() 

    return _argParser 

 

 

def requireStrict(): 

    global _argParser 

    _argParser = None 

    getGlobalArgParser().strict = True 

 

 

def args(): 

    return getGlobalArgParser().getArgs() 

 

 

class DirectorConfig(object): 

 

    def __init__(self, filename): 

 

        self.filename = filename 

        if not os.path.isfile(filename): 

            raise Exception('Director config file not found: %s' % filename) 

 

        self.dirname = os.path.dirname(os.path.abspath(filename)) 

        self.config = json.load(open(filename)) 

 

        if self.config.get('fixedPointFile'): 

            self.config['fixedPointFile'] = os.path.join(self.dirname, self.config['fixedPointFile']) 

 

        self.urdfConfig = self.config['urdfConfig'] 

        for key, urdf in list(self.urdfConfig.items()): 

            self.urdfConfig[key] = os.path.join(self.dirname, urdf) 

 

    _defaultInstance = None 

 

    @classmethod 

    def getDefaultInstance(cls): 

        if cls._defaultInstance is None: 

            if not args().directorConfigFile: 

                raise Exception('Director config file is not defined. ' 

                                'Use --director-config <filename> on the command line.') 

            cls._defaultInstance = DirectorConfig(args().directorConfigFile) 

        return cls._defaultInstance 

 

 

def getDirectorConfig(): 

    return DirectorConfig.getDefaultInstance().config