def parseLog(self): log = lcm.EventLog(self.logFile, 'r') print 'Log size: ' + sizeof_fmt(log.size()) log.seek(0) while True: event = log.read_next_event() if not event: break timestamp = event.timestamp if event.channel == 'EST_ROBOT_STATE': msg = spy.decodeMessage(event.data) self.jointVelocityTimes.append(timestamp) self.jointVelocityNorms.append(np.linalg.norm(msg.joint_velocity)) elif event.channel == 'ATLAS_BATTERY_DATA': msg = spy.decodeMessage(event.data) self.batteryTimes.append(timestamp) self.batteryPercentage.append(msg.remaining_charge_percentage) elif event.channel == 'ATLAS_STATUS': msg = spy.decodeMessage(event.data) self.pressureTimes.append(timestamp) self.pressureReadings.append(msg.pump_supply_pressure) print 'parsed ' + str(len(self.jointVelocityNorms)) + ' robot states' print 'parsed ' + str(len(self.batteryPercentage)) + ' battery states' print 'parsed ' + str(len(self.pressureReadings)) + ' pump readings'
def parseLog(self): log = lcm.EventLog(self.logFile, 'r') print 'Log size: ' + sizeof_fmt(log.size()) log.seek(0) while True: event = log.read_next_event() if not event: break timestamp = event.timestamp if event.channel == 'EST_ROBOT_STATE': msg = spy.decodeMessage(event.data) self.jointVelocityTimes.append(timestamp) self.jointVelocityNorms.append( np.linalg.norm(msg.joint_velocity)) elif event.channel == 'ATLAS_BATTERY_DATA': msg = spy.decodeMessage(event.data) self.batteryTimes.append(timestamp) self.batteryPercentage.append(msg.remaining_charge_percentage) elif event.channel == 'ATLAS_STATUS': msg = spy.decodeMessage(event.data) self.pressureTimes.append(timestamp) self.pressureReadings.append(msg.pump_supply_pressure) print 'parsed ' + str(len(self.jointVelocityNorms)) + ' robot states' print 'parsed ' + str(len(self.batteryPercentage)) + ' battery states' print 'parsed ' + str(len(self.pressureReadings)) + ' pump readings'
def getImage(self, utime): filename, filepos = self.utimeMap[utime] log = self.logs.get(filename) if log is None: log = lcm.EventLog(filename, 'r') self.logs[filename] = log log.seek(filepos) event = log.read_next_event() msg = spy.decodeMessage(event.data) if hasattr(msg, 'images'): msg = msg.images[0] return msg, filename
def onControlMessage(self, channel, msgBytes): if self.getLastPublishElapsedTime() > self.publishFrequency: msg = spy.decodeMessage(msgBytes) self.onFrameRequest(msg.utime)
def unwrapCommand(self, msgBytes): msg = spy.decodeMessage(msgBytes) argDict = json.loads(msg.command) return FieldData(**argDict)