initial upload

This commit is contained in:
Harald Pichler 2017-11-09 08:39:35 +01:00
parent 80388188f7
commit b929b419af
13 changed files with 914 additions and 0 deletions

View file

@ -0,0 +1,64 @@
# Set this to the name of your sketch (without extension .pde)
SKETCH=sketch
EXE=arduino-example
all: $(EXE)
CONTIKI=../../..
# Contiki IPv6 configuration
CONTIKI_WITH_IPV6 = 1
CFLAGS += -DPROJECT_CONF_H=\"project-conf.h\"
LFLAGS += -lm
PROJECT_SOURCEFILES += ${SKETCH}.cpp Servo.cpp
# automatically build RESTful resources
REST_RESOURCES_DIR = ./resources
REST_RESOURCES_DIR_COMMON = ../resources-common
REST_RESOURCES_FILES= $(notdir \
$(shell find $(REST_RESOURCES_DIR) -name '*.c') \
$(shell find $(REST_RESOURCES_DIR_COMMON) -name '*.c') \
)
PROJECTDIRS += $(REST_RESOURCES_DIR) $(REST_RESOURCES_DIR_COMMON)
PROJECT_SOURCEFILES += $(REST_RESOURCES_FILES)
# variable for Makefile.include
ifneq ($(TARGET), minimal-net)
CFLAGS += -DUIP_CONF_IPV6_RPL=1
else
# minimal-net does not support RPL under Linux and is mostly used to test CoAP only
${info INFO: compiling without RPL}
CFLAGS += -DUIP_CONF_IPV6_RPL=0
CFLAGS += -DHARD_CODED_ADDRESS=\"fdfd::10\"
${info INFO: compiling with large buffers}
CFLAGS += -DUIP_CONF_BUFFER_SIZE=2048
CFLAGS += -DREST_MAX_CHUNK_SIZE=1024
CFLAGS += -DCOAP_MAX_HEADER_SIZE=640
endif
# linker optimizations
SMALL=1
# REST Engine shall use Erbium CoAP implementation
APPS += er-coap
APPS += rest-engine
APPS += arduino
include $(CONTIKI)/Makefile.include
include $(CONTIKI)/apps/arduino/Makefile.include
$(CONTIKI)/tools/tunslip6: $(CONTIKI)/tools/tunslip6.c
(cd $(CONTIKI)/tools && $(MAKE) tunslip6)
connect-router: $(CONTIKI)/tools/tunslip6
sudo $(CONTIKI)/tools/tunslip6 aaaa::1/64
connect-router-cooja: $(CONTIKI)/tools/tunslip6
sudo $(CONTIKI)/tools/tunslip6 -a 127.0.0.1 aaaa::1/64
connect-minimal:
sudo ip address add fdfd::1/64 dev tap0

View file

@ -0,0 +1,13 @@
Arduino compatibility example
=============================
make clean TARGET=osd-merkur-256 flash
This example shows that it is now possible to re-use arduino sketches in
Contiki. This example documents the necessary magic. Arduino specifies
two routines, `setup` and `loop`. Before `setup` is called, the
framework initializes hardware. In original Arduino, all this is done in
a `main` function (in C). For contiki we define a process that does the
same.
See the documentation file in apps/contiki-compat/README.md

View file

@ -0,0 +1,17 @@
Arduino Servo example
=============================
work in progress !!!
Not compile yet !!
make clean TARGET=osd-merkur-256 flash
This example shows that it is now possible to re-use arduino sketches in
Contiki. This example documents the necessary magic. Arduino specifies
two routines, `setup` and `loop`. Before `setup` is called, the
framework initializes hardware. In original Arduino, all this is done in
a `main` function (in C). For contiki we define a process that does the
same.
See the documentation file in apps/contiki-compat/README.md

View file

@ -0,0 +1,319 @@
/*
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined(ARDUINO_ARCH_AVR)
#include <avr/interrupt.h>
extern "C" {
#include "Arduino.h"
}
#include "Servo.h"
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009
//#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER)
static servo_t servos[MAX_SERVOS]; // static array of servo structures
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
uint8_t ServoCount = 0; // the total number of attached servos
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
/************ static functions common to all instances ***********************/
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA)
{
if( Channel[timer] < 0 )
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
else{
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true )
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
}
Channel[timer]++; // increment to the next channel
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
}
else {
// finished all channels so wait for the refresh period to expire before starting over
if( ((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL) ) // allow a few ticks to ensure the next OCR1A not missed
*OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL);
else
*OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
}
#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform
// Interrupt handlers for Arduino
#if defined(_useTimer1)
SIGNAL (TIMER1_COMPA_vect)
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif
#if defined(_useTimer3)
SIGNAL (TIMER3_COMPA_vect)
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif
#if defined(_useTimer4)
SIGNAL (TIMER4_COMPA_vect)
{
handle_interrupts(_timer4, &TCNT4, &OCR4A);
}
#endif
#if defined(_useTimer5)
SIGNAL (TIMER5_COMPA_vect)
{
handle_interrupts(_timer5, &TCNT5, &OCR5A);
}
#endif
#elif defined WIRING
// Interrupt handlers for Wiring
#if defined(_useTimer1)
void Timer1Service()
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif
#if defined(_useTimer3)
void Timer3Service()
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif
#endif
static void initISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1)
if(timer == _timer1) {
TCCR1A = 0; // normal counting mode
TCCR1B = _BV(CS11); // set prescaler of 8
TCNT1 = 0; // clear the timer count
#if defined(__AVR_ATmega8__)|| defined(__AVR_ATmega128__)
TIFR |= _BV(OCF1A); // clear any pending interrupts;
TIMSK |= _BV(OCIE1A) ; // enable the output compare interrupt
#else
// here if not ATmega8 or ATmega128
TIFR1 |= _BV(OCF1A); // clear any pending interrupts;
TIMSK1 |= _BV(OCIE1A) ; // enable the output compare interrupt
#endif
#if defined(WIRING)
timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service);
#endif
}
#endif
#if defined (_useTimer3)
if(timer == _timer3) {
TCCR3A = 0; // normal counting mode
TCCR3B = _BV(CS31); // set prescaler of 8
TCNT3 = 0; // clear the timer count
#if defined(__AVR_ATmega128__)
TIFR |= _BV(OCF3A); // clear any pending interrupts;
ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt
#else
TIFR3 = _BV(OCF3A); // clear any pending interrupts;
TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt
#endif
#if defined(WIRING)
timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only
#endif
}
#endif
#if defined (_useTimer4)
if(timer == _timer4) {
TCCR4A = 0; // normal counting mode
TCCR4B = _BV(CS41); // set prescaler of 8
TCNT4 = 0; // clear the timer count
TIFR4 = _BV(OCF4A); // clear any pending interrupts;
TIMSK4 = _BV(OCIE4A) ; // enable the output compare interrupt
}
#endif
#if defined (_useTimer5)
if(timer == _timer5) {
TCCR5A = 0; // normal counting mode
TCCR5B = _BV(CS51); // set prescaler of 8
TCNT5 = 0; // clear the timer count
TIFR5 = _BV(OCF5A); // clear any pending interrupts;
TIMSK5 = _BV(OCIE5A) ; // enable the output compare interrupt
}
#endif
}
static void finISR(timer16_Sequence_t timer)
{
//disable use of the given timer
#if defined WIRING // Wiring
if(timer == _timer1) {
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
#else
TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
#endif
timerDetach(TIMER1OUTCOMPAREA_INT);
}
else if(timer == _timer3) {
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
#else
ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
#endif
timerDetach(TIMER3OUTCOMPAREA_INT);
}
#else
//For arduino - in future: call here to a currently undefined function to reset the timer
#endif
}
static boolean isTimerActive(timer16_Sequence_t timer)
{
// returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if(SERVO(timer,channel).Pin.isActive == true)
return true;
}
return false;
}
/****************** end of static functions ******************************/
Servo::Servo(void)
{
if( ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
}
else
this->servoIndex = INVALID_SERVO ; // too many servos
}
uint8_t Servo::attach(int pin)
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t Servo::attach(int pin, int min, int max)
{
if(this->servoIndex < MAX_SERVOS ) {
pinMode( pin, OUTPUT) ; // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
this->max = (MAX_PULSE_WIDTH - max)/4;
// initialize the timer if it has not already been initialized
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false)
initISR(timer);
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
}
return this->servoIndex ;
}
void Servo::detach()
{
servos[this->servoIndex].Pin.isActive = false;
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) {
finISR(timer);
}
}
void Servo::write(int value)
{
if(value < MIN_PULSE_WIDTH)
{ // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
if(value < 0) value = 0;
if(value > 180) value = 180;
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
}
this->writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
// calculate and store the values for the given channel
byte channel = this->servoIndex;
if( (channel < MAX_SERVOS) ) // ensure channel is valid
{
if( value < SERVO_MIN() ) // ensure pulse width is valid
value = SERVO_MIN();
else if( value > SERVO_MAX() )
value = SERVO_MAX();
value = value - TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
uint8_t oldSREG = SREG;
cli();
servos[channel].ticks = value;
SREG = oldSREG;
}
}
int Servo::read() // return the value as degrees
{
return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
}
int Servo::readMicroseconds()
{
unsigned int pulsewidth;
if( this->servoIndex != INVALID_SERVO )
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009
else
pulsewidth = 0;
return pulsewidth;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive ;
}
#endif // ARDUINO_ARCH_AVR

View file

@ -0,0 +1,112 @@
/*
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
A servo is activated by creating an instance of the Servo class passing
the desired pin to the attach() method.
The servos are pulsed in the background using the value most recently
written using the write() method.
Note that analogWrite of PWM on pins associated with the timer are
disabled when the first servo is attached.
Timers are seized as needed in groups of 12 servos - 24 servos use two
timers, 48 servos will use four.
The sequence used to sieze timers is defined in timers.h
The methods are:
Servo - Class for manipulating servo motors connected to Arduino pins.
attach(pin ) - Attaches a servo motor to an i/o pin.
attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds
default min is 544, max is 2400
write() - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds)
writeMicroseconds() - Sets the servo pulse width in microseconds
read() - Gets the last written servo pulse width as an angle between 0 and 180.
readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
attached() - Returns true if there is a servo attached.
detach() - Stops an attached servos from pulsing its i/o pin.
*/
#ifndef Servo_h
#define Servo_h
#include <inttypes.h>
#define ARDUINO_ARCH_AVR
/*
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available.
*/
// Architecture specific include
#if defined(ARDUINO_ARCH_AVR)
#include "ServoTimers.h"
#elif defined(ARDUINO_ARCH_SAM)
#include "sam/ServoTimers.h"
#elif defined(ARDUINO_ARCH_SAMD)
#include "samd/ServoTimers.h"
#else
#error "This library only supports boards with an AVR, SAM or SAMD processor."
#endif
#define Servo_VERSION 2 // software version of this library
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
#define REFRESH_INTERVAL 20000 // minumim time to refresh servos in microseconds
#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer
#define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER)
#define INVALID_SERVO 255 // flag indicating an invalid servo index
typedef struct {
uint8_t nbr :6 ; // a pin number from 0 to 63
uint8_t isActive :1 ; // true if this channel is enabled, pin not pulsed if false
} ServoPin_t ;
typedef struct {
ServoPin_t Pin;
volatile unsigned int ticks;
} servo_t;
class Servo
{
public:
Servo(void);
uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure
uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes.
void detach();
void write(int value); // if value is < 200 its treated as an angle, otherwise as pulse width in microseconds
void writeMicroseconds(int value); // Write pulse width in microseconds
int read(); // returns current pulse width as an angle between 0 and 180 degrees
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
bool attached(); // return true if this servo is attached, otherwise false
private:
uint8_t servoIndex; // index into the channel data for this servo
int8_t min; // minimum is this value times 4 added to MIN_PULSE_WIDTH
int8_t max; // maximum is this value times 4 added to MAX_PULSE_WIDTH
};
#endif

View file

@ -0,0 +1,59 @@
/*
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available.
*/
/**
* AVR Only definitions
* --------------------
*/
// Say which 16 bit timers can be used and in what order
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define _useTimer5
#define _useTimer1
#define _useTimer3
#define _useTimer4
typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_ATmega32U4__)
#define _useTimer1
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_ATmega128__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega2561__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t;
#else // everything else
#define _useTimer1
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#endif

View file

@ -0,0 +1,2 @@
#include <arduino-process.h>
AUTOSTART_PROCESSES(&arduino_sketch);

View file

@ -0,0 +1,53 @@
[file_prefs]
final_new_line=true
ensure_convert_new_lines=false
strip_trailing_spaces=false
replace_tabs=false
[indentation]
indent_width=4
indent_type=1
indent_hard_tab_width=8
detect_indent=false
detect_indent_width=false
indent_mode=2
[project]
name=arduino-servo
base_path=/home/harald/install/osd-contiki/examples/osd/arduino-servo/
description=
file_patterns=
[long line marker]
long_line_behaviour=1
long_line_column=72
[files]
current_page=0
FILE_NAME_0=893;C++;0;EUTF-8;1;1;0;%2Fhome%2Fharald%2Finstall%2Fosd-contiki%2Fexamples%2Fosd%2Farduino-servo%2Fsketch.pde;0;4
[VTE]
last_dir=/home/harald
[build-menu]
NF_00_LB=_Make
NF_00_CM=make TARGET=osd-merkur-256
NF_00_WD=
NF_01_LB=Make flash
NF_01_CM=make TARGET=osd-merkur-256 flash
NF_01_WD=
NF_03_LB=Make Clean
NF_03_CM=make clean TARGET=osd-merkur-256
NF_03_WD=
C++FT_00_LB=_Kompilieren
C++FT_00_CM=make TARGET=osd-merkur-256
C++FT_00_WD=
C++FT_01_LB=_Erstellen
C++FT_01_CM=make TARGET=osd-merkur-256 flash
C++FT_01_WD=
filetypes=C++;
[editor]
line_wrapping=false
line_break_column=72
auto_continue_multiline=true

View file

@ -0,0 +1,2 @@
#!/bin/bash
make TARGET=osd-merkur-128 flash

View file

@ -0,0 +1,105 @@
/*
* Copyright (c) 2010, Swedish Institute of Computer Science.
* All rights reserved.
*
* 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 PROJECT_RPL_WEB_CONF_H_
#define PROJECT_RPL_WEB_CONF_H_
#define PLATFORM_HAS_LEDS 1
//#define PLATFORM_HAS_BUTTON 1
#define PLATFORM_HAS_BATTERY 1
#define LOOP_INTERVAL (30 * CLOCK_SECOND)
/* Save energy */
//#define RDC_CONF_PT_YIELD_OFF
/* For Debug: Dont allow MCU sleeping between channel checks */
#undef RDC_CONF_MCU_SLEEP
#define RDC_CONF_MCU_SLEEP 0
/* Disabling RDC for demo purposes. Core updates often require more memory. */
/* For projects, optimize memory and enable RDC again. */
//#undef NETSTACK_CONF_RDC
//#define NETSTACK_CONF_RDC nullrdc_driver
//#undef NETSTACK_CONF_MAC
//#define NETSTACK_CONF_MAC nullmac_driver
/* Increase rpl-border-router IP-buffer when using more than 64. */
//#undef REST_MAX_CHUNK_SIZE
//#define REST_MAX_CHUNK_SIZE 64
/* Estimate your header size, especially when using Proxy-Uri. */
/*
#undef COAP_MAX_HEADER_SIZE
#define COAP_MAX_HEADER_SIZE 70
*/
/* The IP buffer size must fit all other hops, in particular the border router. */
#undef UIP_CONF_BUFFER_SIZE
#define UIP_CONF_BUFFER_SIZE 256
/* Multiplies with chunk size, be aware of memory constraints. */
#undef COAP_MAX_OPEN_TRANSACTIONS
#define COAP_MAX_OPEN_TRANSACTIONS 4
/* Must be <= open transaction number, default is COAP_MAX_OPEN_TRANSACTIONS-1. */
/*
#undef COAP_MAX_OBSERVERS
#define COAP_MAX_OBSERVERS 2
*/
/* Filtering .well-known/core per query can be disabled to save space. */
/*
#undef COAP_LINK_FORMAT_FILTERING
#define COAP_LINK_FORMAT_FILTERING 0
*/
/*
#undef LLSEC802154_CONF_ENABLED
#define LLSEC802154_CONF_ENABLED 1
#undef NETSTACK_CONF_FRAMER
#define NETSTACK_CONF_FRAMER noncoresec_framer
#undef NETSTACK_CONF_LLSEC
#define NETSTACK_CONF_LLSEC noncoresec_driver
#undef NONCORESEC_CONF_SEC_LVL
#define NONCORESEC_CONF_SEC_LVL 1
#define NONCORESEC_CONF_KEY { 0x00 , 0x01 , 0x02 , 0x03 , \
0x04 , 0x05 , 0x06 , 0x07 , \
0x08 , 0x09 , 0x0A , 0x0B , \
0x0C , 0x0D , 0x0E , 0x0F }
*/
#endif /* PROJECT_RPL_WEB_CONF_H_ */

View file

@ -0,0 +1,104 @@
/*
* Copyright (c) 2013, Institute for Pervasive Computing, ETH Zurich
* All rights reserved.
*
* 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*/
/**
* \file
* Door resource
* \author
* Harald Pichler <harald@the-develop.net>
*/
#include "contiki.h"
#include <string.h>
#include "rest-engine.h"
#include "Arduino.h"
static void res_get_handler(void *request, void *response, uint8_t *buffer, uint16_t preferred_size, int32_t *offset);
static void res_post_put_handler(void *request, void *response, uint8_t *buffer, uint16_t preferred_size, int32_t *offset);
/* A simple getter example. Returns the reading from the sensor with a simple etag */
RESOURCE(res_led,
"title=\"LED: , POST/PUT mode=on|off\";rt=\"Control\"",
res_get_handler,
res_post_put_handler,
res_post_put_handler,
NULL);
extern uint8_t led_pin;
extern uint8_t led_status;
static void
res_get_handler(void *request, void *response, uint8_t *buffer, uint16_t preferred_size, int32_t *offset)
{
unsigned int accept = -1;
REST.get_header_accept(request, &accept);
if(accept == -1 || accept == REST.type.TEXT_PLAIN) {
REST.set_header_content_type(response, REST.type.TEXT_PLAIN);
snprintf((char *)buffer, REST_MAX_CHUNK_SIZE, "%d", led_status);
REST.set_response_payload(response, buffer, strlen((char *)buffer));
} else if(accept == REST.type.APPLICATION_JSON) {
REST.set_header_content_type(response, REST.type.APPLICATION_JSON);
snprintf((char *)buffer, REST_MAX_CHUNK_SIZE, "{'led':%d}", led_status);
REST.set_response_payload(response, buffer, strlen((char *)buffer));
} else {
REST.set_response_status(response, REST.status.NOT_ACCEPTABLE);
const char *msg = "Supporting content-types text/plain and application/json";
REST.set_response_payload(response, msg, strlen(msg));
}
}
static void
res_post_put_handler(void *request, void *response, uint8_t *buffer, uint16_t preferred_size, int32_t *offset)
{
size_t len = 0;
const char *mode = NULL;
int success = 1;
if(success && (len = REST.get_post_variable(request, "mode", &mode))) {
if(strncmp(mode, "on", len) == 0) {
digitalWrite(led_pin, LOW);
led_status=1;
} else if(strncmp(mode, "off", len) == 0) {
digitalWrite(led_pin, HIGH);
led_status=0;
} else {
success = 0;
}
} else {
success = 0;
} if(!success) {
REST.set_response_status(response, REST.status.BAD_REQUEST);
}
}

View file

@ -0,0 +1,5 @@
#!/bin/bash
# For the ages-old bootloader (before 2014) you want to use
# BOOTLOADER_GET_MAC=0x0001f3a0 as parameter to make below.
make clean TARGET=osd-merkur-128
make TARGET=osd-merkur-128

View file

@ -0,0 +1,59 @@
/*
* Sample arduino sketch using contiki features.
* We turn the LED off
* We allow read the moisture sensor
* Unfortunately sleeping for long times in loop() isn't currently
* possible, something turns off the CPU (including PWM outputs) if a
* Proto-Thread is taking too long. We need to find out how to sleep in
* a Contiki-compatible way.
* Note that for a normal arduino sketch you won't have to include any
* of the contiki-specific files here, the sketch should just work.
*/
extern "C" {
#include "arduino-process.h"
#include "rest-engine.h"
#include "net/netstack.h"
#include "Servo.h"
extern resource_t res_led, res_battery, res_cputemp;
uint8_t led_pin=4;
uint8_t led_status;
int potpin = A5; // analog pin used to connect the potentiometer
int val; // variable to read the value from the analog pin
Servo servo(); // create servo object to control a servo
}
void setup (void)
{
// switch off the led
pinMode(led_pin, OUTPUT);
digitalWrite(led_pin, HIGH);
led_status=0;
// Servo
servo.attach(3); // attaches the servo on pin 9 to the servo object
// init coap resourcen
rest_init_engine ();
#pragma GCC diagnostic ignored "-Wwrite-strings"
rest_activate_resource (&res_led, "s/led");
rest_activate_resource (&res_battery, "s/battery");
rest_activate_resource (&res_cputemp, "s/cputemp");
#pragma GCC diagnostic pop
// NETSTACK_MAC.off(1);
mcu_sleep_set(128);
}
void loop (void)
{
val = analogRead(potpin); // reads the value of the potentiometer (value between 0 and 1023)
val = map(val, 0, 1023, 0, 180); // scale it to use it with the servo (value between 0 and 180)
servo.write(val); // sets the servo position according to the scaled value
}