Hide keyboard shortcuts

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

206

207

208

209

210

211

212

213

214

215

216

217

218

219

220

221

222

223

224

225

226

227

228

229

230

231

232

233

234

235

236

237

238

239

240

241

242

243

244

245

246

247

248

249

250

251

252

253

254

255

256

257

258

259

260

261

262

263

264

265

266

267

268

269

270

271

272

273

274

275

#!/usr/bin/env python 

# -*- coding: utf-8 -*- 

""" 

Programmatically control a ROS bag file. 

 

This module implements the base class, and the various functions. 

 

Currently implemented are: 

 

* ``rosbag play`` 

 

""" 

import logging 

import subprocess as sp 

import time 

try: 

from types import StringTypes 

except ImportError: 

StringTypes = str 

 

 

try: 

input = raw_input 

except NameError: 

pass 

 

 

logger = logging.getLogger("bag_player") 

 

 

class BagError(Exception): 

""" 

Catch bag player exceptions. 

 

""" 

 

 

class BagNotRunningError(BagError, AttributeError): 

""" 

Raised when interaction is attempted with a bag file which is not running. 

 

""" 

def __init__(self, action="talk to"): 

message = u"Cannot {} process while bag is not running.".format(action) 

super(BagNotRunningError, self).__init__(message) 

 

 

class Bag(object): 

""" 

Open and manipulate a bag file programmatically. 

 

Parameters 

---------- 

filenames : StringTypes | List[StringTypes] 

The location of the bag files. 

 

Attributes 

---------- 

filenames : List[StringTypes] 

The location of the bag files. 

process : subprocess.Popen 

The process containing the running bag file. 

 

""" 

def __init__(self, filenames): 

if isinstance(filenames, StringTypes): 

filenames = [filenames] 

self.filenames = filenames 

self.process = None 

 

def send(self, string): 

""" 

Write something to process stdin. 

 

Parameters 

---------- 

string : str 

The string to write. 

 

Raises 

------ 

BagNotRunningError 

If interaction is attempted when the bag file is not running. 

 

""" 

try: 

self.process.stdin.write(string) 

except AttributeError: 

raise BagNotRunningError() 

 

def stop(self): 

""" 

Stop a running bag file. 

 

Raises 

------ 

BagNotRunningError 

If the bag file is not running. 

 

""" 

try: 

self.process.terminate() 

self.process.kill() 

except AttributeError: 

raise BagNotRunningError("stop") 

 

def wait(self): 

""" 

Block until process is complete. 

 

Raises 

------ 

BagNotRunningError 

If the bag file is not running. 

 

""" 

try: 

self.process.wait() 

except AttributeError: 

raise BagNotRunningError("wait for") 

 

@property 

def is_running(self): 

""" 

Check whether the bag file is running. 

 

Returns 

------- 

bool 

The bag file is running. 

 

""" 

try: 

return self.process.poll() is None 

except AttributeError: 

return False 

 

def __enter__(self): 

""" 

Context manager entry point. 

 

""" 

return self 

 

# noinspection PyUnusedLocal 

def __exit__(self, exc_type, exc_value, traceback): 

""" 

Context manager exit point. 

 

""" 

time.sleep(1) # For pretty output. 

if self.is_running: 

if exc_type is None: 

logger.warning("Exited while process is still running.") 

logger.info("Hint: Use Bag.wait() or Bag.play(wait=True) " 

"to wait until completion.") 

else: 

self.stop() 

 

if exc_type == KeyboardInterrupt: 

logger.info("User exit.") 

return True 

elif exc_type is not None: 

logger.critical("An error occurred. Exiting.") 

else: 

logger.info("Goodbye!") 

 

def __repr__(self): 

return "<Bag({})>".format(self.filenames) 

 

 

class BagPlayer(Bag): 

""" 

Play Bag files. 

 

""" 

def play(self, wait=False, stdin=sp.PIPE, stdout=None, stderr=None, 

quiet=None, immediate=None, start_paused=None, queue_size=None, 

publish_clock=None, clock_publish_freq=None, delay=None, 

publish_rate_multiplier=None, start_time=None, duration=None, 

loop=None, keep_alive=None): 

""" 

Play the bag file. 

 

Parameters 

---------- 

wait : Optional[Bool] 

Wait until completion. 

stdin : Optional[file] 

The stdin buffer. Default is subprocess.PIPE. 

stdout : Optional[file] 

The stdout buffer. 

stderr : Optional[file] 

The stderr buffer. 

quiet : Optional[Bool] 

Suppress console output. 

immediate : Optional[Bool] 

Play back all messages without waiting. 

start_paused : Optional[Bool] 

Start in paused mode. 

queue_size : Optional[int] 

Set outgoing queue size. Default is 100. 

publish_clock : Optional[Bool] 

Publish the clock time. 

clock_publish_freq : Optional[float] 

The frequency, in Hz, at which to publish the clock time. Default is 

100. 

delay : Optional[float] 

The number of seconds to sleep afer every advertise call (e.g., to 

allow subscribers to connect). 

publish_rate_multiplier : Optional[float] 

The factor by which to multiply the publish rate. 

start_time : Optional[float] 

The number of seconds into the bag file at which to start. 

duration : Optional[float] 

The number of seconds from the start to play. 

loop : Optional[Bool] 

Loop playback. 

keep_alive : Optional[Bool] 

Keep alive past end of bag (e.g. for publishing latched topics). 

 

""" 

arguments = ["rosbag", "play"] 

arguments.extend(self.filenames) 

 

if quiet: 

arguments.append("-q") 

if immediate: 

arguments.append("-i") 

if start_paused: 

arguments.append("--pause") 

if queue_size is not None: 

arguments.append("--queue={}".format(queue_size)) 

if publish_clock: 

arguments.append("--clock") 

if clock_publish_freq: 

arguments.append("--hz={}".format(clock_publish_freq)) 

if delay: 

arguments.append("--delay={}".format(delay)) 

if publish_rate_multiplier: 

arguments.append("--rate={}".format(publish_rate_multiplier)) 

if start_time: 

arguments.append("--start={}".format(start_time)) 

if duration: 

arguments.append("--duration={}".format(duration)) 

if loop: 

arguments.append("-l") 

if keep_alive: 

arguments.append("-k") 

 

self.process = sp.Popen(arguments, 

stdin=stdin, stdout=stdout, stderr=stderr) 

if wait: 

self.wait() 

 

def pause(self): 

""" 

Pause the bag file. 

 

""" 

self.send(" ") 

 

def resume(self): 

""" 

Resume the bag file. 

 

""" 

self.send(" ") 

 

def step(self): 

""" 

Step through a paused bag file. 

 

""" 

self.send("s")