Browse Source

Merge branch 'master' of github.com:PX4/Firmware into mpu6k_queue

sbg
Lorenz Meier 12 years ago
parent
commit
86e5d39b89
  1. 9
      Makefile
  2. 6
      src/drivers/device/cdev.cpp
  3. 17
      src/drivers/device/device.cpp
  4. 66
      src/drivers/device/device.h
  5. 6
      src/drivers/device/i2c.h
  6. 2
      src/drivers/device/spi.h
  7. 32
      src/drivers/meas_airspeed/meas_airspeed.cpp
  8. 6
      src/drivers/stm32/drv_pwm_servo.c
  9. 185
      src/modules/systemlib/hx_stream.c
  10. 42
      src/modules/systemlib/hx_stream.h
  11. 27
      src/modules/systemlib/perf_counter.c
  12. 14
      src/modules/systemlib/perf_counter.h

9
Makefile

@ -161,6 +161,12 @@ $(NUTTX_SRC):
@$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again."
@$(ECHO) "" @$(ECHO) ""
#
# Testing targets
#
testbuild:
$(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8)
# #
# Cleanup targets. 'clean' should remove all built products and force # Cleanup targets. 'clean' should remove all built products and force
# a complete re-compilation, 'distclean' should remove everything # a complete re-compilation, 'distclean' should remove everything
@ -211,6 +217,9 @@ help:
@$(ECHO) " firmware to the board when the build is complete. Not supported for" @$(ECHO) " firmware to the board when the build is complete. Not supported for"
@$(ECHO) " all configurations." @$(ECHO) " all configurations."
@$(ECHO) "" @$(ECHO) ""
@$(ECHO) " testbuild"
@$(ECHO) " Perform a complete clean build of the entire tree."
@$(ECHO) ""
@$(ECHO) " Common options:" @$(ECHO) " Common options:"
@$(ECHO) " ---------------" @$(ECHO) " ---------------"
@$(ECHO) "" @$(ECHO) ""

6
src/drivers/device/cdev.cpp

@ -111,21 +111,21 @@ CDev::~CDev()
int int
CDev::init() CDev::init()
{ {
int ret = OK;
// base class init first // base class init first
ret = Device::init(); int ret = Device::init();
if (ret != OK) if (ret != OK)
goto out; goto out;
// now register the driver // now register the driver
if (_devname != nullptr) {
ret = register_driver(_devname, &fops, 0666, (void *)this); ret = register_driver(_devname, &fops, 0666, (void *)this);
if (ret != OK) if (ret != OK)
goto out; goto out;
_registered = true; _registered = true;
}
out: out:
return ret; return ret;

17
src/drivers/device/device.cpp

@ -223,5 +223,22 @@ interrupt(int irq, void *context)
return OK; return OK;
} }
int
Device::read(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
int
Device::write(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
int
Device::ioctl(unsigned operation, unsigned &arg)
{
return -ENODEV;
}
} // namespace device } // namespace device

66
src/drivers/device/device.h

@ -68,11 +68,62 @@ namespace device __EXPORT
class __EXPORT Device class __EXPORT Device
{ {
public: public:
/**
* Destructor.
*
* Public so that anonymous devices can be destroyed.
*/
virtual ~Device();
/** /**
* Interrupt handler. * Interrupt handler.
*/ */
virtual void interrupt(void *ctx); /**< interrupt handler */ virtual void interrupt(void *ctx); /**< interrupt handler */
/*
* Direct access methods.
*/
/**
* Initialise the driver and make it ready for use.
*
* @return OK if the driver initialized OK, negative errno otherwise;
*/
virtual int init();
/**
* Read directly from the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param offset The device address at which to start reading
* @param data The buffer into which the read values should be placed.
* @param count The number of items to read.
* @return The number of items read on success, negative errno otherwise.
*/
virtual int read(unsigned address, void *data, unsigned count);
/**
* Write directly to the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param address The device address at which to start writing.
* @param data The buffer from which values should be read.
* @param count The number of items to write.
* @return The number of items written on success, negative errno otherwise.
*/
virtual int write(unsigned address, void *data, unsigned count);
/**
* Perform a device-specific operation.
*
* @param operation The operation to perform.
* @param arg An argument to the operation.
* @return Negative errno on error, OK or positive value on success.
*/
virtual int ioctl(unsigned operation, unsigned &arg);
protected: protected:
const char *_name; /**< driver name */ const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */ bool _debug_enabled; /**< if true, debug messages are printed */
@ -85,14 +136,6 @@ protected:
*/ */
Device(const char *name, Device(const char *name,
int irq = 0); int irq = 0);
~Device();
/**
* Initialise the driver and make it ready for use.
*
* @return OK if the driver initialised OK.
*/
virtual int init();
/** /**
* Enable the device interrupt * Enable the device interrupt
@ -189,7 +232,7 @@ public:
/** /**
* Destructor * Destructor
*/ */
~CDev(); virtual ~CDev();
virtual int init(); virtual int init();
@ -282,6 +325,7 @@ public:
* Test whether the device is currently open. * Test whether the device is currently open.
* *
* This can be used to avoid tearing down a device that is still active. * This can be used to avoid tearing down a device that is still active.
* Note - not virtual, cannot be overridden by a subclass.
* *
* @return True if the device is currently open. * @return True if the device is currently open.
*/ */
@ -396,9 +440,9 @@ public:
const char *devname, const char *devname,
uint32_t base, uint32_t base,
int irq = 0); int irq = 0);
~PIO(); virtual ~PIO();
int init(); virtual int init();
protected: protected:

6
src/drivers/device/i2c.h

@ -58,9 +58,7 @@ public:
/** /**
* Get the address * Get the address
*/ */
uint16_t get_address() { int16_t get_address() { return _address; }
return _address;
}
protected: protected:
/** /**
@ -90,7 +88,7 @@ protected:
uint16_t address, uint16_t address,
uint32_t frequency, uint32_t frequency,
int irq = 0); int irq = 0);
~I2C(); virtual ~I2C();
virtual int init(); virtual int init();

2
src/drivers/device/spi.h

@ -71,7 +71,7 @@ protected:
enum spi_mode_e mode, enum spi_mode_e mode,
uint32_t frequency, uint32_t frequency,
int irq = 0); int irq = 0);
~SPI(); virtual ~SPI();
virtual int init(); virtual int init();

32
src/drivers/meas_airspeed/meas_airspeed.cpp

@ -34,6 +34,7 @@
/** /**
* @file meas_airspeed.cpp * @file meas_airspeed.cpp
* @author Lorenz Meier * @author Lorenz Meier
* @author Sarthak Kaingade
* @author Simon Wilks * @author Simon Wilks
* *
* Driver for the MEAS Spec series connected via I2C. * Driver for the MEAS Spec series connected via I2C.
@ -92,9 +93,6 @@
/* Register address */ /* Register address */
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */ #define ADDR_READ_MR 0x00 /* write to this address to start conversion */
#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */
#define ADDR_READ_DF3 0x01
#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */
/* Measurement rate is 100Hz */ /* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
@ -160,7 +158,7 @@ MEASAirspeed::collect()
perf_begin(_sample_perf); perf_begin(_sample_perf);
ret = transfer(nullptr, 0, &val[0], 2); ret = transfer(nullptr, 0, &val[0], 4);
if (ret < 0) { if (ret < 0) {
log("error reading from sensor: %d", ret); log("error reading from sensor: %d", ret);
@ -171,25 +169,37 @@ MEASAirspeed::collect()
if (status == 2) { if (status == 2) {
log("err: stale data"); log("err: stale data");
} else if (status == 3) { } else if (status == 3) {
log("err: fault"); log("err: fault");
} }
uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8); //uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8);
uint16_t temp = (val[3] & 0xE0) << 8 | val[2]; uint16_t temp = (val[3] & 0xE0) << 8 | val[2];
diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f)); // XXX leaving this in until new calculation method has been cross-checked
diff_pres_pa -= _diff_pres_offset; //diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
//diff_pres_pa -= _diff_pres_offset;
int16_t dp_raw = 0, dT_raw = 0;
dp_raw = (val[0] << 8) + val[1];
dp_raw = 0x3FFF & dp_raw;
dT_raw = (val[2] << 8) + val[3];
dT_raw = (0xFFE0 & dT_raw) >> 5;
float temperature = ((200 * dT_raw) / 2047) - 50;
// XXX we may want to smooth out the readings to remove noise. // XXX we may want to smooth out the readings to remove noise.
// Calculate differential pressure. As its centered around 8000
// and can go positive or negative, enforce absolute value
uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f));
_reports[_next_report].timestamp = hrt_absolute_time(); _reports[_next_report].timestamp = hrt_absolute_time();
_reports[_next_report].temperature = temp; _reports[_next_report].temperature = temperature;
_reports[_next_report].differential_pressure_pa = diff_pres_pa; _reports[_next_report].differential_pressure_pa = diff_press_pa;
// Track maximum differential pressure measured (so we can work out top speed). // Track maximum differential pressure measured (so we can work out top speed).
if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { if (diff_press_pa > _reports[_next_report].max_differential_pressure_pa) {
_reports[_next_report].max_differential_pressure_pa = diff_pres_pa; _reports[_next_report].max_differential_pressure_pa = diff_press_pa;
} }
/* announce the airspeed if needed, just publish else */ /* announce the airspeed if needed, just publish else */

6
src/drivers/stm32/drv_pwm_servo.c

@ -88,6 +88,7 @@
#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET) #define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET) #define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET) #define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
static void pwm_timer_init(unsigned timer); static void pwm_timer_init(unsigned timer);
static void pwm_timer_set_rate(unsigned timer, unsigned rate); static void pwm_timer_set_rate(unsigned timer, unsigned rate);
@ -110,6 +111,11 @@ pwm_timer_init(unsigned timer)
rCCER(timer) = 0; rCCER(timer) = 0;
rDCR(timer) = 0; rDCR(timer) = 0;
if ((pwm_timers[timer].base == STM32_TIM1_BASE) || (pwm_timers[timer].base == STM32_TIM8_BASE)) {
/* master output enable = on */
rBDTR(timer) = ATIM_BDTR_MOE;
}
/* configure the timer to free-run at 1MHz */ /* configure the timer to free-run at 1MHz */
rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1; rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1;

185
src/modules/systemlib/hx_stream.c

@ -53,14 +53,26 @@
struct hx_stream { struct hx_stream {
uint8_t buf[HX_STREAM_MAX_FRAME + 4]; /* RX state */
unsigned frame_bytes; uint8_t rx_buf[HX_STREAM_MAX_FRAME + 4];
bool escaped; unsigned rx_frame_bytes;
bool txerror; bool rx_escaped;
hx_stream_rx_callback rx_callback;
void *rx_callback_arg;
/* TX state */
int fd; int fd;
hx_stream_rx_callback callback; bool tx_error;
void *callback_arg; uint8_t *tx_buf;
unsigned tx_resid;
uint32_t tx_crc;
enum {
TX_IDLE = 0,
TX_SEND_START,
TX_SEND_DATA,
TX_SENT_ESCAPE,
TX_SEND_END
} tx_state;
perf_counter_t pc_tx_frames; perf_counter_t pc_tx_frames;
perf_counter_t pc_rx_frames; perf_counter_t pc_rx_frames;
@ -81,21 +93,7 @@ static void
hx_tx_raw(hx_stream_t stream, uint8_t c) hx_tx_raw(hx_stream_t stream, uint8_t c)
{ {
if (write(stream->fd, &c, 1) != 1) if (write(stream->fd, &c, 1) != 1)
stream->txerror = true; stream->tx_error = true;
}
static void
hx_tx_byte(hx_stream_t stream, uint8_t c)
{
switch (c) {
case FBO:
case CEO:
hx_tx_raw(stream, CEO);
c ^= 0x20;
break;
}
hx_tx_raw(stream, c);
} }
static int static int
@ -105,11 +103,11 @@ hx_rx_frame(hx_stream_t stream)
uint8_t b[4]; uint8_t b[4];
uint32_t w; uint32_t w;
} u; } u;
unsigned length = stream->frame_bytes; unsigned length = stream->rx_frame_bytes;
/* reset the stream */ /* reset the stream */
stream->frame_bytes = 0; stream->rx_frame_bytes = 0;
stream->escaped = false; stream->rx_escaped = false;
/* not a real frame - too short */ /* not a real frame - too short */
if (length < 4) { if (length < 4) {
@ -122,11 +120,11 @@ hx_rx_frame(hx_stream_t stream)
length -= 4; length -= 4;
/* compute expected CRC */ /* compute expected CRC */
u.w = crc32(&stream->buf[0], length); u.w = crc32(&stream->rx_buf[0], length);
/* compare computed and actual CRC */ /* compare computed and actual CRC */
for (unsigned i = 0; i < 4; i++) { for (unsigned i = 0; i < 4; i++) {
if (u.b[i] != stream->buf[length + i]) { if (u.b[i] != stream->rx_buf[length + i]) {
perf_count(stream->pc_rx_errors); perf_count(stream->pc_rx_errors);
return 0; return 0;
} }
@ -134,7 +132,7 @@ hx_rx_frame(hx_stream_t stream)
/* frame is good */ /* frame is good */
perf_count(stream->pc_rx_frames); perf_count(stream->pc_rx_frames);
stream->callback(stream->callback_arg, &stream->buf[0], length); stream->rx_callback(stream->rx_callback_arg, &stream->rx_buf[0], length);
return 1; return 1;
} }
@ -150,8 +148,8 @@ hx_stream_init(int fd,
if (stream != NULL) { if (stream != NULL) {
memset(stream, 0, sizeof(struct hx_stream)); memset(stream, 0, sizeof(struct hx_stream));
stream->fd = fd; stream->fd = fd;
stream->callback = callback; stream->rx_callback = callback;
stream->callback_arg = arg; stream->rx_callback_arg = arg;
} }
return stream; return stream;
@ -179,49 +177,112 @@ hx_stream_set_counters(hx_stream_t stream,
stream->pc_rx_errors = rx_errors; stream->pc_rx_errors = rx_errors;
} }
void
hx_stream_reset(hx_stream_t stream)
{
stream->rx_frame_bytes = 0;
stream->rx_escaped = false;
stream->tx_buf = NULL;
stream->tx_resid = 0;
stream->tx_state = TX_IDLE;
}
int int
hx_stream_send(hx_stream_t stream, hx_stream_start(hx_stream_t stream,
const void *data, const void *data,
size_t count) size_t count)
{ {
union { if (count > HX_STREAM_MAX_FRAME)
uint8_t b[4];
uint32_t w;
} u;
const uint8_t *p = (const uint8_t *)data;
unsigned resid = count;
if (resid > HX_STREAM_MAX_FRAME)
return -EINVAL; return -EINVAL;
/* start the frame */ stream->tx_buf = data;
hx_tx_raw(stream, FBO); stream->tx_resid = count;
stream->tx_state = TX_SEND_START;
stream->tx_crc = crc32(data, count);
return OK;
}
/* transmit the data */ int
while (resid--) hx_stream_send_next(hx_stream_t stream)
hx_tx_byte(stream, *p++); {
int c;
/* compute the CRC */ /* sort out what we're going to send */
u.w = crc32(data, count); switch (stream->tx_state) {
/* send the CRC */ case TX_SEND_START:
p = &u.b[0]; stream->tx_state = TX_SEND_DATA;
resid = 4; return FBO;
while (resid--) case TX_SEND_DATA:
hx_tx_byte(stream, *p++); c = *stream->tx_buf;
/* and the trailing frame separator */ switch (c) {
hx_tx_raw(stream, FBO); case FBO:
case CEO:
stream->tx_state = TX_SENT_ESCAPE;
return CEO;
}
break;
case TX_SENT_ESCAPE:
c = *stream->tx_buf ^ 0x20;
stream->tx_state = TX_SEND_DATA;
break;
case TX_SEND_END:
stream->tx_state = TX_IDLE;
return FBO;
case TX_IDLE:
default:
return -1;
}
/* if we are here, we have consumed a byte from the buffer */
stream->tx_resid--;
stream->tx_buf++;
/* buffer exhausted */
if (stream->tx_resid == 0) {
uint8_t *pcrc = (uint8_t *)&stream->tx_crc;
/* was the buffer the frame CRC? */
if (stream->tx_buf == (pcrc + sizeof(stream->tx_crc))) {
stream->tx_state = TX_SEND_END;
} else {
/* no, it was the payload - switch to sending the CRC */
stream->tx_buf = pcrc;
stream->tx_resid = sizeof(stream->tx_crc);
}
}
return c;
}
int
hx_stream_send(hx_stream_t stream,
const void *data,
size_t count)
{
int result;
result = hx_stream_start(stream, data, count);
if (result != OK)
return result;
int c;
while ((c = hx_stream_send_next(stream)) >= 0)
hx_tx_raw(stream, c);
/* check for transmit error */ /* check for transmit error */
if (stream->txerror) { if (stream->tx_error) {
stream->txerror = false; stream->tx_error = false;
return -EIO; return -EIO;
} }
perf_count(stream->pc_tx_frames); perf_count(stream->pc_tx_frames);
return 0; return OK;
} }
void void
@ -234,17 +295,17 @@ hx_stream_rx(hx_stream_t stream, uint8_t c)
} }
/* escaped? */ /* escaped? */
if (stream->escaped) { if (stream->rx_escaped) {
stream->escaped = false; stream->rx_escaped = false;
c ^= 0x20; c ^= 0x20;
} else if (c == CEO) { } else if (c == CEO) {
/* now escaped, ignore the byte */ /* now rx_escaped, ignore the byte */
stream->escaped = true; stream->rx_escaped = true;
return; return;
} }
/* save for later */ /* save for later */
if (stream->frame_bytes < sizeof(stream->buf)) if (stream->rx_frame_bytes < sizeof(stream->rx_buf))
stream->buf[stream->frame_bytes++] = c; stream->rx_buf[stream->rx_frame_bytes++] = c;
} }

42
src/modules/systemlib/hx_stream.h

@ -58,7 +58,8 @@ __BEGIN_DECLS
* Allocate a new hx_stream object. * Allocate a new hx_stream object.
* *
* @param fd The file handle over which the protocol will * @param fd The file handle over which the protocol will
* communicate. * communicate, or -1 if the protocol will use
* hx_stream_start/hx_stream_send_next.
* @param callback Called when a frame is received. * @param callback Called when a frame is received.
* @param callback_arg Passed to the callback. * @param callback_arg Passed to the callback.
* @return A handle to the stream, or NULL if memory could * @return A handle to the stream, or NULL if memory could
@ -80,6 +81,7 @@ __EXPORT extern void hx_stream_free(hx_stream_t stream);
* *
* Any counter may be set to NULL to disable counting that datum. * Any counter may be set to NULL to disable counting that datum.
* *
* @param stream A handle returned from hx_stream_init.
* @param tx_frames Counter for transmitted frames. * @param tx_frames Counter for transmitted frames.
* @param rx_frames Counter for received frames. * @param rx_frames Counter for received frames.
* @param rx_errors Counter for short and corrupt received frames. * @param rx_errors Counter for short and corrupt received frames.
@ -89,6 +91,44 @@ __EXPORT extern void hx_stream_set_counters(hx_stream_t stream,
perf_counter_t rx_frames, perf_counter_t rx_frames,
perf_counter_t rx_errors); perf_counter_t rx_errors);
/**
* Reset a stream.
*
* Forces the local stream state to idle.
*
* @param stream A handle returned from hx_stream_init.
*/
__EXPORT extern void hx_stream_reset(hx_stream_t stream);
/**
* Prepare to send a frame.
*
* Use this in conjunction with hx_stream_send_next to
* set the frame to be transmitted.
*
* Use hx_stream_send() to write to the stream fd directly.
*
* @param stream A handle returned from hx_stream_init.
* @param data Pointer to the data to send.
* @param count The number of bytes to send.
* @return Zero on success, -errno on error.
*/
__EXPORT extern int hx_stream_start(hx_stream_t stream,
const void *data,
size_t count);
/**
* Get the next byte to send for a stream.
*
* This requires that the stream be prepared for sending by
* calling hx_stream_start first.
*
* @param stream A handle returned from hx_stream_init.
* @return The byte to send, or -1 if there is
* nothing left to send.
*/
__EXPORT extern int hx_stream_send_next(hx_stream_t stream);
/** /**
* Send a frame. * Send a frame.
* *

27
src/modules/systemlib/perf_counter.c

@ -201,6 +201,8 @@ perf_end(perf_counter_t handle)
switch (handle->type) { switch (handle->type) {
case PC_ELAPSED: { case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle; struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
if (pce->time_start != 0) {
hrt_abstime elapsed = hrt_absolute_time() - pce->time_start; hrt_abstime elapsed = hrt_absolute_time() - pce->time_start;
pce->event_count++; pce->event_count++;
@ -211,13 +213,38 @@ perf_end(perf_counter_t handle)
if (pce->time_most < elapsed) if (pce->time_most < elapsed)
pce->time_most = elapsed; pce->time_most = elapsed;
pce->time_start = 0;
}
} }
break;
default: default:
break; break;
} }
} }
void
perf_cancel(perf_counter_t handle)
{
if (handle == NULL)
return;
switch (handle->type) {
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
pce->time_start = 0;
}
break;
default:
break;
}
}
void void
perf_reset(perf_counter_t handle) perf_reset(perf_counter_t handle)
{ {

14
src/modules/systemlib/perf_counter.h

@ -92,13 +92,25 @@ __EXPORT extern void perf_begin(perf_counter_t handle);
* End a performance event. * End a performance event.
* *
* This call applies to counters that operate over ranges of time; PC_ELAPSED etc. * This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
* If a call is made without a corresopnding perf_begin call, or if perf_cancel
* has been called subsequently, no change is made to the counter.
* *
* @param handle The handle returned from perf_alloc. * @param handle The handle returned from perf_alloc.
*/ */
__EXPORT extern void perf_end(perf_counter_t handle); __EXPORT extern void perf_end(perf_counter_t handle);
/** /**
* Reset a performance event. * Cancel a performance event.
*
* This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
* It reverts the effect of a previous perf_begin.
*
* @param handle The handle returned from perf_alloc.
*/
__EXPORT extern void perf_cancel(perf_counter_t handle);
/**
* Reset a performance counter.
* *
* This call resets performance counter to initial state * This call resets performance counter to initial state
* *

Loading…
Cancel
Save