This commit adds a 1wire subsystem.

Squashed commit of the following:

Author: Gregory Nutt <gnutt@nuttx.org>
    Some cosmetic changes from coding style review.
Author: Juha Niskanen <juha.niskanen@haltian.com>
    drivers/1wire: add 1-wire subsystem and ds28e17 driver
This commit is contained in:
Juha Niskanen 2018-04-04 10:57:36 -06:00 committed by Gregory Nutt
parent b4c1ac0659
commit 797d9b1822
11 changed files with 2092 additions and 11 deletions

640
drivers/1wire/1wire.c Normal file
View File

@ -0,0 +1,640 @@
/****************************************************************************
* drivers/1wire/1wire.c
*
* Copyright (C) 2018 Haltian Ltd. All rights reserved.
* Author: Juha Niskanen <juha.niskanen@haltian.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <errno.h>
#include <debug.h>
#include <string.h>
#include <nuttx/kmalloc.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/drivers/1wire.h>
#include "1wire_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define MATCH_FAMILY(rom, family) ((family) == 0 || ((rom) & 0xff) == (family))
#ifndef CONFIG_ENDIAN_BIG
# define onewire_leuint64(x) (x)
# define onewire_leuint32(x) (x)
#endif
#define NO_HOLDER ((pid_t)-1)
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: onewire_leuint64
*
* Description:
* Get a 64-bit value stored in little endian order for a big-endian
* machine.
*
****************************************************************************/
#ifdef CONFIG_ENDIAN_BIG
static inline uint64_t onewire_leuint64(uint64_t x)
{
return (((x & 0xff00000000000000ull) >> 56) |
((x & 0x00ff000000000000ull) >> 40) |
((x & 0x0000ff0000000000ull) >> 24) |
((x & 0x000000ff00000000ull) >> 8) |
((x & 0x00000000ff000000ull) << 8) |
((x & 0x0000000000ff0000ull) << 24) |
((x & 0x000000000000ff00ull) << 40) |
((x & 0x00000000000000ffull) << 56));
}
#endif
/****************************************************************************
* Name: onewire_leuint32
*
* Description:
* Get a 32-bit value stored in little endian order for a big-endian
* machine.
*
****************************************************************************/
#ifdef CONFIG_ENDIAN_BIG
static inline uint32_t onewire_leuint32(uint32_t x)
{
return (((x & 0xff000000) >> 24) |
((x & 0x00ff0000) >> 8) |
((x & 0x0000ff00) << 8) |
((x & 0x000000ff) << 24));
}
#endif
/****************************************************************************
* Name: onewire_sem_init
*
* Description:
*
****************************************************************************/
static inline void onewire_sem_init(FAR struct onewire_sem_s *sem)
{
sem->holder = NO_HOLDER;
sem->count = 0;
nxsem_init(&sem->sem, 0, 1);
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: onewire_sem_wait
*
* Description:
* Take the exclusive access, waiting as necessary
*
****************************************************************************/
void onewire_sem_wait(FAR struct onewire_master_s *master)
{
pid_t me;
/* Do we already hold the semaphore? */
me = getpid();
if (me == master->devsem.holder)
{
/* Yes... just increment the count */
master->devsem.count++;
DEBUGASSERT(master->devsem.count > 0);
}
/* Take the semaphore (perhaps waiting) */
else
{
int ret;
do
{
ret = nxsem_wait(&master->devsem.sem);
/* The only case that an error should occur here is if the wait
* was awakened by a signal.
*/
DEBUGASSERT(ret == OK || ret == -EINTR);
}
while (ret == -EINTR);
/* No we hold the semaphore */
master->devsem.holder = me;
master->devsem.count = 1;
}
}
/****************************************************************************
* Name: onewire_sem_post
*
* Description:
* Release the mutual exclusion semaphore
*
****************************************************************************/
void onewire_sem_post(FAR struct onewire_master_s *master)
{
DEBUGASSERT(master->devsem.holder == getpid());
/* Is this our last count on the semaphore? */
if (master->devsem.count > 1)
{
/* No.. just decrement the count */
master->devsem.count--;
}
/* Yes.. then we can really release the semaphore */
else
{
master->devsem.holder = NO_HOLDER;
master->devsem.count = 0;
nxsem_post(&master->devsem.sem);
}
}
/****************************************************************************
* Name: onewire_reset_resume
*
* Description:
*
****************************************************************************/
int onewire_reset_resume(FAR struct onewire_master_s *master)
{
int ret;
uint8_t buf[] = { ONEWIRE_CMD_RESUME };
ret = ONEWIRE_RESET(master->dev);
if (ret < 0)
{
return ret;
}
return ONEWIRE_WRITE(master->dev, buf, 1);
}
/****************************************************************************
* Name: onewire_reset_select
*
* Description:
*
****************************************************************************/
int onewire_reset_select(FAR struct onewire_slave_s *slave)
{
FAR struct onewire_master_s *master = slave->master;
uint64_t tmp;
uint8_t skip_rom[1] = { ONEWIRE_CMD_SKIP_ROM };
uint8_t match_rom[9] = { ONEWIRE_CMD_MATCH_ROM, 0 };
int ret;
ret = ONEWIRE_RESET(master->dev);
if (ret < 0)
{
return ret;
}
/* Issue skip-ROM if single slave, match-ROM otherwise. */
if (master->nslaves == 1)
{
ret = ONEWIRE_WRITE(master->dev, skip_rom, sizeof(skip_rom));
}
else
{
tmp = onewire_leuint64(slave->romcode);
memcpy(&match_rom[1], &tmp, 8);
ret = ONEWIRE_WRITE(master->dev, match_rom, sizeof(match_rom));
}
return ret;
}
/****************************************************************************
* Name: onewire_readrom
*
* Description:
*
****************************************************************************/
int onewire_readrom(FAR struct onewire_master_s *master, FAR uint64_t *rom)
{
uint8_t txbuf[] = { ONEWIRE_CMD_READ_ROM };
uint8_t rxbuf[8] = { 0 };
uint64_t tmp = -1;
int ret;
DEBUGASSERT(master != NULL && rom != NULL);
/* Read ROM-code of single connected slave and check its checksum. */
ret = ONEWIRE_RESET(master->dev);
if (ret < 0)
{
return ret;
}
ret = ONEWIRE_WRITE(master->dev, txbuf, sizeof(txbuf));
if (ret < 0)
{
return ret;
}
ret = ONEWIRE_READ(master->dev, rxbuf, sizeof(rxbuf));
if (ret < 0)
{
return ret;
}
#ifdef CONFIG_DEBUG_I2C_INFO
lib_dumpbuffer("onewire_readrom: rxbuf", rxbuf, sizeof(rxbuf));
#endif
tmp = onewire_leuint64(*(uint64_t *)rxbuf);
#ifdef CONFIG_DEBUG_FEATURES
if (!onewire_valid_rom(tmp))
{
i2cerr("ERROR: crc8 does not match!\n");
ret = -EIO;
}
#endif
*rom = tmp;
return ret;
}
/****************************************************************************
* Name: onewire_triplet
*
* Description:
* Used by 1-wire search algorithm. Reads two bits and writes
* one based on comparison of read bits.
*
* Input Parameters:
* search_bit - Bit to write if both id_bit and cmp_id_bit match
*
* Output Parameters:
* taken_bit - Bit indicating the direction where the search is
* progressing.
*
* Return Value:
* Number of valid bits or negative on error.
*
****************************************************************************/
int onewire_triplet(FAR struct onewire_master_s *master,
uint8_t search_bit,
FAR uint8_t *taken_bit)
{
int ret;
int nvalid;
uint8_t id_bit;
uint8_t cmp_id_bit;
ret = ONEWIRE_READBIT(master->dev, &id_bit);
if (ret < 0)
{
return ret;
}
ret = ONEWIRE_READBIT(master->dev, &cmp_id_bit);
if (ret < 0)
{
return ret;
}
if (id_bit == 1 && cmp_id_bit == 1)
{
/* No devices on bus */
return 0;
}
else if (id_bit != cmp_id_bit)
{
/* Only one bit is valid, search to that direction. */
nvalid = 1;
*taken_bit = id_bit;
}
else
{
/* Two bits are valid, search to pre-determined direction. */
nvalid = 2;
*taken_bit = search_bit;
}
ret = ONEWIRE_WRITEBIT(master->dev, taken_bit);
if (ret < 0)
{
return ret;
}
return nvalid;
}
/****************************************************************************
* Name: onewire_search
*
* Description:
* Search all devices from a 1-wire network. This is the 1-wire search
* algorithm from Maxim Application Note 187.
*
* Input Parameters:
* master - Pointer to the allocated 1-wire interface
* family - Limit search to devices of matching family
* alarmonly - Limit search to devices on alarm state
* cb_search - Callback to call on each device found
* arg - Argument passed to cb_search
*
* Return Value:
* Number of slaves present and matching family.
*
****************************************************************************/
int onewire_search(FAR struct onewire_master_s *master,
int family,
bool alarmonly,
CODE void (*cb_search)(int family, uint64_t romcode, FAR void *arg),
FAR void *arg)
{
FAR struct onewire_dev_s *dev = master->dev;
uint8_t cmd[1];
uint64_t rom = 0;
uint64_t last_rom;
int last_zero = -1;
int last_bit = 64; /* bit of last discrepancy */
int nslaves = 0;
int nslaves_match = 0;
int ret;
/* Disallow nested search. */
DEBUGASSERT(master->insearch == false);
/* Skip costly search if bus supports only a single slave. */
if (master->maxslaves == 1)
{
ret = onewire_readrom(master, &rom);
if (ret >= 0 && MATCH_FAMILY(rom, family))
{
master->insearch = true;
cb_search(rom & 0xff, rom, arg);
master->insearch = false;
nslaves_match++;
}
return (ret < 0) ? ret : nslaves_match;
}
/* Select search type. */
cmd[0] = alarmonly ? ONEWIRE_CMD_ALARM_SEARCH : ONEWIRE_CMD_SEARCH;
while (nslaves++ < master->maxslaves)
{
int i;
/* Reset bus so slaves are ready to answer our probing. */
ret = ONEWIRE_RESET(dev);
if (ret < 0)
{
return ret;
}
/* Send the Search-ROM command. */
ret = ONEWIRE_WRITE(dev, cmd, sizeof(cmd));
if (ret < 0)
{
return ret;
}
last_rom = rom;
rom = 0;
/* TODO: setup initial rom from family to reduce search space. */
for (i = 0; i < 64; i++)
{
uint8_t search_bit;
uint8_t taken_bit;
/* Setup search direction. */
if (i == last_bit)
{
search_bit = 1;
}
else if (i > last_bit)
{
search_bit = 0;
}
else
{
search_bit = !!(last_rom & (1 << i));
}
ret = onewire_triplet(master, search_bit, &taken_bit);
if (ret <= 0)
{
/* Error or zero valid directions. */
return ret;
}
if (ret == 2 && taken_bit == 0)
{
/* If both directions were valid, and we took the 0 path,
* remember this.
*/
last_zero = i;
}
/* Update rom code from taken bit. */
rom |= (uint64_t)taken_bit << i;
}
#ifdef CONFIG_DEBUG_FEATURES
if (!onewire_valid_rom(rom))
{
i2cerr("ERROR: crc8 does not match!\n");
}
#endif
if (last_zero == last_bit || last_zero == -1)
{
i2cinfo("search complete, rom=0x%llx\n", rom);
/* Found last device, quit searching. */
if (MATCH_FAMILY(rom, family))
{
master->insearch = true;
cb_search(rom & 0xff, rom, arg);
master->insearch = false;
nslaves_match++;
}
break;
}
last_bit = last_zero;
/* Found device, will keep looking for more. */
if (MATCH_FAMILY(rom, family))
{
master->insearch = true;
cb_search(rom & 0xff, rom, arg);
master->insearch = false;
nslaves_match++;
}
/* TODO: does not handle case when there are more than maxslaves
* slaves present in the bus.
*/
}
return nslaves_match;
}
/****************************************************************************
* Name: onewire_addslave
*
* Description:
*
****************************************************************************/
int onewire_addslave(FAR struct onewire_master_s *master,
FAR struct onewire_slave_s *slave)
{
DEBUGASSERT(master != NULL && slave != NULL);
DEBUGASSERT(slave->master == NULL);
if (master->nslaves >= master->maxslaves)
{
return -EAGAIN;
}
/* TODO: linked list of slaves? */
master->nslaves++;
slave->master = master;
return OK;
}
/****************************************************************************
* Name: onewire_removeslave
*
* Description:
*
****************************************************************************/
int onewire_removeslave(FAR struct onewire_master_s *master,
FAR struct onewire_slave_s *slave)
{
DEBUGASSERT(master != NULL && slave != NULL);
DEBUGASSERT(master->nslaves > 0 && slave->master == master);
/* TODO: linked list of slaves? */
master->nslaves--;
slave->master = NULL;
return OK;
}
/****************************************************************************
* Name: onewire_initialize
*
* Description:
* Return 1-wire bus master from 1-wire lower half device.
*
* Input Parameters:
* dev - Pointer to the allocated 1-wire lower half
* maxslaves - Maximum number of 1-wire slave devices
*
****************************************************************************/
FAR struct onewire_master_s *
onewire_initialize(FAR struct onewire_dev_s *dev, int maxslaves)
{
FAR struct onewire_master_s *master;
DEBUGASSERT(dev != NULL);
DEBUGASSERT(maxslaves > 0);
master = (FAR struct onewire_master_s *)kmm_malloc(sizeof(struct onewire_master_s));
if (master == NULL)
{
i2cerr("ERROR: Failed to allocate\n");
return NULL;
}
/* Initialize the device structure */
master->dev = dev;
onewire_sem_init(&master->devsem);
master->nslaves = 0;
master->maxslaves = maxslaves;
master->insearch = false;
return master;
}

159
drivers/1wire/1wire_crc.c Normal file
View File

@ -0,0 +1,159 @@
/****************************************************************************
* drivers/1wire/1wire_crc.c
*
* Copyright (C) 2018 Haltian Ltd. All rights reserved.
* Author: Juha Niskanen <juha.niskanen@haltian.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include "1wire_internal.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/* Compute a Dallas Semiconductor 8 bit CRC. */
uint8_t onewire_crc8(FAR const uint8_t *input, uint8_t len)
{
uint8_t crc = 0;
while (len-- > 0)
{
int i;
uint8_t inbyte = *input++;
for (i = 0; i < 8; i++)
{
uint8_t mix = (crc ^ inbyte) & 0x01;
crc >>= 1;
if (mix)
crc ^= 0x8c;
inbyte >>= 1;
}
}
return crc;
}
/* Compute a Dallas Semiconductor 16 bit CRC. This is used to check
* the integrity of received data from many 1-wire devices.
*
* Note: the CRC-16 computed here is not what you'll get from the 1-wire
* network, because:
* - The CRC-16 is transmitted bitwise inverted.
* - The binary representation of the return value may have a different
* byte order than the two bytes you get from 1-wire due to endian-ness.
*/
uint16_t onewire_crc16(FAR const uint8_t *input, uint16_t len,
uint16_t initial_crc)
{
uint16_t crc = initial_crc;
while (len-- > 0)
{
int i;
uint8_t inbyte = *input++;
for (i = 0; i < 8; i++)
{
uint8_t mix = ((crc & 0xff) ^ inbyte) & 0x01;
crc >>= 1;
if (mix)
{
crc ^= 0xa001;
}
inbyte >>= 1;
}
}
return crc;
}
/****************************************************************************
* Name: onewire_valid_rom
*
* Description:
* Check CRC-8 of received input
*
* Input Parameters:
* rom - 64-bit rom code
*
* Returned Value:
* true if CRC-8 of rom matches
*
****************************************************************************/
bool onewire_valid_rom(uint64_t rom)
{
uint8_t crc;
uint8_t buf[8];
memcpy(buf, &rom, sizeof(buf));
crc = onewire_crc8(buf, 7);
return crc == buf[7];
}
/****************************************************************************
* Name: onewire_check_crc16
*
* Description:
* Check CRC-16 of received input
*
* Input Parameters:
* input - Array of bytes to checksum
* len - Length of input
* inverted_crc - The two CRC16 bytes in the received data
*
* Returned Value:
* true if CRC-16 matches
*
****************************************************************************/
bool onewire_check_crc16(FAR const uint8_t *input, uint16_t len,
FAR const uint8_t *inverted_crc)
{
uint16_t crc;
crc = ~onewire_crc16(input, len, 0);
return (crc & 0xff) == inverted_crc[0] && (crc >> 8) == inverted_crc[1];
}

View File

@ -0,0 +1,180 @@
/****************************************************************************
* drivers/1wire/1wire_internal.h
*
* Copyright (C) 2018 Haltian Ltd. All rights reserved.
* Author: Juha Niskanen <juha.niskanen@haltian.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __DRIVERS_1WIRE_1WIRE_INTERNAL_H
#define __DRIVERS_1WIRE_1WIRE_INTERNAL_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include <semaphore.h>
/****************************************************************************
* Public Types
****************************************************************************/
struct onewire_dev_s;
struct onewire_sem_s
{
sem_t sem;
pid_t holder; /* The current holder of the semaphore */
int16_t count; /* Number of counts held */
};
struct onewire_master_s
{
FAR struct onewire_dev_s *dev; /* 1-Wire lower half */
struct onewire_sem_s devsem; /* Re-entrant semaphore */
int nslaves; /* Number of 1-wire slaves */
int maxslaves; /* Maximum number of 1-wire slaves */
bool insearch; /* If we are in middle of 1-wire search */
};
struct onewire_slave_s
{
FAR struct onewire_master_s *master; /* Slave's bus master */
uint64_t romcode; /* Unique ROM id in bus */
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/* CRC helpers from 1wire_crc.c */
uint8_t onewire_crc8(FAR const uint8_t *input, uint8_t len);
uint16_t onewire_crc16(FAR const uint8_t *input, uint16_t len,
uint16_t initial_crc);
bool onewire_valid_rom(uint64_t rom);
bool onewire_check_crc16(FAR const uint8_t *input, uint16_t len,
FAR const uint8_t *inverted_crc);
/* Rest are from 1wire.c */
void onewire_sem_wait(FAR struct onewire_master_s *master);
void onewire_sem_post(FAR struct onewire_master_s *master);
int onewire_addslave(FAR struct onewire_master_s *master,
FAR struct onewire_slave_s *slave);
int onewire_removeslave(FAR struct onewire_master_s *master,
FAR struct onewire_slave_s *slave);
/****************************************************************************
* Name: onewire_reset_resume
*
* Description:
*
****************************************************************************/
int onewire_reset_resume(FAR struct onewire_master_s *master);
/****************************************************************************
* Name: onewire_reset_select
*
* Description:
*
****************************************************************************/
int onewire_reset_select(FAR struct onewire_slave_s *slave);
/****************************************************************************
* Name: onewire_triplet
*
* Description:
* Used by 1-wire search algorithm. Reads two bits and writes
* one based on comparison of read bits.
*
* Input Parameters:
* search_bit - Bit to write if both id_bit and cmp_id_bit match
*
* Output Parameters:
* taken_bit - Bit indicating the direction where the search is
* progressing.
*
* Return Value:
* Number of valid bits or negative on error.
*
****************************************************************************/
int onewire_triplet(FAR struct onewire_master_s *master,
uint8_t search_bit,
FAR uint8_t *taken_bit);
/****************************************************************************
* Name: onewire_search
*
* Description:
* Search all devices from a 1-wire network. This is the 1-wire search
* algorithm from Maxim Application Note 187.
*
* Input Parameters:
* master - Pointer to the allocated 1-wire interface
* family - Limit search to devices of matching family
* alarmonly - Limit search to devices on alarm state
* cb_search - Callback to call on each device found
* arg - Argument passed to cb_search
*
* Return Value:
* Number of slaves present and matching family.
*
****************************************************************************/
int onewire_search(FAR struct onewire_master_s *master,
int family,
bool alarmonly,
CODE void (*cb_search)(int family, uint64_t romcode, FAR void *arg),
FAR void *arg);
/****************************************************************************
* Name: onewire_initialize
*
* Description:
* Return 1-wire bus master from 1-wire lower half device.
*
* Input Parameters:
* dev - Pointer to the allocated 1-wire lower half
* maxslaves - Maximum number of 1-wire slave devices
*
****************************************************************************/
FAR struct onewire_master_s *
onewire_initialize(FAR struct onewire_dev_s *dev, int maxslaves);
#endif /* __DRIVERS_1WIRE_1WIRE_INTERNAL_H */

15
drivers/1wire/Kconfig Normal file
View File

@ -0,0 +1,15 @@
#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
if 1WIRE
config 1WIRE_DS28E17
bool "DS28E17 1-wire to I2C converter"
default n
depends on I2C
---help---
Enable support for the Maxim DS28E17 1-wire to I2C converter
endif # 1WIRE

49
drivers/1wire/Make.defs Normal file
View File

@ -0,0 +1,49 @@
############################################################################
# drivers/1wire/Make.defs
#
# Copyright (C) 2018 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
ifeq ($(CONFIG_1WIRE),y)
CSRCS += 1wire.c 1wire_crc.c
ifeq ($(CONFIG_1WIRE_DS28E17),y)
CSRCS += ds28e17.c
endif
# Include 1wire device driver build support
DEPPATH += --dep-path 1wire
VPATH += :1wire
CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)1wire}
endif

872
drivers/1wire/ds28e17.c Normal file
View File

@ -0,0 +1,872 @@
/****************************************************************************
* drivers/1wire/ds28e17.c
*
* Copyright (C) 2018 Haltian Ltd. All rights reserved.
* Author: Juha Niskanen <juha.niskanen@haltian.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <errno.h>
#include <debug.h>
#include <string.h>
#include <nuttx/kmalloc.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/drivers/1wire.h>
#include <nuttx/1wire/ds28e17.h>
#include "1wire_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef CONFIG_DS28E17_I2C_FREQUENCY
# define CONFIG_DS28E17_I2C_FREQUENCY 400000
#endif
/* DS28E17 device 1-Wire family ID */
#define DS_FAMILY 0x19
/* DS28E17 device I2C commands */
#define DS_WRITE_DATA_WITH_STOP 0x4b
#define DS_WRITE_DATA_NO_STOP 0x5a
#define DS_WRITE_DATA_ONLY 0x69
#define DS_WRITE_DATA_ONLY_WITH_STOP 0x78
#define DS_READ_DATA_WITH_STOP 0x87
#define DS_WRITE_READ_DATA_WITH_STOP 0x2d
#define DS_WRITE_CONFIGURATION 0xd2
#define DS_READ_CONFIGURATION 0xe1
#define DS_ENABLE_SLEEP_MODE 0x1e
#define DS_READ_DEVICE_REVISION 0xc4
/* DS28E17 status bits */
#define DS_STATUS_CRC 0x01
#define DS_STATUS_ADDRESS 0x02
#define DS_STATUS_START 0x08
/* Maximum number of I2C bytes to transfer within one CRC16 protected onewire
* command (same for either read and write).
*/
#define DS_DATA_LIMIT 255
/* Default I2C frequency to use when DS28E17 is detected. */
#define DS_DEFAULT_FREQUENCY CONFIG_DS28E17_I2C_FREQUENCY
/* Default I2C stretch value. */
#define DS_DEFAULT_STRETCH 1
/* How many times to retry check for chip busy condition vanishing. */
#define DS_BUSYWAIT_RETRIES 500
/****************************************************************************
* Private Types
****************************************************************************/
struct ds28e17_dev_s /* Must be cast-compatible with onewire_master_s */
{
FAR struct onewire_dev_s *dev; /* 1-wire interface */
};
/* I2C Device, Instance */
struct ds_i2c_inst_s /* Must be cast-compatible with i2c_master_s */
{
FAR const struct i2c_ops_s *ops; /* Standard I2C operations */
/* 1-wire data */
FAR struct onewire_master_s *master; /* 1-wire bus master */
FAR struct onewire_slave_s slave; /* Our slave data on 1-wire bus */
/* I2C data */
uint32_t frequency; /* Current I2C frequency */
uint8_t stretch; /* Current I2C stretch value */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int ds_i2c_reset(FAR struct i2c_master_s *i2cdev);
static int ds_i2c_transfer(FAR struct i2c_master_s *i2cdev,
FAR struct i2c_msg_s *msgs, int count);
/****************************************************************************
* Private Data
****************************************************************************/
/* Device Structures, Instantiation */
static const struct i2c_ops_s ds_i2c_ops =
{
.transfer = ds_i2c_transfer
#ifdef CONFIG_I2C_RESET
, .reset = ds_i2c_reset
#endif
};
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: ds_i2c_sem_wait
*
* Description:
* Take the exclusive access, waiting as necessary
*
****************************************************************************/
static inline void ds_i2c_sem_wait(FAR struct i2c_master_s *i2cdev)
{
FAR struct ds_i2c_inst_s *inst = (FAR struct ds_i2c_inst_s *)i2cdev;
FAR struct onewire_master_s *master = inst->master;
return onewire_sem_wait(master);
}
/****************************************************************************
* Name: ds_i2c_sem_post
*
* Description:
* Release the mutual exclusion semaphore
*
****************************************************************************/
static inline void ds_i2c_sem_post(FAR struct i2c_master_s *i2cdev)
{
FAR struct ds_i2c_inst_s *inst = (FAR struct ds_i2c_inst_s *)i2cdev;
FAR struct onewire_master_s *master = inst->master;
onewire_sem_post(master);
}
static int ds_error(uint8_t buf[])
{
/* Warnings */
if (buf[0] & DS_STATUS_CRC)
{
i2cwarn("crc16 match failed\n");
}
if ((buf[0] & (DS_STATUS_CRC | DS_STATUS_ADDRESS)) == 0 && buf[1] != 0)
{
i2cwarn("I2C short write, no ack for %d bytes\n", buf[1]);
}
/* Error conditions */
if (buf[0] & DS_STATUS_ADDRESS)
{
i2cerr("I2C device not responding\n");
return -ENXIO;
}
if (buf[0] & DS_STATUS_START)
{
i2cerr("I2C status start\n");
return -EAGAIN;
}
if (buf[0] != 0 || buf[1] != 0)
{
i2cerr("I2C IO error\n");
return -EIO;
}
return OK;
}
static inline int ds_busywait_time(FAR struct ds_i2c_inst_s *inst)
{
int d;
/* Return busywait time (us) for I2C speeds 100 kHz, 400 kHz
* and 900 kHz, adjusted with current stretch value.
*/
switch (inst->frequency)
{
case 100000:
d = 90;
break;
case 400000:
default:
d = 23;
break;
case 900000:
d = 10;
break;
}
return d * inst->stretch;
}
static int ds_busywait(FAR struct ds_i2c_inst_s *inst, size_t length)
{
FAR struct onewire_master_s *master = inst->master;
int retries = DS_BUSYWAIT_RETRIES;
int delay;
int ret;
uint8_t bit = 1;
/* Calculate delay time from current I2C settings. */
delay = ds_busywait_time(inst);
do
{
ret = ONEWIRE_READBIT(master->dev, &bit);
if (ret < 0)
{
i2cerr("ERROR: ONEWIRE_READBIT failed\n");
return ret;
}
if (bit == 0)
{
return OK;
}
if (retries == DS_BUSYWAIT_RETRIES)
{
/* First time, after checking bit once, do a big delay
* for I2C to process all bytes in message.
*/
up_udelay(delay * length);
}
else
{
/* Otherwise, wait for one byte duration. */
up_udelay(delay);
}
} while (retries-- > 0);
i2cwarn("busywait timeout\n");
return -ETIMEDOUT;
}
/****************************************************************************
* Name: ds_i2c_read
*
* Description:
* Read data from I2C slave.
*
****************************************************************************/
static int ds_i2c_read(FAR struct ds_i2c_inst_s *inst, uint16_t i2c_addr,
FAR uint8_t *buffer, ssize_t length)
{
FAR struct onewire_master_s *master = inst->master;
uint16_t crc;
int ret;
uint8_t buf[5];
if (length <= 0)
{
return -EINVAL;
}
if (length > DS_DATA_LIMIT)
{
i2cerr("ERROR: reading too many bytes!\n");
return -EINVAL;
}
/* Send command to DS28E17. */
buf[0] = DS_READ_DATA_WITH_STOP;
buf[1] = i2c_addr << 1 | 0x01;
buf[2] = length;
crc = onewire_crc16(buf, 3, 0);
buf[3] = ~(crc & 0xff);
buf[4] = ~((crc >> 8) & 0xff);
ret = ONEWIRE_WRITE(master->dev, buf, 5);
if (ret < 0)
{
return ret;
}
/* Wait busy indication to vanish. */
ret = ds_busywait(inst, length + 1);
if (ret < 0)
{
return ret;
}
/* Read status from DS28E17. */
ret = ONEWIRE_READ(master->dev, buf, 1);
buf[1] = 0;
/* Check error conditions. */
ret = ds_error(buf);
if (ret < 0)
{
return ret;
}
/* Read received I2C data from DS28E17. */
return ONEWIRE_READ(master->dev, buffer, length);
}
/****************************************************************************
* Name: ds_i2c_write
*
* Description:
* Write data to I2C slave.
*
****************************************************************************/
static int ds_i2c_write(FAR struct ds_i2c_inst_s *inst, uint16_t i2c_addr,
FAR const uint8_t *buffer, ssize_t length, bool stop)
{
FAR struct onewire_master_s *master = inst->master;
uint16_t crc;
int ret;
uint8_t buf[5];
if (length <= 0)
{
return -EINVAL;
}
if (length > DS_DATA_LIMIT)
{
/* TODO: split big writes into multiple chunks. */
i2cerr("ERROR: writing too many bytes!\n");
return -EINVAL;
}
/* Write command header. */
buf[0] = stop ? DS_WRITE_DATA_WITH_STOP : DS_WRITE_DATA_NO_STOP;
buf[1] = i2c_addr << 1;
buf[2] = length;
crc = onewire_crc16(buf, 3, 0);
ret = ONEWIRE_WRITE(master->dev, buf, 3);
if (ret < 0)
{
return ret;
}
/* Write payload I2C data to DS28E17. */
crc = onewire_crc16(buffer, length, crc);
ret = ONEWIRE_WRITE(master->dev, buffer, length);
if (ret < 0)
{
return ret;
}
/* Write checksum. */
buf[0] = ~(crc & 0xff);
buf[1] = ~((crc >> 8) & 0xff);
ret = ONEWIRE_WRITE(master->dev, buf, 2);
if (ret < 0)
{
return ret;
}
/* Wait busy indication to vanish. */
ret = ds_busywait(inst, length + 1);
if (ret < 0)
{
return ret;
}
/* Read status from DS28E17. */
ret = ONEWIRE_READ(master->dev, buf, 2);
if (ret < 0)
{
return ret;
}
/* Check error conditions. */
ret = ds_error(buf);
if (ret < 0)
{
return ret;
}
/* Return count of bytes written. */
return length;
}
static int ds_i2c_setfrequency(FAR struct ds_i2c_inst_s *inst, uint32_t frequency)
{
FAR struct onewire_master_s *master = inst->master;
uint8_t buf[2];
int speed;
int ret;
switch (frequency)
{
case 100000:
speed = 0;
break;
case 400000:
speed = 1;
break;
case 900000:
speed = 2;
break;
default:
i2cerr("ERROR: bad I2C freq %u\n", frequency);
return -EINVAL;
}
i2cinfo("Changing I2C freq %u -> %u\n", inst->frequency, frequency);
/* Select DS28E17 */
ret = onewire_reset_select(&inst->slave);
if (ret < 0)
{
i2cerr("ERROR: cannot change I2C freq\n");
return ret;
}
/* Write new speed to device */
buf[0] = DS_WRITE_CONFIGURATION;
buf[1] = speed;
ret = ONEWIRE_WRITE(master->dev, buf, 2);
if (ret < 0)
{
i2cerr("ERROR: cannot change I2C freq\n");
return ret;
}
inst->frequency = frequency;
return ret;
}
/****************************************************************************
* Name: ds_i2c_process
*
* Description:
* Common I2C transfer logic
*
* Initiates a master mode transaction on the I2C bus to transfer the
* provided messages to and from the slave devices.
*
****************************************************************************/
static int ds_i2c_process(FAR struct i2c_master_s *i2cdev,
FAR struct i2c_msg_s *msgs, int count)
{
FAR struct ds_i2c_inst_s *inst = (FAR struct ds_i2c_inst_s *)i2cdev;
FAR struct onewire_master_s *master = inst->master;
int ret;
int i;
/* Check from first message only, if we want to change I2C frequency. */
if (inst->frequency != msgs[0].frequency)
{
ds_i2c_setfrequency(inst, msgs[0].frequency);
}
/* Select DS28E17 */
i = onewire_reset_select(&inst->slave);
if (i < 0)
{
goto errout;
}
while (i < count)
{
/* TODO: we could use DS_WRITE_READ_DATA_WITH_STOP to optimize the
* common case of write followed by read to a same address.
*/
if (msgs[i].flags & I2C_M_READ)
{
/* Read transfer. */
ret = ds_i2c_read(inst, msgs[i].addr, msgs[i].buffer, msgs[i].length);
if (ret < 0)
{
i = ret;
goto errout;
}
}
else
{
/* Write transfer. Stop condition only for last transfer. */
ret = ds_i2c_write(inst, msgs[i].addr, msgs[i].buffer, msgs[i].length,
i == (count-1));
if (ret < 0)
{
i = ret;
goto errout;
}
}
/* Any more messages to process? */
i++;
if (i < count)
{
/* Yes. Resume to same DS28E17. */
/* Oddness: Skip-ROM does not set RS-bit needed by resume. */
if (master->nslaves > 1)
{
ret = onewire_reset_resume(master);
}
else
{
ret = onewire_reset_select(&inst->slave);
}
if (ret < 0)
{
i = ret;
goto errout;
}
}
}
errout:
return i;
}
/****************************************************************************
* Name: ds_i2c_reset
*
* Description:
* Reset an I2C bus
*
****************************************************************************/
#ifdef CONFIG_I2C_RESET
static int ds_i2c_reset(FAR struct i2c_master_s *i2cdev)
{
FAR struct ds_i2c_inst_s *inst = (FAR struct ds_i2c_inst_s *)i2cdev;
FAR struct onewire_master_s *master = inst->master;
int ret;
ds_i2c_sem_wait(i2cdev);
ret = ONEWIRE_RESET(master->dev);
ds_i2c_sem_post(i2cdev);
return ret;
}
#endif
/****************************************************************************
* Name: ds_i2c_transfer
*
* Description:
* Generic I2C transfer function
*
****************************************************************************/
static int ds_i2c_transfer(FAR struct i2c_master_s *i2cdev,
FAR struct i2c_msg_s *msgs,
int count)
{
int ret;
ds_i2c_sem_wait(i2cdev);
ret = ds_i2c_process(i2cdev, msgs, count);
ds_i2c_sem_post(i2cdev);
return ret;
}
/****************************************************************************
* Name: ds28e17_selftest
*
* Description:
*
****************************************************************************/
static int ds28e17_selftest(FAR struct ds_i2c_inst_s *inst)
{
FAR struct onewire_master_s *master = inst->master;
uint8_t txbuf[] = { ONEWIRE_CMD_READ_ROM };
uint8_t rxbuf[8] = { 0 };
uint64_t rom;
uint8_t crc;
int ret;
/* Read ROM-code of single connected slave and
* check its checksum.
*/
ret = ONEWIRE_RESET(master->dev);
if (ret < 0)
{
i2cerr("ERROR: ONEWIRE_RESET failed: %d\n", ret);
return ret;
}
ret = ONEWIRE_WRITE(master->dev, txbuf, sizeof(txbuf));
if (ret < 0)
{
i2cerr("ERROR: ONEWIRE_WRITE failed: %d\n", ret);
return ret;
}
ret = ONEWIRE_READ(master->dev, rxbuf, sizeof(rxbuf));
if (ret < 0)
{
i2cerr("ERROR: ONEWIRE_READ failed: %d\n", ret);
return ret;
}
#ifdef CONFIG_DEBUG_I2C_INFO
lib_dumpbuffer("ds28e17_selftest: rxbuf", rxbuf, sizeof(rxbuf));
#endif
memcpy(&rom, rxbuf, 8);
i2cinfo("recv rom: 0x%llx\n", rom);
crc = onewire_crc8(rxbuf, sizeof(rxbuf)-1);
i2cinfo("crc8=%d, recv crc8=%d\n", crc, (int)rxbuf[7]);
if (crc != rxbuf[7])
{
i2cerr("ERROR: crc8 does not match!\n");
ret = -EIO;
}
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: ds28e17_search
*
* Description:
* Search all DS28E17 devices from a 1-wire network.
*
* Input Parameters:
* priv - Pointer to the associated DS28E17
* cb_search - Callback to call on each device found
* arg - Argument passed to cb_search
*
* Return Value:
* Number of DS28E17 devices present.
*
****************************************************************************/
int ds28e17_search(FAR struct ds28e17_dev_s *priv,
void (*cb_search)(int family, uint64_t romcode, void *arg),
void *arg)
{
FAR struct onewire_master_s *master = (FAR struct onewire_master_s *)priv;
int ret;
DEBUGASSERT(master != NULL && cb_search != NULL);
onewire_sem_wait(master);
ret = onewire_search(master, DS_FAMILY, false, cb_search, arg);
onewire_sem_post(master);
return ret;
}
/****************************************************************************
* Name: ds28e17_lower_half
*
* Description:
* Initialize the lower half of the DS28E17 by creating a i2c_master_s
* for the virtual i2c master and link it to the associated DS28E17 and
* its port.
*
* Input Parameters:
* dev - Pointer to the associated DS28E17
* romcode - The unique 64-bit address in 1-wire network.
* Use zero for skip-ROM mode.
*
* Returned Value:
* i2c device instance; NULL on failure.
*
****************************************************************************/
FAR struct i2c_master_s *
ds28e17_lower_half(FAR struct ds28e17_dev_s *priv, uint64_t romcode)
{
FAR struct ds_i2c_inst_s *inst; /* device, single instance */
FAR struct onewire_master_s *master = (FAR struct onewire_master_s *)priv;
DEBUGASSERT(master != NULL);
/* Allocate instance */
inst = kmm_malloc(sizeof(struct ds_i2c_inst_s));
if (inst == NULL)
{
i2cerr("ERROR: Failed to allocate instance\n");
return NULL;
}
/* Initialize instance */
inst->ops = &ds_i2c_ops;
inst->master = master;
inst->frequency = 400000; /* power-on frequency */
inst->stretch = DS_DEFAULT_STRETCH;
/* We need a recursive lock as this may be called from a search callback. */
onewire_sem_wait(master);
inst->slave.romcode = romcode;
if (onewire_addslave(master, &inst->slave) < 0)
{
kmm_free(inst);
i2cerr("ERROR: Failed to add slave\n");
onewire_sem_post(master);
return NULL;
}
/* Should default speed be different from DS28E17 power-on frequency? */
if (inst->frequency != DS_DEFAULT_FREQUENCY)
{
ds_i2c_setfrequency(inst, DS_DEFAULT_FREQUENCY);
}
/* TODO: better selftest */
if (master->maxslaves == 1)
{
ds28e17_selftest(inst);
}
onewire_sem_post(master);
return (struct i2c_master_s *)inst;
}
/****************************************************************************
* Name: ds28e17_lower_half_unregister
*
* Description:
* Put back the lower half of the DS28E17.
*
* Input Parameters:
* priv - Pointer to the associated DS28E17
* i2cdev - i2c device instance from ds28e17_lower_half()
*
* Returned Value:
* Zero on success; a negated errno value on failure.
*
****************************************************************************/
int ds28e17_lower_half_unregister(FAR struct ds28e17_dev_s *priv,
FAR struct i2c_master_s *i2cdev)
{
FAR struct ds_i2c_inst_s *inst = (FAR struct ds_i2c_inst_s *)i2cdev;
FAR struct onewire_master_s *master = inst->master;
int ret;
onewire_sem_wait(master);
ret = onewire_removeslave(master, &inst->slave);
if (ret < 0)
{
kmm_free(inst);
i2cerr("ERROR: Failed to remove slave\n");
onewire_sem_post(master);
return ret;
}
kmm_free(inst);
onewire_sem_post(master);
return OK;
}
/****************************************************************************
* Name: ds28e17_initialize
*
* Description:
* Returns a common DS28E17 device from 1-wire lower half device
*
* Input Parameters:
* dev - The allocated 1-wire lower half
*
****************************************************************************/
FAR struct ds28e17_dev_s *ds28e17_initialize(FAR struct onewire_dev_s *dev)
{
FAR struct onewire_master_s *priv;
priv = onewire_initialize(dev, DS_DEFAULT_MAXSLAVES);
/* We do not have our own data fields so just cast it. */
return (FAR struct ds28e17_dev_s *)priv;
}

View File

@ -477,4 +477,12 @@ menuconfig DRIVERS_CONTACTLESS
source drivers/contactless/Kconfig
menuconfig 1WIRE
bool "1wire Device Support"
default n
---help---
Drivers for various 1wire devices.
source drivers/1wire/Kconfig
source drivers/syslog/Kconfig

View File

@ -78,6 +78,7 @@ include usbmonitor$(DELIM)Make.defs
include video$(DELIM)Make.defs
include wireless$(DELIM)Make.defs
include contactless$(DELIM)Make.defs
include 1wire$(DELIM)Make.defs
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
CSRCS += dev_null.c dev_zero.c

View File

@ -0,0 +1,139 @@
/****************************************************************************
* include/nuttx/1wire/ds28e17.h
*
* Copyright (C) 2018 Haltian Ltd. All rights reserved.
* Author: Juha Niskanen <juha.niskanen@haltian.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES(INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __INCLUDE_NUTTX_1WIRE_DS28E17_H
#define __INCLUDE_NUTTX_1WIRE_DS28E17_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <nuttx/drivers/1wire.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Default how many converters in a bus. */
#define DS_DEFAULT_MAXSLAVES 10
/****************************************************************************
* Public Types
****************************************************************************/
struct ds28e17_dev_s;
struct i2c_master_s;
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: ds28e17_search
*
* Description:
* Search all DS28E17 devices from a 1-wire network.
*
* Input Parameters:
* priv - Pointer to the associated DS28E17
* cb_search - Callback to call on each device found
* arg - Argument passed to cb_search
*
* Return Value:
* Number of DS28E17 devices present.
*
****************************************************************************/
int ds28e17_search(FAR struct ds28e17_dev_s *priv,
CODE void (*cb_search)(int family, uint64_t romcode, FAR void *arg),
FAR oid *arg);
/****************************************************************************
* Name: ds28e17_lower_half
*
* Description:
* Initialize the lower half of the DS28E17 by creating a i2c_master_s
* for the virtual i2c master and link it to the associated DS28E17 and
* its port.
*
* Input Parameters:
* priv - Pointer to the associated DS28E17
* romcode - The unique 64-bit address in 1-wire network.
* Use zero for skip-ROM mode.
*
* Returned Value:
* i2c device instance; NULL on failure.
*
****************************************************************************/
FAR struct i2c_master_s *ds28e17_lower_half(FAR struct ds28e17_dev_s *priv,
uint64_t romcode);
/****************************************************************************
* Name: ds28e17_lower_half_unregister
*
* Description:
* Put back the lower half of the DS28E17.
*
* Input Parameters:
* priv - Pointer to the associated DS28E17
* i2cdev - i2c device instance from ds28e17_lower_half()
*
* Returned Value:
* Zero on success; a negated errno value on failure.
*
****************************************************************************/
int ds28e17_lower_half_unregister(FAR struct ds28e17_dev_s *priv,
FAR struct i2c_master_s *i2cdev);
/****************************************************************************
* Name: ds28e17_initialize
*
* Description:
* Returns a common DS28E17 device from 1-wire lower half device
*
* Input Parameters:
* dev - The allocated 1-wire lower half
*
****************************************************************************/
FAR struct ds28e17_dev_s *ds28e17_initialize(FAR struct onewire_dev_s *dev);
#endif /* __INCLUDE_NUTTX_1WIRE_DS28E17_H */

View File

@ -48,6 +48,18 @@
* Pre-processor Definitions
****************************************************************************/
/* Supported 1-Wire commands */
#define ONEWIRE_CMD_SEARCH 0xf0
#define ONEWIRE_CMD_ALARM_SEARCH 0xec
#define ONEWIRE_CMD_SKIP_ROM 0xcc
#define ONEWIRE_CMD_COPY_SCRATCHPAD 0x48
#define ONEWIRE_CMD_WRITE_SCRATCHPAD 0x4e
#define ONEWIRE_CMD_READ_SCRATCHPAD 0xbe
#define ONEWIRE_CMD_READ_ROM 0x33
#define ONEWIRE_CMD_MATCH_ROM 0x55
#define ONEWIRE_CMD_RESUME 0xa5
/****************************************************************************
* Name: ONEWIRE_RESET
*

View File

@ -217,10 +217,15 @@ static int btnet_advertise(FAR struct net_driver_s *dev)
DEBUGASSERT(dev != NULL && dev->d_private != NULL);
/* Get the 6-byte local address from the device */
#warning Missing logic
/* Get the 6-byte local address from the device.
*
* REVISIT: The use of the g_btdev global restricts the implementation to
* a single Bluetooth device.
*/
/* Set the MAC address using that address */
addr = g_btdev.bdaddr.val
/* Set the MAC address using 6-byte local address from the device. */
BLUETOOTH_ADDRCOPY(dev->d_mac.radio.nv_addr, addr);
dev->d_mac.radio.nv_addrlen = BLUETOOTH_ADDRSIZE;
@ -228,15 +233,16 @@ static int btnet_advertise(FAR struct net_driver_s *dev)
#ifdef CONFIG_NET_IPv6
/* Set the IP address based on the 6-byte address */
dev->d_ipv6addr[0] = HTONS(0xfe80);
dev->d_ipv6addr[1] = 0;
dev->d_ipv6addr[2] = 0;
dev->d_ipv6addr[3] = 0;
dev->d_ipv6addr[4] = HTONS(0x0200);
dev->d_ipv6addr[5] = (uint16_t)addr[0] << 8 | (uint16_t)addr[1];
dev->d_ipv6addr[6] = (uint16_t)addr[2] << 8 | (uint16_t)addr[3];
dev->d_ipv6addr[7] = (uint16_t)addr[4] << 8 | (uint16_t)addr[5];
dev->d_ipv6addr[0] = HTONS(0xfe80);
dev->d_ipv6addr[1] = 0;
dev->d_ipv6addr[2] = 0;
dev->d_ipv6addr[3] = 0;
dev->d_ipv6addr[4] = HTONS(0x0200);
dev->d_ipv6addr[5] = (uint16_t)addr[0] << 8 | (uint16_t)addr[1];
dev->d_ipv6addr[6] = (uint16_t)addr[2] << 8 | (uint16_t)addr[3];
dev->d_ipv6addr[7] = (uint16_t)addr[4] << 8 | (uint16_t)addr[5];
#endif
return OK;
}