adxl345: Change default chip name from "default" to "adxl345"
Signed-off-by: Kevin O'Connor <kevin@koconnor.net>
This commit is contained in:
parent
22167f9510
commit
404b64fd62
|
@ -8,6 +8,10 @@ All dates in this document are approximate.
|
||||||
|
|
||||||
## Changes
|
## Changes
|
||||||
|
|
||||||
|
20210830: The default adxl345 name is now "adxl345". The default CHIP
|
||||||
|
parameter for the `ACCELEROMETER_MEASURE` and `ACCELEROMETER_QUERY` is
|
||||||
|
now also "adxl345".
|
||||||
|
|
||||||
20210830: The adxl345 ACCELEROMETER_MEASURE command no longer supports
|
20210830: The adxl345 ACCELEROMETER_MEASURE command no longer supports
|
||||||
a RATE parameter. To alter the query rate, update the printer.cfg
|
a RATE parameter. To alter the query rate, update the printer.cfg
|
||||||
file and issue a RESTART command.
|
file and issue a RESTART command.
|
||||||
|
|
|
@ -727,7 +727,7 @@ The following commands are available when an
|
||||||
[adxl345 config section](Config_Reference.md#adxl345) is enabled:
|
[adxl345 config section](Config_Reference.md#adxl345) is enabled:
|
||||||
- `ACCELEROMETER_MEASURE [CHIP=<config_name>] [NAME=<value>]`: Starts
|
- `ACCELEROMETER_MEASURE [CHIP=<config_name>] [NAME=<value>]`: Starts
|
||||||
accelerometer measurements at the requested number of samples per
|
accelerometer measurements at the requested number of samples per
|
||||||
second. If CHIP is not specified it defaults to "default". The
|
second. If CHIP is not specified it defaults to "adxl345". The
|
||||||
command works in a start-stop mode: when executed for the first
|
command works in a start-stop mode: when executed for the first
|
||||||
time, it starts the measurements, next execution stops them. The
|
time, it starts the measurements, next execution stops them. The
|
||||||
results of measurements are written to a file named
|
results of measurements are written to a file named
|
||||||
|
@ -740,7 +740,7 @@ The following commands are available when an
|
||||||
generated.
|
generated.
|
||||||
- `ACCELEROMETER_QUERY [CHIP=<config_name>] [RATE=<value>]`: queries
|
- `ACCELEROMETER_QUERY [CHIP=<config_name>] [RATE=<value>]`: queries
|
||||||
accelerometer for the current value. If CHIP is not specified it
|
accelerometer for the current value. If CHIP is not specified it
|
||||||
defaults to "default". If RATE is not specified, the default value
|
defaults to "adxl345". If RATE is not specified, the default value
|
||||||
is used. This command is useful to test the connection to the
|
is used. This command is useful to test the connection to the
|
||||||
ADXL345 accelerometer: one of the returned values should be a
|
ADXL345 accelerometer: one of the returned values should be a
|
||||||
free-fall acceleration (+/- some noise of the chip).
|
free-fall acceleration (+/- some noise of the chip).
|
||||||
|
|
|
@ -83,11 +83,9 @@ class ADXLCommandHelper:
|
||||||
self.printer = config.get_printer()
|
self.printer = config.get_printer()
|
||||||
self.chip = chip
|
self.chip = chip
|
||||||
self.bg_client = None
|
self.bg_client = None
|
||||||
self.name = "default"
|
self.name = config.get_name().split()[-1]
|
||||||
if len(config.get_name().split()) > 1:
|
|
||||||
self.name = config.get_name().split()[1]
|
|
||||||
self.register_commands(self.name)
|
self.register_commands(self.name)
|
||||||
if self.name == "default":
|
if self.name == "adxl345":
|
||||||
self.register_commands(None)
|
self.register_commands(None)
|
||||||
def register_commands(self, name):
|
def register_commands(self, name):
|
||||||
# Register commands
|
# Register commands
|
||||||
|
@ -121,7 +119,7 @@ class ADXLCommandHelper:
|
||||||
self.bg_client = None
|
self.bg_client = None
|
||||||
bg_client.finish_measurements()
|
bg_client.finish_measurements()
|
||||||
# Write data to file
|
# Write data to file
|
||||||
if self.name == "default":
|
if self.name == "adxl345":
|
||||||
filename = "/tmp/adxl345-%s.csv" % (name,)
|
filename = "/tmp/adxl345-%s.csv" % (name,)
|
||||||
else:
|
else:
|
||||||
filename = "/tmp/adxl345-%s-%s.csv" % (self.name, name,)
|
filename = "/tmp/adxl345-%s-%s.csv" % (self.name, name,)
|
||||||
|
@ -246,9 +244,7 @@ class ADXL345:
|
||||||
# API server endpoints
|
# API server endpoints
|
||||||
self.api_dump = motion_report.APIDumpHelper(
|
self.api_dump = motion_report.APIDumpHelper(
|
||||||
self.printer, self._api_update, self._api_startstop, 0.100)
|
self.printer, self._api_update, self._api_startstop, 0.100)
|
||||||
self.name = "default"
|
self.name = config.get_name().split()[-1]
|
||||||
if len(config.get_name().split()) > 1:
|
|
||||||
self.name = config.get_name().split()[1]
|
|
||||||
wh = self.printer.lookup_object('webhooks')
|
wh = self.printer.lookup_object('webhooks')
|
||||||
wh.register_mux_endpoint("adxl345/dump_adxl345", "sensor", self.name,
|
wh.register_mux_endpoint("adxl345/dump_adxl345", "sensor", self.name,
|
||||||
self._handle_dump_adxl345)
|
self._handle_dump_adxl345)
|
||||||
|
|
Loading…
Reference in New Issue