firebug-cvs Mailing List for FireBug: wireless wildfire monitoring (Page 31)
Brought to you by:
doolin
You can subscribe to this list here.
2003 |
Jan
|
Feb
|
Mar
|
Apr
|
May
(36) |
Jun
(45) |
Jul
(108) |
Aug
(31) |
Sep
(2) |
Oct
(4) |
Nov
(113) |
Dec
(20) |
---|---|---|---|---|---|---|---|---|---|---|---|---|
2004 |
Jan
(63) |
Feb
(37) |
Mar
(24) |
Apr
(6) |
May
(5) |
Jun
(5) |
Jul
(71) |
Aug
(42) |
Sep
(7) |
Oct
|
Nov
|
Dec
|
2005 |
Jan
|
Feb
|
Mar
(3) |
Apr
|
May
(64) |
Jun
(71) |
Jul
(51) |
Aug
(89) |
Sep
(24) |
Oct
(1) |
Nov
(1) |
Dec
(2) |
2006 |
Jan
|
Feb
|
Mar
(3) |
Apr
(2) |
May
|
Jun
|
Jul
(21) |
Aug
|
Sep
|
Oct
|
Nov
|
Dec
|
2007 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
(1) |
From: <cs...@us...> - 2003-08-01 19:25:23
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv1126 Added Files: hpluartc1.nc i2cc.nc jnk.nc Log Message: files for new Leadtek --- NEW FILE: hpluartc1.nc --- /* tab:4 * * * "Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * * Permission to use, copy, modify, and distribute this software and its * documentation for any purpose, without fee, and without written agreement is * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY * AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS * ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION TO * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS." * */ /* tab:4 * IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. By * downloading, copying, installing or using the software you agree to * this license. If you do not agree to this license, do not download, * install, copy or use the software. * * Intel Open Source License * * Copyright (c) 2002 Intel Corporation * All rights reserved. * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are * met: * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 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. * Neither the name of the Intel Corporation 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 INTEL OR ITS * 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. * * */ /* * * Authors: Jason Hill, David Gay, Philip Levis * Date last modified: 6/25/02 * */ // The hardware presentation layer. See hpl.h for the C side. // Note: there's a separate C side (hpl.h) to get access to the avr macros // The model is that HPL is stateless. If the desired interface is as stateless // it can be implemented here (Clock, FlashBitSPI). Otherwise you should // create a separate component configuration HPLUARTC1 { provides interface HPLUART as UART; } implementation { components HPLUART1M as HPLUART0M, HPLInterrupt; UART = HPLUART0M; HPLUART0M.Interrupt -> HPLInterrupt; } --- NEW FILE: i2cc.nc --- /* tab:4 * * * "Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * * Permission to use, copy, modify, and distribute this software and its * documentation for any purpose, without fee, and without written agreement is * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY * AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS * ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION TO * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS." * */ /* * * Authors: Phil Buonadonna, Joe Polastre, Rob Szewczyk * Date last modified: 12/19/02 * * Note: Modify this configuration file to choose between software or hardware * based I2C. */ /* Uncomment line below to enable Hardware based I2C on the mica128 */ #define HARDWARE_I2C configuration I2CC { provides { interface StdControl; interface I2C; } } implementation { #ifdef HARDWARE_I2C components HPLI2CM, HPLInterrupt; StdControl = HPLI2CM; I2C = HPLI2CM; HPLI2CM.Interrupt->HPLInterrupt; #else components I2CM; StdControl = I2CM; I2C = I2CM; #endif } --- NEW FILE: jnk.nc --- interface jnk { command result_t GpsPower(uint8_t PowerState); /* 0 => gps power off; 1 => gps power on */ } |
From: <cs...@us...> - 2003-08-01 19:09:35
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv1569 Added Files: gpspacket.nc Log Message: files for new Leadtek --- NEW FILE: gpspacket.nc --- /* tab:4 * * * "Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * * Permission to use, copy, modify, and distribute this software and its * documentation for any purpose, without fee, and without written agreement is * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY * AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS * ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION TO * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS." * */ /* tab:4 * IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. By * downloading, copying, installing or using the software you agree to * this license. If you do not agree to this license, do not download, * install, copy or use the software. * * Intel Open Source License * * Copyright (c) 2002 Intel Corporation * All rights reserved. * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are * met: * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 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. * Neither the name of the Intel Corporation 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 INTEL OR ITS * 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. * * */ /* * * Authors: * Date last modified: 6/25/02 * */ /* This component handles the gps control and packet abstraction */ includes sensorboard; includes gps; module GpsPacket { provides { interface StdControl as Control; interface BareSendMsg as Send; interface ReceiveMsg as Receive; interface SendVarLenPacket; interface GpsCmd; command result_t txBytes(uint8_t *bytes, uint8_t numBytes); /* Effects: start sending 'numBytes' bytes from 'bytes' */ // command result_t GpsPower(uint8_t PowerState); // /* 0 => gps power off; 1 => gps power on */ } uses { interface ByteComm; interface StdControl as ByteControl; interface Leds; interface StdControl as SwitchControl; interface Switch as Switch1; interface Switch as SwitchI2W; } } implementation { GPS_Msg buffer; //GPS_Msg* bufferPtr; TOS_MsgPtr bufferPtr; //really a GPS_Msg pointer enum {GPS_SWITCH_IDLE, //GPS I2C switches are not using the I2C bus GPS_PWR_SWITCH_WAIT, //Waiting for GPS I2C power switch to set GPS_EN_SWITCH_WAIT, //Waiting for GPS I2C enable switch to set GPS_TX_SWITCH_WAIT, //Waiting for GPS I2C tx switch to set GPS_RX_SWITCH_WAIT, //Waiting for GPS I2C rx switch to set BUSY, BUSY_0, BUSY_1, GET_SAMPLE_0, GET_SAMPLE_1, OPENSCK, OPENDATA, CLOSESCK, CLOSEDATA, POWEROFF, MAIN_SWITCH_ON, MAIN_SWITCH_OFF, WAIT_SWITCH_ON, WAIT_SWITCH_OFF, TIMER}; uint8_t state_gps; //state of I2C switches uint8_t power_gps; //gps on off uint16_t rxCount, rxLength, txCount, txLength; // TOS_Msg buffers[2]; // TOS_Msg* bufferPtrs[2]; uint8_t bufferIndex; uint8_t *recPtr; uint8_t *sendPtr; enum { IDLE, PACKET, BYTES }; uint8_t state; /* state == IDLE, nothing is being sent state == PACKET, this level is sending a packet state == BYTES, this level is just transferring bytes The purpose of adding the new state, to simply transfer bytes, is because certain applications may want to just send a sequence of bytes without the packet abstraction. One such example is the UART. */ /* Initialization of this component */ command result_t Control.init() { recPtr = (uint8_t *)&buffer; bufferIndex = 0; (GPS_Msg*) bufferPtr = &buffer; // bufferPtrs[1] = &buffers[1]; state_gps = GPS_SWITCH_IDLE; state = IDLE; txCount = rxCount = 0; // make sure we always read up to the type (which determines length) rxLength = GPS_DATA_LENGTH + 2; dbg(DBG_BOOT, "Packet handler initialized.\n"); return call ByteControl.init(); } /* Command to control the power of the network stack */ command result_t Control.start() { // apply your power management algorithm return call ByteControl.start(); call SwitchControl.start(); } /* Command to control the power of the network stack */ command result_t Control.stop() { // apply your power management algorithm return call ByteControl.stop(); } command result_t txBytes(uint8_t *bytes, uint8_t numBytes) { if (txCount == 0) { txCount = 1; txLength = numBytes; sendPtr = bytes; /* send the first byte */ if (call ByteComm.txByte(sendPtr[0])) return SUCCESS; else txCount = 0; } return FAIL; } /* Command to transmit a packet */ command result_t Send.send(TOS_MsgPtr msg) { state = PACKET; msg->crc = 1; /* Fake out the CRC as passed. */ return call txBytes((uint8_t *)msg, TOS_MsgLength(msg->type)); } /* Command to transfer a variable length packet */ command result_t SendVarLenPacket.send(uint8_t* packet, uint8_t numBytes) { state = BYTES; return call txBytes(packet, numBytes); } task void sendDoneFailTask() { txCount = 0; state = IDLE; signal Send.sendDone((TOS_MsgPtr)sendPtr, FAIL); } task void sendDoneSuccessTask() { txCount = 0; state = IDLE; signal Send.sendDone((TOS_MsgPtr)sendPtr, SUCCESS); } task void sendVarLenFailTask() { txCount = 0; state = IDLE; signal SendVarLenPacket.sendDone((uint8_t*)sendPtr, FAIL); } task void sendVarLenSuccessTask() { txCount = 0; state = IDLE; signal SendVarLenPacket.sendDone((uint8_t*)sendPtr, SUCCESS); } void sendComplete(result_t success) { if (state == PACKET) { TOS_MsgPtr msg = (TOS_MsgPtr)sendPtr; /* This is a non-ack based layer */ if (success) { msg->ack = TRUE; post sendDoneSuccessTask(); } else { post sendDoneFailTask(); } } else if (state == BYTES) { if (success) { post sendVarLenSuccessTask(); } else { post sendVarLenFailTask(); } } else { txCount = 0; state = IDLE; } } default event result_t SendVarLenPacket.sendDone(uint8_t* packet, result_t success) { return success; } default event result_t Send.sendDone(TOS_MsgPtr msg, result_t success){ return success; } /* Byte level component signals it is ready to accept the next byte. Send the next byte if there are data pending to be sent */ event result_t ByteComm.txByteReady(bool success) { if (txCount > 0) { if (!success) { dbg(DBG_ERROR, "TX_packet failed, TX_byte_failed"); sendComplete(FAIL); } else if (txCount < txLength) { dbg(DBG_PACKET, "PACKET: byte sent: %x, COUNT: %d\n", sendPtr[txCount], txCount); if (!call ByteComm.txByte(sendPtr[txCount++])) sendComplete(FAIL); } } return SUCCESS; } event result_t ByteComm.txDone() { if (txCount == txLength) sendComplete(TRUE); return SUCCESS; } /////////////////////////////////////////////////////////////////////////// // need to hold off getting more gps bytes until buffer released!!!!! ////////////////////////////////////////////////////////////////////////// task void receiveTask() { // TOS_MsgPtr tmp = signal Receive.receive(bufferPtrs[bufferIndex ^ 1]); // if (tmp) { // bufferPtrs[bufferIndex ^ 1] = tmp; TOS_Msg* tmp = signal Receive.receive(bufferPtr); // } } /****************************************************************************** * Modify this routine for the GPS *****************************************************************************/ /* The handles the latest decoded byte propagated by the Byte Level component*/ event result_t ByteComm.rxByteReady(uint8_t data, bool error, uint16_t strength) { dbg(DBG_PACKET, "PACKET: byte arrived: %x, COUNT: %d\n", data, rxCount); if (error) { rxCount = 0; return FAIL; } recPtr[rxCount++] = data; if (rxCount == rxLength){ bufferIndex = bufferIndex ^ 1; // recPtr = (uint8_t*)bufferPtrs[bufferIndex]; recPtr = (uint8_t*)bufferPtr; dbg(DBG_PACKET, "got packet\n"); rxCount = 0; post receiveTask(); return FAIL; } return SUCCESS; } /****************************************************************************** * Turn Gps on/off * PowerState = 0 then GPS power off, GPS enable off, tx and rx disabled * = 1 then GPS power on, GPS enable on, tx and rx enabled * NOTE - rx,tx share pressure lines. * - GPS switching power supply is enabled by a lo, disabled by a hi *****************************************************************************/ command result_t GpsCmd.GpsPower(uint8_t PowerState){ if (state_gps == GPS_SWITCH_IDLE){ power_gps = PowerState; if (power_gps){ if (call Switch1.set(MICAWB_GPS_POWER,0) == SUCCESS) state_gps = GPS_PWR_SWITCH_WAIT; } else{ if (call Switch1.set(MICAWB_GPS_POWER,1) == SUCCESS) state_gps = GPS_PWR_SWITCH_WAIT; } return SUCCESS; } return FAIL; } event result_t Switch1.getDone(char value) { return SUCCESS; } event result_t Switch1.setDone(bool local_result) { if (state_gps == GPS_PWR_SWITCH_WAIT) { if (call Switch1.set(MICAWB_GPS_ENABLE ,power_gps) == SUCCESS) { state_gps = GPS_EN_SWITCH_WAIT; } } else if (state_gps == GPS_EN_SWITCH_WAIT) { if (call SwitchI2W.set( MICAWB_GPS_TX_SELECT ,power_gps) == SUCCESS) { state_gps = GPS_TX_SWITCH_WAIT; } } return SUCCESS; } event result_t SwitchI2W.setAllDone(bool local_result) { return SUCCESS; } event result_t Switch1.setAllDone(bool local_result) { return SUCCESS; } event result_t SwitchI2W.getDone(char value) { return SUCCESS; } event result_t SwitchI2W.setDone(bool local_result) { if (state_gps == GPS_TX_SWITCH_WAIT) { if (call SwitchI2W.set( MICAWB_GPS_RX_SELECT ,power_gps) == SUCCESS) { state_gps = GPS_RX_SWITCH_WAIT; } } else if (state_gps == GPS_RX_SWITCH_WAIT) { state_gps = GPS_SWITCH_IDLE; } return SUCCESS; } // else if (state == OPENSCK) { // state = OPENDATA; // return call SwitchI2W.set(MICAWB_HUMIDITY_DATA,1); // } else if (state == OPENDATA) { // state = TIMER; // return call Timer.start(TIMER_ONE_SHOT, 100); // } else if (state == CLOSESCK) { // state = CLOSEDATA; // return call SwitchI2W.set(MICAWB_HUMIDITY_DATA,0); // } else if (state == CLOSEDATA) { // uint16_t l_result = result; // state = GPS_SWITCH_IDLE; // if (id == MICAWB_HUMIDITY) // signal Humidity.dataReady(l_result); // else if (id == MICAWB_HUMIDITY_TEMP) // signal Temperature.dataReady(l_result); // } // return SUCCESS; // } } |
From: <cs...@us...> - 2003-08-01 18:22:19
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv1367 Added Files: gpspacket_0.nc hpli2cm.nc hpluart1m.nc Log Message: files for new Leadtek --- NEW FILE: gpspacket_0.nc --- /* tab:4 * * * "Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * * Permission to use, copy, modify, and distribute this software and its * documentation for any purpose, without fee, and without written agreement is * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY * AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS * ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION TO * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS." * */ /* tab:4 * IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. By * downloading, copying, installing or using the software you agree to * this license. If you do not agree to this license, do not download, * install, copy or use the software. * * Intel Open Source License * * Copyright (c) 2002 Intel Corporation * All rights reserved. * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are * met: * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 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. * Neither the name of the Intel Corporation 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 INTEL OR ITS * 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. * * */ /* * * Authors: * Date last modified: 6/25/02 * */ configuration GpsC { provides { interface StdControl as Control; interface BareSendMsg as Send; interface ReceiveMsg as Receive; interface SendVarLenPacket; } } implementation { components GpsPacketM ; TestMTS350M.GpsControl -> UARTGpsPacket; TestMTS350M.GpsSend -> UARTGpsPacket; TestMTS350M.GpsReceive -> UARTGpsPacket; StdControl = GpsPacketM; Humidity = SensirionHumidityM.Humidity; Temperature = SensirionHumidityM.Temperature; SensirionHumidityM.Timer -> TimerC.Timer[unique("Timer")]; SensirionHumidityM.SensorControl -> TempHum.StdControl; SensirionHumidityM.HumSensor -> TempHum.HumSensor; SensirionHumidityM.TempSensor -> TempHum.TempSensor; SensirionHumidityM.SwitchControl -> MicaWbSwitch.StdControl; SensirionHumidityM.Switch1 -> MicaWbSwitch.Switch[0]; SensirionHumidityM.SwitchI2W -> MicaWbSwitch.Switch[1]; } --- NEW FILE: hpli2cm.nc --- //Mohammad Rahimi,Phil Buonadonna module HPLI2CM { provides { interface StdControl; interface I2C; } uses interface Interrupt; uses interface Leds; } implementation { // global variables char state; // maintain the state of the current processx char global_data; #define SET_START_TX() sbi(TWCR,TWSTA) #define CLEAR_START_TX() cbi(TWCR,TWSTA) #define SET_STOP_TX() sbi(TWCR,TWSTO) #define CLEAR_STOP_TX() cbi(TWCR,TWSTO) #define I2C_ENABLE() sbi(TWCR,TWEN) #define I2C_DISABLE() cbi(TWCR,TWEN) #define INT_ENABLE() sbi(TWCR,TWIE) #define INT_DISABLE() cbi(TWCR,TWIE) #define INT_FLAG_ENABLE() sbi(TWCR,TWINT) #define INT_FLAG_DISABLE() cbi(TWCR,TWINT) #define ACK_ENABLE() sbi(TWCR,TWEA) #define NACK_ENABLE() cbi(TWCR,TWEA) #define RESET() outp(0x0,TWCR); #define MAKE_CLOCK_OUTPUT() sbi(DDRD, 0); #define CLOCK_HIGH() sbi(PORTD,0); #define CLCOK_LOW() sbi(PORTD,0); #define MAKE_DATA_INPUT() cbi(DDRD, 1); #define DATA_PULL_UP() sbi(PORTD, 1); #define DATA_NO_PULL_UP() cbi(PORTD, 1); // define constants for state enum { IDLE = 1, // idle MA_START, // Initiation of the Master Bus MA_ADDRESS, // Master Transmitter,writing address MA_DATA, // Master Transmitter,writing data MR_DATA, // Master Receiver ST, // Slave Transmitter SR // Slave Receiver }; // define TWI device status codes. enum { TWS_BUSERROR = 0x00, TWS_START = 0x08, TWS_RSTART = 0x10, TWS_MT_SLA_ACK = 0x18, TWS_MT_SLA_NACK = 0x20, TWS_MT_DATA_ACK = 0x28, TWS_MT_DATA_NACK = 0x30, TWS_M_ARB_LOST = 0x38, TWS_MR_SLA_ACK = 0x40, TWS_MR_SLA_NACK = 0x48, TWS_MR_DATA_ACK = 0x50, TWS_MR_DATA_NACK = 0x58 }; static inline void setBitRate() // See Note, Page 205 of ATmega128 docs { cbi(TWSR, TWPS0); cbi(TWSR, TWPS1); outp(100,TWBR); } static inline void init() { //sbi(PORTD, 0); // i2c SCL,this activate pullup resistor //sbi(PORTD, 1); // i2c SDA,this activate pullup resistor MAKE_CLOCK_OUTPUT(); MAKE_DATA_INPUT(); CLOCK_HIGH(); DATA_PULL_UP(); RESET(); I2C_ENABLE(); INT_ENABLE(); ACK_ENABLE(); call Interrupt.enable(); state = IDLE; } static inline void reset() { RESET(); setBitRate(); init(); } // Silly task to signal when a stop condition is completed. task void I2C_task() { loop_until_bit_is_clear(TWCR,TWSTO); INT_FLAG_ENABLE(); signal I2C.sendEndDone(); } command result_t StdControl.init() { setBitRate(); init(); return SUCCESS; } command result_t StdControl.start() { return SUCCESS; } command result_t StdControl.stop() { return SUCCESS; } command result_t I2C.sendStart() { state=MA_START; signal I2C.sendStartDone(); return SUCCESS; } void sendstart() { SET_START_TX(); INT_FLAG_ENABLE(); } void sendAddress() { outb(TWDR,global_data); CLEAR_START_TX(); INT_FLAG_ENABLE(); } command result_t I2C.sendEnd() { SET_STOP_TX(); post I2C_task(); return SUCCESS; } // For reads and writes, if the TWINT bit is clear, the TWI is // busy or the TWI improperly initialized command result_t I2C.read(bool ack) { if (ack) ACK_ENABLE(); else NACK_ENABLE(); INT_FLAG_ENABLE(); return SUCCESS; } command result_t I2C.write(char data) { global_data=data; if(state==MA_START) { state=MA_ADDRESS; sendstart(); } if(state==MA_DATA) { outb(TWDR,data); INT_FLAG_ENABLE(); } return SUCCESS; } default event result_t I2C.sendStartDone() { return SUCCESS; } default event result_t I2C.sendEndDone() { return SUCCESS; } default event result_t I2C.readDone(char data) { return SUCCESS; } default event result_t I2C.writeDone(bool success) { return SUCCESS; } TOSH_SIGNAL(SIG_2WIRE_SERIAL) { uint8_t i2cState; i2cState=inp(TWSR) & 0xF8; INT_FLAG_DISABLE(); switch (i2cState) { case TWS_BUSERROR: reset(); //outb(TWCR,((1 << TWSTO) | (1 << TWINT))); // Reset TWI break; case TWS_START: //08 case TWS_RSTART: //10 sendAddress(); //signal I2C.sendStartDone(); break; case TWS_MT_SLA_ACK: //18 state=MA_DATA; signal I2C.writeDone(TRUE); break; case TWS_MT_DATA_ACK: //28 state=MA_DATA; signal I2C.writeDone(TRUE); break; case TWS_MT_SLA_NACK: //20 signal I2C.writeDone(FALSE); break; case TWS_MT_DATA_NACK: //30 signal I2C.writeDone(FALSE); break; case TWS_MR_SLA_ACK: state=MA_DATA; signal I2C.writeDone(TRUE); break; case TWS_MR_SLA_NACK: signal I2C.writeDone(FALSE); break; case TWS_MR_DATA_ACK: case TWS_MR_DATA_NACK: state=MA_DATA; signal I2C.readDone(inb(TWDR)); break; default: //something wrong reset(); break; } } } --- NEW FILE: hpluart1m.nc --- /* tab:4 * * * "Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * * Permission to use, copy, modify, and distribute this software and its * documentation for any purpose, without fee, and without written agreement is * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY * AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS * ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION TO * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS." * */ /* tab:4 * IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. By * downloading, copying, installing or using the software you agree to * this license. If you do not agree to this license, do not download, * install, copy or use the software. * * Intel Open Source License * * Copyright (c) 2002 Intel Corporation * All rights reserved. * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are * met: * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 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. * Neither the name of the Intel Corporation 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 INTEL OR ITS * 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. * * */ /* * * Authors: Jason Hill, David Gay, Philip Levis, Phil Buonadonna * Date last modified: $Revision: 1.1 $ * */ // The hardware presentation layer. See hpl.h for the C side. // Note: there's a separate C side (hpl.h) to get access to the avr macros // The model is that HPL is stateless. If the desired interface is as stateless // it can be implemented here (Clock, FlashBitSPI). Otherwise you should // create a separate component module HPLUART1M { provides interface HPLUART as UART; uses interface Interrupt; } implementation { command result_t UART.init() { // UART will run at: (N-8-1) // Baud UBRR1L Value: // 115kbps, 15 // 19.2kbps 47 // 9600 bps 95 // 4800 bps 191 // Set Baud Rate outp(0,UBRR1H); outp(191, UBRR1L); // Set UART double speed outp((1<<U2X),UCSR1A); // Set frame format: 8 data-bits, 1 stop-bit outp(((1 << UCSZ1) | (1 << UCSZ0)) , UCSR1C); // Enable reciever and transmitter and their interrupts outp(((1 << RXCIE) | (1 << TXCIE) | (1 << RXEN) | (1 << TXEN)) ,UCSR1B); call Interrupt.enable(); return SUCCESS; } command result_t UART.stop() { outp(0x00, UCSR1A); outp(0x00, UCSR1B); outp(0x00, UCSR1C); return SUCCESS; } default event result_t UART.get(uint8_t data) { return SUCCESS; } TOSH_SIGNAL(SIG_UART1_RECV) { if (inp(UCSR1A) & (1 << RXC)) signal UART.get(inp(UDR1)); } default event result_t UART.putDone() { return SUCCESS; } TOSH_INTERRUPT(SIG_UART1_TRANS) { signal UART.putDone(); } command result_t UART.put(uint8_t data) { outp(data, UDR1); sbi(UCSR1A, TXC); return SUCCESS; } } |
From: <cs...@us...> - 2003-08-01 18:06:03
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv2916 Added Files: avr-insight.exe.stackdump Log Message: files for new Leadtek |
From: <cs...@us...> - 2003-08-01 18:04:53
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv2665 Added Files: readme Log Message: files for new Leadtek --- NEW FILE: readme --- README for GenericBase Author/Contact: tin...@mi... Description: GenericBase is a PC to sensor network bridge. Packets received from a PC from the UART are sent out on the radio, and packets received from the radio are sent out on the UART. This allows a PC to monitor network traffic and inject packets into a network. By default, GenericBase checks CRCs. Packets sent to it over the UART must set the CRC field of the packet to 1, or GenericBase will not successfully receive the packet. When GenericBase sends a packet to the UART (receives from the radio), it toggles the green LED. When GenericBase sends a packet to the radio (receives from the UART), it blinks the red LED. If a send fails, GenericBase toggles the yellow LED. GenericBase only receives and sends packets addressed to its AM group. It receives and sends packets to any mote ID. Tools: Many tools use GenericBase as a bridge to send a receive packets from motes. Known bugs/limitations: Because the UART layer has no framing protocol, extra bytes over the UART can cause the packet layer to become unresponsive, as subsequent packets are at unexpected offsets. |
From: <cs...@us...> - 2003-08-01 18:03:39
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv2418 Added Files: uartgpspacket.nc Log Message: files for new Leadtek --- NEW FILE: uartgpspacket.nc --- /* tab:4 * * * "Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * * Permission to use, copy, modify, and distribute this software and its * documentation for any purpose, without fee, and without written agreement is * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY * AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS * ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION TO * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS." * */ /* tab:4 * IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. By * downloading, copying, installing or using the software you agree to * this license. If you do not agree to this license, do not download, * install, copy or use the software. * * Intel Open Source License * * Copyright (c) 2002 Intel Corporation * All rights reserved. * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are * met: * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 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. * Neither the name of the Intel Corporation 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 INTEL OR ITS * 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. * * */ /* * * Authors: Jason Hill, David Gay, Philip Levis * Date last modified: 6/25/02 * */ configuration UARTGpsPacket { provides { interface StdControl as Control; interface BareSendMsg as Send; interface ReceiveMsg as Receive; interface GpsCmd; } } implementation { components GpsPacket as Packet, UART1 as UART,MicaWbSwitch; GpsCmd = Packet.GpsCmd; Control = Packet.Control; Send = Packet.Send; Receive = Packet.Receive; Packet.ByteControl -> UART; Packet.ByteComm -> UART; Packet.SwitchControl -> MicaWbSwitch.StdControl; Packet.Switch1 -> MicaWbSwitch.Switch[0]; Packet.SwitchI2W -> MicaWbSwitch.Switch[1]; } |
From: <cs...@us...> - 2003-08-01 17:44:39
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv31299 Modified Files: TestMTS350M.nc Log Message: satellite check added Index: TestMTS350M.nc =================================================================== RCS file: /cvsroot/firebug/firebug/project/src/gps/TestMTS350M.nc,v retrieving revision 1.7 retrieving revision 1.8 diff -C2 -d -r1.7 -r1.8 *** TestMTS350M.nc 1 Aug 2003 16:29:20 -0000 1.7 --- TestMTS350M.nc 1 Aug 2003 17:44:35 -0000 1.8 *************** *** 72,76 **** #define GPS_MSG_LENGTH 100 #define GPS_CHAR 11 ! #define GPS_FIELDS 6 #define GPS_CHAR_PER_FIELD 10 #define GPS_DELIMITER ',' --- 72,76 ---- #define GPS_MSG_LENGTH 100 #define GPS_CHAR 11 ! #define GPS_FIELDS 8 #define GPS_CHAR_PER_FIELD 10 #define GPS_DELIMITER ',' *************** *** 360,363 **** --- 360,364 ---- char EW; uint8_t i,j; + uint8_t nos; // number of satellites // Assemble GGA_Msg *************** *** 388,391 **** --- 389,394 ---- gga_log_array[10] = pGGA->NSEWind; + nos = 10*(gga_fields[7][0]-'0') + (gga_fields[7][1]-'0'); + //***DEBUG: Output GGA data before gga_fields*** for(j=0; j<11; j++) UARTPutChar(gga_log_array[j]); *************** *** 393,404 **** //***************************************** ! //if(call GpsCmd.GpsPower(0)) { ! // SODbg(DBG_USR2, "GPS Power Off\n"); ! //} ! ! if(call LoggerWrite.write(0x19,(char *)gga_log_array)){ ! call Leds.redOn(); } - return SUCCESS; } --- 396,405 ---- //***************************************** ! //Log GGA data if three or more satellites used ! if(nos >= 3) { ! if(call LoggerWrite.write(0x19,(char *)gga_log_array)){ ! call Leds.redOn(); ! } } return SUCCESS; } |
From: <cs...@us...> - 2003-08-01 17:43:24
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv31097 Removed Files: avr-insight.exe.stackdump Log Message: problem with cvs --- avr-insight.exe.stackdump DELETED --- |
From: <cs...@us...> - 2003-08-01 17:41:20
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv29039 Modified Files: gps.html gps_driver.html Log Message: satellite check added Index: gps.html =================================================================== RCS file: /cvsroot/firebug/firebug/web/gps.html,v retrieving revision 1.7 retrieving revision 1.8 diff -C2 -d -r1.7 -r1.8 *** gps.html 1 Aug 2003 16:30:57 -0000 1.7 --- gps.html 1 Aug 2003 17:32:28 -0000 1.8 *************** *** 16,23 **** <h1>FireBug GPS</h1> ! Each wireless sensor is equipped with a Leadtek GPS receiver for localization. Each receiver has an external antenna and is mounted on the sensorboard. The schematic below represents the ! relationship between the GPS receiver and the mica2 host. <center> --- 16,23 ---- <h1>FireBug GPS</h1> ! <p>Each wireless sensor is equipped with a Leadtek GPS receiver for localization. Each receiver has an external antenna and is mounted on the sensorboard. The schematic below represents the ! relationship between the GPS receiver and the mica2 host.</p> <center> *************** *** 46,53 **** <h2>NMEA Data Format<h2> ! For this application, a standard, NMEA format is used for collecting GPS data. There are various types of NMEA messages, all containing information related to universal time, geographical location, and the ! Global Positioning System. All messages share the common features: <ul> --- 46,53 ---- <h2>NMEA Data Format<h2> ! <p>For this application, a standard, NMEA format is used for collecting GPS data. There are various types of NMEA messages, all containing information related to universal time, geographical location, and the ! Global Positioning System. All messages share the common features:</p> <ul> *************** *** 61,69 **** <blockquote> <blockquote> ! @@ GP DTS , ... (data) ... ,<CR><LF><br> where <blockquote> @@ = start indicator<br> ! DTS = data set identifier<br> <CR><LF> = stop indicator<br> </blockquote> --- 61,69 ---- <blockquote> <blockquote> ! @@ GP MID , ... (data) ... ,<CR><LF><br> where <blockquote> @@ = start indicator<br> ! MID = message set identifier<br> <CR><LF> = stop indicator<br> </blockquote> *************** *** 72,76 **** <ul> <li> ! Popular data sets include GGA (for fixed GPS data) and GLL (for geographic position) </li> --- 72,76 ---- <ul> <li> ! Popular message sets include GGA (for fixed GPS data) and GLL (for geographic position) </li> Index: gps_driver.html =================================================================== RCS file: /cvsroot/firebug/firebug/web/gps_driver.html,v retrieving revision 1.9 retrieving revision 1.10 diff -C2 -d -r1.9 -r1.10 *** gps_driver.html 1 Aug 2003 16:30:57 -0000 1.9 --- gps_driver.html 1 Aug 2003 17:32:28 -0000 1.10 *************** *** 246,250 **** gga_log_array[6] = pGGA->Lat_dec_min;</p></tt> ! <p>Lastly, <tt>gga_log_array</tt> is written into line 25 of EEPROM with the command <tt>call LoggerWrite.write(0x19,(char *)gga_log_array))</tt></p> --- 246,251 ---- gga_log_array[6] = pGGA->Lat_dec_min;</p></tt> ! <p>Lastly, if three or more satellites were used in the acquisition then ! <tt>gga_log_array</tt> is written into line 25 of EEPROM with the command <tt>call LoggerWrite.write(0x19,(char *)gga_log_array))</tt></p> |
From: <cs...@us...> - 2003-08-01 16:51:29
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv18140 Modified Files: gps_tests.htm index_old.html Added Files: gps_coldstart_data.htm Log Message: reorganized gps pages --- NEW FILE: gps_coldstart_data.htm --- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0 Transitional//EN"> <HTML><HEAD> <META content="text/html; charset=windows-1252" http-equiv=Content-Type></HEAD> <BODY><XMP>%%%%%%%%%%%%%%% %%% Purpose %%% %%%%%%%%%%%%%%% Determine cold-start acquistion time for Leadtek GPS receiver in a suburban environment. %%%%%%%%%%%% %%% Data %%% %%%%%%%%%%%% Roof of Bechtel Time | Location | Cold Start | # of Sat. -------------------------------------------------- 8:45 Chessboard 40 sec. 3 8:50 " 55 3 8:53 " 46 3 8:55 " >2 min - 8:59 " 53 3 9:00 " 52 3 9:04 Next to Pines 1:15 3 9:06 " 1:24 3 9:08 " 1:09 4 9:12 " 51 3 9:13 " 36 4 9:14 " 52 3 9:15 " 51 3 9:18 Next to Davis 1:45 3 8:21 " >2 min - 9:27 Under Trees 47 5 9:29 " 20 3 9:30 " 51 4 9:31 " >2 min - 9:34 " 42 5 9:35 " >2 min - 9:38 " >2 min - Roof of Main Stacks Time | Location | Cold Start | # of Sat. -------------------------------------------------- 9:45 Main Stacks 48 5 9:47 " 41 5 9:48 " 51 5 9:49 " >2 min - 9:51 " >2 min - 9:53 " 48 5 9:54 " 39 5 mean = 52.54 median = 51 st. dev. = 17.28 %%%%%%%%%%%%%%%%%% %%% Discussion %%% %%%%%%%%%%%%%%%%%% - Cold-start acquisition time seems to be unrelated to the # of satellites in line of sight. - Geographical data more accurate with four or more satellites - As observed at 'Main Stacks' and 'Under Trees', GPS occasionally fails even if an adequate number of satellites is know to be in line of sight - Small tree canopies, like those at 'Under Trees' do not block GPS signals - Acquisition times might be reduced by setting the receiver's sampling rate rather than power cycling it from the host (mote). To test this, though, it will be necessary to send commands to the receiver. </XMP></BODY></HTML> Index: gps_tests.htm =================================================================== RCS file: /cvsroot/firebug/firebug/web/gps_tests.htm,v retrieving revision 1.1 retrieving revision 1.2 diff -C2 -d -r1.1 -r1.2 *** gps_tests.htm 28 Jul 2003 16:47:45 -0000 1.1 --- gps_tests.htm 1 Aug 2003 16:34:06 -0000 1.2 *************** *** 67,71 **** <p> ! For raw data, click <a href="cold_start.htm">here</a>. The average cold-start time from 22 samples taken in various locations was between 51 and 52 seconds. Moreover, the following observations were made: --- 67,71 ---- <p> ! For raw data, click <a href="gps_coldstart_data.htm">here</a>. The average cold-start time from 22 samples taken in various locations was between 51 and 52 seconds. Moreover, the following observations were made: Index: index_old.html =================================================================== RCS file: /cvsroot/firebug/firebug/web/index_old.html,v retrieving revision 1.2 retrieving revision 1.3 diff -C2 -d -r1.2 -r1.3 *** index_old.html 24 Jun 2003 00:07:20 -0000 1.2 --- index_old.html 1 Aug 2003 16:34:06 -0000 1.3 *************** *** 76,80 **** <p> GPS capabilities are explained <a href= ! "gps_driver.html">here</a>. </p> --- 76,80 ---- <p> GPS capabilities are explained <a href= ! "gps.html">here</a>. </p> |
From: <cs...@us...> - 2003-08-01 16:31:00
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv17142 Modified Files: gps.html gps_driver.html Removed Files: cold_start.htm Log Message: rename cold_start Index: gps.html =================================================================== RCS file: /cvsroot/firebug/firebug/web/gps.html,v retrieving revision 1.6 retrieving revision 1.7 diff -C2 -d -r1.6 -r1.7 *** gps.html 12 May 2003 18:14:48 -0000 1.6 --- gps.html 1 Aug 2003 16:30:57 -0000 1.7 *************** *** 1,171 **** ! <!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Strict//EN" ! "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd"> ! ! <html> ! <head> ! <title> ! FireBug GPS ! </title> ! </head> ! <body> ! <h1> ! FireBug GPS ! </h1> ! <hr width="100%" size="2"> ! <h2> ! GPS ! </h2> ! <ul class="noindent"> ! <li> ! <br> ! </li> ! <li style="list-style: none"> ! Receiver ! </li> ! </ul> ! <ul class="noindent"> ! <li> ! <img src="images/gps_receiver.gif" alt="GPS Receiver" ! width="324"> ! </li> ! <li style="list-style: none"> ! <i>Receiver Specifications</i>:<br> ! </li> ! </ul> ! <ul> ! <li> ! Power Supply Voltage 3.3 V ! </li> ! <li> ! ~ 50 mW @ 0.125 Hz (Trickle State) ! </li> ! <li> ! > 400 mW for continuous sampling (Tracking State) ! </li> ! <li> ! Position Accuracy: 15 m ! </li> ! <li> ! NMEA or proprietery data format (eg. SiRF) output<br> ! </li> ! </ul> ! <table cellpadding="2" cellspacing="2" border="1" width="80%" ! align="center" summary="Add summary here"> ! <tbody> ! <tr> ! <td valign="top" bgcolor="#CCCCCC"> ! <b>NMEA Data Format</b><br> ! <br> ! ! <ul> ! <li> ! Broadcast via a serial interface from GPS ! receiver to host ! </li> ! <li> ! Composed of 83 8-bit ASCII character ! </li> ! </ul> ! <blockquote> ! <blockquote> ! @@ GP DTS , ... (data) ... , ! <CR><LF><br> ! where @@ = start indicator<br> ! DTS = data set identifier<br> ! <CR><LF> = stop ! indicator<br> ! </blockquote> ! </blockquote> ! <ul> ! <li> ! Popular data sets include GGA (for fixed GPS ! data) and GLL (for geographic position) ! </li> ! <li> ! commas act as delimiters<br> ! </li> ! </ul> ! </td> ! </tr> ! </tbody> ! </table> - <br> - <br> - - <h2> - GPS Driver - </h2> - <i>Functions of host driver</i>:<br> - - <ul> - <li> - Wake-up GPS receiver - </li> - <li> - Notify host of receiver response - </li> - <li> - Decode GPS message - </li> - <li> - Checksum of message<br> - </li> - <li> - Store information into memory - </li> - </ul> - Position data from NMEA GGA is decoded and stored as 9 bytes - in the mote's EEPROM. Data is stored in the following - structure:<br> - <br> - <img src="images/gps_eeprom_data.gif" alt="GPS EEPROM DATA" - width="690" height="96"> <br> - - <ul> - <li> - Here, Status refers to the N/S,E/W indicators: SE = - 0x00, SW = 0x01, NE = 0x10, NW = 0x11 - </li> - <li> - The remaining 7 bytes in the EEPROM line are given values - 0xFF<br> - </li> - </ul> - <br> - <br> - - <pre> - - 1. Power on mote - a. Turn on mote timer - b. - 2. Mote catches events from timer firing - - a. Mote switches on state of the GPS unit and state of mote ! i. state POWER_ON ! ! b. GPS is powered ! c. Set mote UART to 4800 baud ! ! ! Wake up GPS unit: ! i. set GPS 9600 baud ! ii. set GPS format to NMEA ! </pre> ! <hr /> ! <p> ! Last Updated: $Date$ ! by $Author$. ! </p> ! </body> </html> --- 1,99 ---- ! <!DOCTYPE html PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN"> ! <html xmlns="http://www.w3.org/1999/xhtml"> ! <head name="author" content="Carmel Majidi, UC Berkeley" /="" type="text/css" rel="stylesheet" href="firebug.css"> ! <title>FireBug --- GPS Driver</title> ! ! <meta name="author" content="Carmel Majidi, UC Berkeley" /=""> ! ! <link type="text/css" rel="stylesheet" href="firebug.css"> ! ! <link rel="SHORTCUT ICON" href="./images/favicon.ico"> ! ! <meta name="author" content="Carmel Majidi, UC Berkeley" /=""> ! </head> ! <body> ! <h1>FireBug GPS</h1> ! Each wireless sensor is equipped with a Leadtek GPS receiver ! for localization. Each receiver has an external antenna and is ! mounted on the sensorboard. The schematic below represents the ! relationship between the GPS receiver and the mica2 host. + <center> + <img src="./images/gps_receiver.gif" alt="GPS Interface"> + </center> ! <h2>Receiver Specifications (not updated for new Leadtek receivers)</h2> ! <ul> ! <li> ! Power Supply Voltage 3.3 V ! </li> ! <li> ! ~ 50 mW @ 0.125 Hz (Trickle State) ! </li> ! <li> ! > 400 mW for continuous sampling (Tracking State) ! </li> ! <li> ! Position Accuracy: 15 m ! </li> ! <li> ! NMEA or proprietery data format (eg. SiRF) output<br> ! </li> ! </ul> ! <h2>NMEA Data Format<h2> ! For this application, a standard, NMEA format is used for collecting ! GPS data. There are various types of NMEA messages, all containing ! information related to universal time, geographical location, and the ! Global Positioning System. All messages share the common features: + <ul> + <li> + Broadcast via a serial interface from GPS receiver to host + </li> + <li> + Composed of 83 8-bit ASCII character + </li> + </ul> + <blockquote> + <blockquote> + @@ GP DTS , ... (data) ... ,<CR><LF><br> + where + <blockquote> + @@ = start indicator<br> + DTS = data set identifier<br> + <CR><LF> = stop indicator<br> + </blockquote> + </blockquote> + </blockquote> + <ul> + <li> + Popular data sets include GGA (for fixed GPS data) and GLL + (for geographic position) + </li> + <li> + commas act as delimiters<br> + </li> + </ul> ! <h2><a href="gps_driver.html">GPS Driver</a></h2> ! ! <h2><a href="gps_tests.htm">Receiver Characterization</a></h2> ! ! <hr /=""> ! <h2>Useful Links</h2> ! <p><a href="http://nmviewogc.cr.usgs.gov/viewer.htm">USGS National Map Viewer</a> ! -- use <i>Identify</i> tool to get Long/Lat coordinates of any point ! in the U.S.A.</p> ! <p><a href="http://www.topozone.com">www.topozone.com</a> ! -- interactive USGS topo map of the entire U.S.A.</p> ! <hr /=""> ! <p> Last updated: $Date$ by $Author$. ! </p> ! </body> </html> Index: gps_driver.html =================================================================== RCS file: /cvsroot/firebug/firebug/web/gps_driver.html,v retrieving revision 1.8 retrieving revision 1.9 diff -C2 -d -r1.8 -r1.9 *** gps_driver.html 31 Jul 2003 23:48:21 -0000 1.8 --- gps_driver.html 1 Aug 2003 16:30:57 -0000 1.9 *************** *** 40,45 **** <tr> <td width="100%"> ! <pre> ! event TOS_MsgPtr GpsReceive.receive(TOS_MsgPtr data) {<br> int8_t gga_string[MSG_LENGTH];<br> bool gga_read = FALSE;<br> bool gga_read_done = FALSE;<br> uint16_t i = 0;<br> uint8_t j = 0;<br> <br> GPS_MsgPtr gps_data = (GPS_MsgPtr)data;<br> <br> while (!gga_read_done) {<br> <br> if(gps_data->data[i] == 'G') {<br> if(gps_data->data[i+1] == 'G') {<br> if(gps_data->data[i+2] == 'A') {<br> gga_read = TRUE;<br> }<br> }<br> }<br> ...<br> if(gga_read) {<br> gga_string[j] = gps_data->data[i];<br> j++;<br> }<br> <br> i++;<br> }<br> } </pre> </td> --- 40,70 ---- <tr> <td width="100%"> ! <pre> ! event TOS_MsgPtr GpsReceive.receive(TOS_MsgPtr data) { ! int8_t gga_string[GPS_MSG_LENGTH]; ! bool gga_read = FALSE; ! bool gga_read_done = FALSE; ! uint16_t i = 0; ! uint8_t j = 0; ! GPS_MsgPtr gps_data = (GPS_MsgPtr)data; ! ! while (!gga_read_done) { ! ! if(gps_data->data[i] == 'G') { ! if(gps_data->data[i+1] == 'G') { ! if(gps_data->data[i+2] == 'A') { ! gga_read = TRUE; ! } ! } ! } ! ... ! if(gga_read) { ! gga_string[j] = gps_data->data[i]; ! j++; ! } ! ! i++; ! } ! } </pre> </td> *************** *** 58,63 **** <tr> <td width="100%"> ! <pre> ! event TOS_MsgPtr GpsReceive.receive(TOS_MsgPtr data) {<br> ...<br> while (!gga_read_done) {<br> ...<br> if(gps_data->data[i] == '*') {<br> if(gga_read) {<br> call <b>parseGPS</b>(gga_string, j);<br> gga_read = FALSE;<br> gga_read_done = TRUE;<br> }<br> }<br> ...<br> }<br> } </pre> </td> --- 83,104 ---- <tr> <td width="100%"> ! <pre> ! event TOS_MsgPtr GpsReceive.receive(TOS_MsgPtr data) { ! ... ! while (!gga_read_done) { ! ... ! if(gps_data->data[i] == GPS_END_MSG) { ! if(gga_read) { ! if(call GpsCmd.GpsPower(0)) { ! SODbg(DBG_USR2, "GPS Power Off\n"); ! } ! call parseGPS(gga_string, j); ! gga_read = FALSE; ! gga_read_done = TRUE; ! } ! } ! ... ! } ! } </pre> </td> *************** *** 69,73 **** <h2>Storing GGA data</h2> <p>In <tt>parseGGA</tt>, the comma-delimited fields of <tt>gga_string ! </tt> are placed into an array, <tt>write</tt>, which is then sent to <tt>logGPS</tt> for storage.</p> --- 110,114 ---- <h2>Storing GGA data</h2> <p>In <tt>parseGGA</tt>, the comma-delimited fields of <tt>gga_string ! </tt> are placed into an array, <tt>gga_fields</tt>, which is then sent to <tt>logGPS</tt> for storage.</p> *************** *** 82,86 **** <td width="100%"> <b>gps.h</b> ! <pre> typedef struct GGA_Msg<br> {<br> uint8_t hours;<br> uint8_t minutes;<br> uint16_t dec_sec;<br> uint8_t Lat_deg;<br> uint16_t Lat_dec_min;<br> uint8_t Long_deg;<br> uint16_t Long_dec_min;<br> uint8_t NSEWind;<br> } GGA_Msg; </pre> --- 123,127 ---- <td width="100%"> <b>gps.h</b> ! <pre> typedef struct GGA_Msg<br> {<br> uint8_t hours;<br> uint8_t minutes;<br> uint16_t dec_sec;<br> uint8_t Lat_deg;<br> uint16_t Lat_dec_min;<br> uint8_t Long_deg;<br> uint16_t Long_dec_min;<br> uint8_t NSEWind;<br> } GGA_Msg; </pre> *************** *** 91,95 **** </center> ! <p>The entry <tt>write[i][j]</tt> represents the jth character in the ith field of GGA string. Fields of interest, their field number, and the number of characters they contain, including decimal points, are --- 132,136 ---- </center> ! <p>The entry <tt>gga_fields[i][j]</tt> represents the jth character in the ith field of GGA string. Fields of interest, their field number, and the number of characters they contain, including decimal points, are *************** *** 160,168 **** <p>Characters representing numbers in ASCII are converted to integers ! by the operation <tt>write[i][j]-'0'</tt>. So for example, the UTC hour, which is given by the first two characters of the second field ! of <tt>write</tt>, is stored as a single 8-bit integer in the line</p> ! <center>pGGA->hours = 10*(write[1][0]-'0') + (write[1][1]-'0');</center> <p>The rest of <tt>GGA_Str</tt> is likewise assembled in this manner.</p> --- 201,209 ---- <p>Characters representing numbers in ASCII are converted to integers ! by the operation <tt>gga_fields[i][j]-'0'</tt>. So for example, the UTC hour, which is given by the first two characters of the second field ! of <tt>gga_fields</tt>, is stored as a single 8-bit integer in the line</p> ! <center>pGGA->hours = 10*(gga_fields[1][0]-'0') + (gga_fields[1][1]-'0');</center> <p>The rest of <tt>GGA_Str</tt> is likewise assembled in this manner.</p> *************** *** 174,194 **** <td width="100%"> <pre> ! pGGA->minutes = 10*(write[1][2]-'0') + (write[1][3]-'0'); ! pGGA->dec_sec = 10000*(write[1][4]-'0') + 1000*(write[1][5]-'0') ! + 100*(write[1][7]-'0') + 10*(write[1][8]-'0') ! + (write[1][9]-'0'); ! pGGA->Lat_deg = 10*(write[2][0]-'0') + (write[2][1]-'0'); ! pGGA->Lat_dec_min = 100000*(write[2][2]-'0') + 10000*(write[2][3]-'0') ! + 1000*(write[2][4]-'0') + 100*(write[2][5]-'0') ! + 10*(write[2][6]-'0') + (write[2][7]-'0'); ! pGGA->Long_deg = 100*(write[4][0]-'0') + 10*(write[4][1]-'0') + (write[4][2]-'0'); ! pGGA->Long_dec_min = 100000*(write[4][3]-'0') + 10000*(write[4][4]-'0') ! + 1000*(write[4][5]-'0') + 100*(write[4][6]-'0') ! + 10*(write[4][7]-'0') + (write[4][8]-'0'); ! NS = (write[3][0] == 'N') ? 1 : 0; ! EW = (write[5][0] == 'W') ? 1 : 0; pGGA->NSEWind = EW | (NS<<4); // eg. Status = 000N000E = 00010000 </pre> --- 215,235 ---- <td width="100%"> <pre> ! pGGA->minutes = 10*(gga_fields[1][2]-'0') + (gga_fields[1][3]-'0'); ! pGGA->dec_sec = 10000*(gga_fields[1][4]-'0') + 1000*(gga_fields[1][5]-'0') ! + 100*(gga_fields[1][7]-'0') + 10*(gga_fields[1][8]-'0') ! + (gga_fields[1][9]-'0'); ! pGGA->Lat_deg = 10*(gga_fields[2][0]-'0') + (gga_fields[2][1]-'0'); ! pGGA->Lat_dec_min = 100000*(gga_fields[2][2]-'0') + 10000*(gga_fields[2][3]-'0') ! + 1000*(gga_fields[2][4]-'0') + 100*(gga_fields[2][5]-'0') ! + 10*(gga_fields[2][6]-'0') + (gga_fields[2][7]-'0'); ! pGGA->Long_deg = 100*(gga_fields[4][0]-'0') + 10*(gga_fields[4][1]-'0') + (gga_fields[4][2]-'0'); ! pGGA->Long_dec_min = 100000*(gga_fields[4][3]-'0') + 10000*(gga_fields[4][4]-'0') ! + 1000*(gga_fields[4][5]-'0') + 100*(gga_fields[4][6]-'0') ! + 10*(gga_fields[4][7]-'0') + (gga_fields[4][8]-'0'); ! NS = (gga_fields[3][0] == 'N') ? 1 : 0; ! EW = (gga_fields[5][0] == 'W') ? 1 : 0; pGGA->NSEWind = EW | (NS<<4); // eg. Status = 000N000E = 00010000 </pre> *************** *** 200,223 **** <p>For storage into EEPROM, <tt>GGA_Str</tt> data is entered into character ! array, <tt>log_array</tt>. For 16-bit data, the 8 most significant bits precede the 8 least significant bits as shown for Latitude decimal seconds:</p> ! <tt><p>log_array[5] = (pGGA->Lat_dec_min)>>8;<br> ! log_array[6] = pGGA->Lat_dec_min;</p></tt> ! <p>Lastly, <tt>log_array</tt> is written into line 25 of EEPROM with the command ! <tt>call LoggerWrite.write(0x19,(char *)log_array))</tt></p> ! ! <hr /=""> ! ! <h2>Click <a href="gps_tests.htm">here</a> for experimental results</h2> ! ! <hr /=""> - <h2>Useful Links</h2> - <p><a href="http://nmviewogc.cr.usgs.gov/viewer.htm">USGS National Map Viewer</a> - -- use <i>Identify</i> tool to get Long/Lat coordinates of any point - in the U.S.A.</p> - <p><a href="http://www.topozone.com">www.topozone.com</a> - -- interactive USGS topo map of the entire U.S.A.</p> <hr /=""> <p> Last updated: $Date$ by $Author$. --- 241,252 ---- <p>For storage into EEPROM, <tt>GGA_Str</tt> data is entered into character ! array, <tt>gga_log_array</tt>. For 16-bit data, the 8 most significant bits precede the 8 least significant bits as shown for Latitude decimal seconds:</p> ! <tt><p>gga_log_array[5] = (pGGA->Lat_dec_min)>>8;<br> ! gga_log_array[6] = pGGA->Lat_dec_min;</p></tt> ! <p>Lastly, <tt>gga_log_array</tt> is written into line 25 of EEPROM with the command ! <tt>call LoggerWrite.write(0x19,(char *)gga_log_array))</tt></p> <hr /=""> <p> Last updated: $Date$ by $Author$. --- cold_start.htm DELETED --- |
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv4146 Removed Files: gps.h gps.nc gpsBcast.class gpsBcast.java gpsCmd.nc gpsCmdM.nc gpsCmdMsg.h gpsM.nc gpsRetrieve.nc Log Message: files for Axiom GPS removed --- gps.h DELETED --- --- gps.nc DELETED --- --- gpsBcast.class DELETED --- --- gpsBcast.java DELETED --- --- gpsCmd.nc DELETED --- --- gpsCmdM.nc DELETED --- --- gpsCmdMsg.h DELETED --- --- gpsM.nc DELETED --- --- gpsRetrieve.nc DELETED --- |
From: <do...@us...> - 2003-08-01 00:35:14
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv11938/web Modified Files: gps_driver.html Removed Files: mem_glad.jpg Log Message: Some minor changes resulting from meeting with Carmel. Index: gps_driver.html =================================================================== RCS file: /cvsroot/firebug/firebug/web/gps_driver.html,v retrieving revision 1.7 retrieving revision 1.8 diff -C2 -d -r1.7 -r1.8 *** gps_driver.html 29 Jul 2003 17:54:28 -0000 1.7 --- gps_driver.html 31 Jul 2003 23:48:21 -0000 1.8 *************** *** 91,96 **** </center> ! <p>The entry <tt>write[i][j]</tt> represents the ith character in the ! jth field of GGA string. Fields of interest, their field number, and the number of characters they contain, including decimal points, are given in the table below:</p> --- 91,96 ---- </center> ! <p>The entry <tt>write[i][j]</tt> represents the jth character in the ! ith field of GGA string. Fields of interest, their field number, and the number of characters they contain, including decimal points, are given in the table below:</p> --- mem_glad.jpg DELETED --- |
From: <do...@us...> - 2003-07-31 23:55:22
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv11938/project/src/gps Modified Files: TestMTS350.nc TestMTS350M.nc Log Message: Some minor changes resulting from meeting with Carmel. Index: TestMTS350.nc =================================================================== RCS file: /cvsroot/firebug/firebug/project/src/gps/TestMTS350.nc,v retrieving revision 1.2 retrieving revision 1.3 diff -C2 -d -r1.2 -r1.3 *** TestMTS350.nc 31 Jul 2003 15:33:56 -0000 1.2 --- TestMTS350.nc 31 Jul 2003 23:48:21 -0000 1.3 *************** *** 61,64 **** --- 61,66 ---- configuration TestMTS350 { } + + /* SimpleCmd can be dropped (?) */ implementation { components Main, TestMTS350M, RadioCRCPacket as Comm, UARTNoCRCPacket,SensirionHumidity, MicaWbSwitch,UARTGpsPacket,TimerC, LedsC, Logger, SimpleCmd; Index: TestMTS350M.nc =================================================================== RCS file: /cvsroot/firebug/firebug/project/src/gps/TestMTS350M.nc,v retrieving revision 1.5 retrieving revision 1.6 diff -C2 -d -r1.5 -r1.6 *** TestMTS350M.nc 31 Jul 2003 15:33:56 -0000 1.5 --- TestMTS350M.nc 31 Jul 2003 23:48:21 -0000 1.6 *************** *** 70,73 **** --- 70,74 ---- includes gps; + /* FIXME: GPS name space */ #define MSG_LENGTH 100 #define GGA_BYTES 11 *************** *** 329,332 **** --- 330,334 ---- } + // two commas (,,) indicate empty field // if field is empty, set it equal to 0 if (j <= 1) { |
From: <do...@us...> - 2003-07-31 23:04:33
|
Update of /cvsroot/firebug/firebug/web/images In directory sc8-pr-cvs1:/tmp/cvs-serv3629 Added Files: mem_glad.jpg Log Message: Moved gps figure. --- NEW FILE: mem_glad.jpg --- (This appears to be a binary file; contents omitted.) |
From: <cs...@us...> - 2003-07-31 15:39:57
|
Update of /cvsroot/firebug/firebug/project/src/gps In directory sc8-pr-cvs1:/tmp/cvs-serv10685 Modified Files: TestMTS350.nc TestMTS350M.nc gps.h Log Message: GPS Power cycle every 5 sec. Index: TestMTS350.nc =================================================================== RCS file: /cvsroot/firebug/firebug/project/src/gps/TestMTS350.nc,v retrieving revision 1.1 retrieving revision 1.2 diff -C2 -d -r1.1 -r1.2 *** TestMTS350.nc 8 Jul 2003 21:51:35 -0000 1.1 --- TestMTS350.nc 31 Jul 2003 15:33:56 -0000 1.2 *************** *** 62,66 **** } implementation { ! components Main, TestMTS350M, RadioCRCPacket as Comm, UARTNoCRCPacket,SensirionHumidity, MicaWbSwitch,UARTGpsPacket,TimerC, LedsC, Logger; Main.StdControl -> TestMTS350M; --- 62,66 ---- } implementation { ! components Main, TestMTS350M, RadioCRCPacket as Comm, UARTNoCRCPacket,SensirionHumidity, MicaWbSwitch,UARTGpsPacket,TimerC, LedsC, Logger, SimpleCmd; Main.StdControl -> TestMTS350M; *************** *** 104,107 **** TestMTS350M.LoggerWrite -> Logger.LoggerWrite; TestMTS350M.LoggerRead -> Logger; ! } --- 104,107 ---- TestMTS350M.LoggerWrite -> Logger.LoggerWrite; TestMTS350M.LoggerRead -> Logger; ! } Index: TestMTS350M.nc =================================================================== RCS file: /cvsroot/firebug/firebug/project/src/gps/TestMTS350M.nc,v retrieving revision 1.4 retrieving revision 1.5 diff -C2 -d -r1.4 -r1.5 *** TestMTS350M.nc 15 Jul 2003 16:57:35 -0000 1.4 --- TestMTS350M.nc 31 Jul 2003 15:33:56 -0000 1.5 *************** *** 162,166 **** command result_t StdControl.start() { result_t ok1, ok2, ok3; ! //call Timer.start(TIMER_REPEAT, 5000); ok1 = call UARTControl.start(); ok2 = call RadioControl.start(); --- 162,166 ---- command result_t StdControl.start() { result_t ok1, ok2, ok3; ! call Timer.start(TIMER_REPEAT, 5000); ok1 = call UARTControl.start(); ok2 = call RadioControl.start(); *************** *** 268,271 **** --- 268,274 ---- if(gps_data->data[i] == '*') { if(gga_read) { + if(call GpsCmd.GpsPower(0)) { + SODbg(DBG_USR2, "GPS Power Off\n"); + } call parseGPS(gga_string, j); gga_read = FALSE; *************** *** 417,420 **** --- 420,430 ---- return SUCCESS; } + + //event result_t Timer.fired() { + // call GpsCmd.GpsPower(1); + //} + + + Index: gps.h =================================================================== RCS file: /cvsroot/firebug/firebug/project/src/gps/gps.h,v retrieving revision 1.4 retrieving revision 1.5 diff -C2 -d -r1.4 -r1.5 *** gps.h 14 Apr 2003 18:24:55 -0000 1.4 --- gps.h 31 Jul 2003 15:33:56 -0000 1.5 *************** *** 1,7 **** ! /* -*- Mode: C; c-basic-indent: 3; indent-tabs-mode: nil -*- */ ! ! ! /* tab:4 ! * Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * --- 1,6 ---- ! /* tab:4 ! * ! * ! * "Copyright (c) 2000-2002 The Regents of the University of California. * All rights reserved. * *************** *** 10,19 **** * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. ! * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ! * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY --- 9,18 ---- * hereby granted, provided that the above copyright notice, the following * two paragraphs and the author appear in all copies of this software. ! * * IN NO EVENT SHALL THE UNIVERSITY OF CALIFORNIA BE LIABLE TO ANY PARTY FOR * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT * OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF THE UNIVERSITY OF * CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ! * * THE UNIVERSITY OF CALIFORNIA SPECIFICALLY DISCLAIMS ANY WARRANTIES, * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY *************** *** 23,72 **** * */ ! /* - * This file is part of the FireBug project. * ! * FireBug 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, or (at your option) any ! * later version. * ! * FireBug 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 Geotechnica; see the file COPYING. If not, write to the Free ! * Software Foundation, 59 Temple Place - Suite 330, Boston, ! * MA 02111-1307, USA. */ ! /* ! * The definition of gps messages needs to be moved out ! * of the "private" module files into "public" header ! * files so that third party applications (such as mig) ! * will be able to generate parsing code from the ! * definition of the messages. ! */ - /* - * @todo Break up the typedef, mig won't support it. - * Necessary typedefs can be used internally to the - * nesc source files. - */ - struct GPSMsg { - char LatDegrees; //(0-90) - char LatMinutes; //(0-59) - int LatSeconds; //2 bytes (0-59999) - char LongDegrees; //(0-180) - char LongMinutes; //(0-59) - int LongSeconds; //2 bytes - char Status; //(SE=00, SW=01, NE=10, NW=11); - }; - enum { - AM_GPSMSG = 127 - }; --- 22,96 ---- * */ ! /* tab:4 ! * IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. By ! * downloading, copying, installing or using the software you agree to ! * this license. If you do not agree to this license, do not download, ! * install, copy or use the software. ! * ! * Intel Open Source License ! * ! * Copyright (c) 2002 Intel Corporation ! * All rights reserved. ! * Redistribution and use in source and binary forms, with or without ! * modification, are permitted provided that the following conditions are ! * met: ! * ! * Redistributions of source code must retain the above copyright ! * notice, this list of conditions and the following disclaimer. ! * 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. ! * Neither the name of the Intel Corporation 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 INTEL OR ITS ! * 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. ! * ! * ! */ /* * ! * Authors: * ! * $Id$ */ ! #define GPS_DATA_LENGTH 350 ! typedef struct GPS_Msg ! { ! /* The following fields are received on the gps. */ ! uint8_t length; ! int8_t data[GPS_DATA_LENGTH]; ! uint16_t crc; ! } GPS_Msg; ! typedef GPS_Msg *GPS_MsgPtr; ! ! typedef struct GGA_Msg ! { ! uint8_t hours; ! uint8_t minutes; ! uint16_t dec_sec; ! uint8_t Lat_deg; ! uint16_t Lat_dec_min; ! uint8_t Long_deg; ! uint16_t Long_dec_min; ! uint8_t NSEWind; ! ! ! } GGA_Msg; ! ! |
From: <che...@us...> - 2003-07-30 23:43:20
|
Update of /cvsroot/firebug/firebug/project/src/sensordata In directory sc8-pr-cvs1:/tmp/cvs-serv28632 Modified Files: sensormsg.h Log Message: add rss Index: sensormsg.h =================================================================== RCS file: /cvsroot/firebug/firebug/project/src/sensordata/sensormsg.h,v retrieving revision 1.1 retrieving revision 1.2 diff -C2 -d -r1.1 -r1.2 *** sensormsg.h 10 Jul 2003 09:05:26 -0000 1.1 --- sensormsg.h 30 Jul 2003 23:43:17 -0000 1.2 *************** *** 64,67 **** --- 64,68 ---- float rel_hum; float baro_pres; + uint16_t rss; }; |
From: <che...@us...> - 2003-07-30 23:41:03
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv28332 Added Files: 2003_7_28.txt Log Message: . --- NEW FILE: 2003_7_28.txt --- FireBug web client for mote activity Mote ID Time Temp Rel. Hum. Baro. Pres. Cnt Rss doe_2003_7_28cumulative 2 20030730115440 72.1 98.3 29.1 61 0 2 20030730115440 72.1 98.3 29.1 62 0 2 20030730115440 72.1 98.3 29.1 63 0 2 20030730115440 72.1 98.3 29.1 64 0 2 20030730115440 72.1 98.3 29.1 65 0 2 20030730115440 72.1 98.3 29.1 66 0 2 20030730115440 72.1 98.3 29.1 67 0 2 20030730115440 72.1 98.3 29.1 68 0 2 20030730115440 72.1 98.3 29.1 69 0 2 20030730115440 72.1 98.3 29.1 70 0 2 20030730115440 72.1 98.3 29.1 72 0 2 20030730115440 72.1 98.3 29.1 73 0 2 20030730115440 72.1 98.3 29.1 74 0 2 20030730115440 72.1 98.3 29.1 75 0 2 20030730115440 72.1 98.3 29.1 76 0 [...1378 lines suppressed...] 6 20030730115440 72.1 98.3 29.1 164 0 6 20030730115440 72.1 98.3 29.1 165 0 6 20030730115440 72.1 98.3 29.1 166 0 6 20030730115440 72.1 98.3 29.1 167 0 6 20030730115440 72.1 98.3 29.1 168 0 6 20030730115440 72.1 98.3 29.1 169 0 6 20030730115440 72.1 98.3 29.1 170 0 6 20030730115440 72.1 98.3 29.1 171 0 6 20030730115440 72.1 98.3 29.1 172 0 6 20030730115440 72.1 98.3 29.1 173 0 6 20030730115440 72.1 98.3 29.1 174 0 6 20030730115440 72.1 98.3 29.1 175 0 6 20030730115440 72.1 98.3 29.1 176 0 6 20030730115440 72.1 98.3 29.1 177 0 6 20030730115440 72.1 98.3 29.1 178 0 6 20030730115440 72.1 98.3 29.1 179 0 6 20030730115440 72.1 98.3 29.1 180 0 6 20030730115440 72.1 98.3 29.1 181 0 6 20030730115440 72.1 98.3 29.1 182 0 6 20030730115440 72.1 98.3 29.1 183 0 |
From: <che...@us...> - 2003-07-30 22:17:50
|
Update of /cvsroot/firebug/firebug/project/java/src/org/firebug In directory sc8-pr-cvs1:/tmp/cvs-serv11844/src/org/firebug Modified Files: DBLogger.java SensorMsg.java SensorPacket.java Log Message: add rss Index: DBLogger.java =================================================================== RCS file: /cvsroot/firebug/firebug/project/java/src/org/firebug/DBLogger.java,v retrieving revision 1.21 retrieving revision 1.22 diff -C2 -d -r1.21 -r1.22 *** DBLogger.java 21 Jul 2003 18:34:21 -0000 1.21 --- DBLogger.java 30 Jul 2003 22:17:41 -0000 1.22 *************** *** 60,64 **** // message. ! SensorMsg msg = new SensorMsg(packet,5,21); Connection conn = dbh.getConnection(); --- 60,64 ---- // message. ! SensorMsg msg = new SensorMsg(packet,5,23); Connection conn = dbh.getConnection(); *************** *** 83,86 **** --- 83,87 ---- float rel_hum = msg.get_rel_hum(); float baro_pres = msg.get_baro_pres(); + int rss=msg.get_rss(); if (get_packet_type(packet) != 1){ *************** *** 120,124 **** + "rel_hum=" + rel_hum + ", " + "baro_pres=" + baro_pres + ", " ! + "temp=" + temp + " WHERE mote_id=" + mote_id; String insertquery = "INSERT INTO cumulative VALUES (" --- 121,126 ---- + "rel_hum=" + rel_hum + ", " + "baro_pres=" + baro_pres + ", " ! + "temp=" + temp + ", " ! + "rss=" + rss + " WHERE mote_id=" + mote_id; String insertquery = "INSERT INTO cumulative VALUES (" *************** *** 127,132 **** + temp + ", " + rel_hum + ", " ! + baro_pres + "," ! + cnt + ")"; --- 129,135 ---- + temp + ", " + rel_hum + ", " ! + baro_pres + ", " ! + cnt + ", " ! + rss + ")"; Index: SensorMsg.java =================================================================== RCS file: /cvsroot/firebug/firebug/project/java/src/org/firebug/SensorMsg.java,v retrieving revision 1.4 retrieving revision 1.5 diff -C2 -d -r1.4 -r1.5 *** SensorMsg.java 10 Jul 2003 09:02:58 -0000 1.4 --- SensorMsg.java 30 Jul 2003 22:17:41 -0000 1.5 *************** *** 10,19 **** /** The default size of this message type in bytes. */ ! public static final int DEFAULT_MESSAGE_SIZE = 16; /** The Active Message type associated with this message. */ public static final int AM_TYPE = 128; ! /** Create a new SensorMsg of size 16. */ public SensorMsg() { super(DEFAULT_MESSAGE_SIZE); --- 10,19 ---- /** The default size of this message type in bytes. */ ! public static final int DEFAULT_MESSAGE_SIZE = 18; /** The Active Message type associated with this message. */ public static final int AM_TYPE = 128; ! /** Create a new SensorMsg of size 18. */ public SensorMsg() { super(DEFAULT_MESSAGE_SIZE); *************** *** 102,105 **** --- 102,108 ---- s += " [baro_pres="+Float.toString(get_baro_pres())+"]\n"; } catch (ArrayIndexOutOfBoundsException aioobe) { /* Skip field */ } + try { + s += " [rss=0x"+Long.toHexString(get_rss())+"]\n"; + } catch (ArrayIndexOutOfBoundsException aioobe) { /* Skip field */ } return s; } *************** *** 109,113 **** ///////////////////////////////////////////////////////// // Accessor methods for field: addr ! // Field type: int // Offset (bits): 0 // Size (bits): 16 --- 112,116 ---- ///////////////////////////////////////////////////////// // Accessor methods for field: addr ! // Field type: int, unsigned // Offset (bits): 0 // Size (bits): 16 *************** *** 115,122 **** /** ! * Return whether the field 'addr' is signed (true). */ public static boolean isSigned_addr() { ! return true; } --- 118,125 ---- /** ! * Return whether the field 'addr' is signed (false). */ public static boolean isSigned_addr() { ! return false; } *************** *** 172,176 **** ///////////////////////////////////////////////////////// // Accessor methods for field: cnt ! // Field type: int // Offset (bits): 16 // Size (bits): 16 --- 175,179 ---- ///////////////////////////////////////////////////////// // Accessor methods for field: cnt ! // Field type: int, unsigned // Offset (bits): 16 // Size (bits): 16 *************** *** 178,185 **** /** ! * Return whether the field 'cnt' is signed (true). */ public static boolean isSigned_cnt() { ! return true; } --- 181,188 ---- /** ! * Return whether the field 'cnt' is signed (false). */ public static boolean isSigned_cnt() { ! return false; } *************** *** 235,239 **** ///////////////////////////////////////////////////////// // Accessor methods for field: temp ! // Field type: float // Offset (bits): 32 // Size (bits): 32 --- 238,242 ---- ///////////////////////////////////////////////////////// // Accessor methods for field: temp ! // Field type: float, unsigned // Offset (bits): 32 // Size (bits): 32 *************** *** 241,248 **** /** ! * Return whether the field 'temp' is signed (true). */ public static boolean isSigned_temp() { ! return true; } --- 244,251 ---- /** ! * Return whether the field 'temp' is signed (false). */ public static boolean isSigned_temp() { ! return false; } *************** *** 298,302 **** ///////////////////////////////////////////////////////// // Accessor methods for field: rel_hum ! // Field type: float // Offset (bits): 64 // Size (bits): 32 --- 301,305 ---- ///////////////////////////////////////////////////////// // Accessor methods for field: rel_hum ! // Field type: float, unsigned // Offset (bits): 64 // Size (bits): 32 *************** *** 304,311 **** /** ! * Return whether the field 'rel_hum' is signed (true). */ public static boolean isSigned_rel_hum() { ! return true; } --- 307,314 ---- /** ! * Return whether the field 'rel_hum' is signed (false). */ public static boolean isSigned_rel_hum() { ! return false; } *************** *** 361,365 **** ///////////////////////////////////////////////////////// // Accessor methods for field: baro_pres ! // Field type: float // Offset (bits): 96 // Size (bits): 32 --- 364,368 ---- ///////////////////////////////////////////////////////// // Accessor methods for field: baro_pres ! // Field type: float, unsigned // Offset (bits): 96 // Size (bits): 32 *************** *** 367,374 **** /** ! * Return whether the field 'baro_pres' is signed (true). */ public static boolean isSigned_baro_pres() { ! return true; } --- 370,377 ---- /** ! * Return whether the field 'baro_pres' is signed (false). */ public static boolean isSigned_baro_pres() { ! return false; } *************** *** 420,423 **** --- 423,489 ---- public static int sizeBits_baro_pres() { return 32; + } + + ///////////////////////////////////////////////////////// + // Accessor methods for field: rss + // Field type: int, unsigned + // Offset (bits): 128 + // Size (bits): 16 + ///////////////////////////////////////////////////////// + + /** + * Return whether the field 'rss' is signed (false). + */ + public static boolean isSigned_rss() { + return false; + } + + /** + * Return whether the field 'rss' is an array (false). + */ + public static boolean isArray_rss() { + return false; + } + + /** + * Return the offset (in bytes) of the field 'rss' + */ + public static int offset_rss() { + return (128 / 8); + } + + /** + * Return the offset (in bits) of the field 'rss' + */ + public static int offsetBits_rss() { + return 128; + } + + /** + * Return the value (as a int) of the field 'rss' + */ + public int get_rss() { + return (int)getUIntElement(offsetBits_rss(), 16); + } + + /** + * Set the value of the field 'rss' + */ + public void set_rss(int value) { + setUIntElement(offsetBits_rss(), 16, value); + } + + /** + * Return the size, in bytes, of the field 'rss' + */ + public static int size_rss() { + return (16 / 8); + } + + /** + * Return the size, in bits, of the field 'rss' + */ + public static int sizeBits_rss() { + return 16; } Index: SensorPacket.java =================================================================== RCS file: /cvsroot/firebug/firebug/project/java/src/org/firebug/SensorPacket.java,v retrieving revision 1.8 retrieving revision 1.9 diff -C2 -d -r1.8 -r1.9 *** SensorPacket.java 21 Jul 2003 18:24:22 -0000 1.8 --- SensorPacket.java 30 Jul 2003 22:17:41 -0000 1.9 *************** *** 84,94 **** s += " [="+Long.toString((long)tempF)+" Fahrenheit Degree]\n"; */ ! if (packet[2]==1 && packet[7]!=-1 && packet[10]!=1){ ! s += " [MoteID="+Long.toString(packet[10])+ "]\n"; //Humidity //s += " [Humidity Data="+Long.toString(packet[12]*256)+Long.toString(packet[11])+"]"; //Temperature //s += " [TempData="+Long.toString(packet[14]*256)+ Long.toString(packet[13])+"]"; s += " [TempData="+Long.toString(packet[14])+ " " + Long.toString(packet[13])+"]"; } return s; --- 84,99 ---- s += " [="+Long.toString((long)tempF)+" Fahrenheit Degree]\n"; */ ! //if (packet[2]==1 && packet[7]!=-1 && packet[5]!=1){ ! if (packet[2]==1 && packet[5]!=1){ ! s += " [MoteID="+Long.toString(packet[5])+ "]\n"; //Humidity //s += " [Humidity Data="+Long.toString(packet[12]*256)+Long.toString(packet[11])+"]"; + //cnt + s += " [Cnt#="+Long.toString(packet[7])+ "]\n"; + //Temperature //s += " [TempData="+Long.toString(packet[14]*256)+ Long.toString(packet[13])+"]"; s += " [TempData="+Long.toString(packet[14])+ " " + Long.toString(packet[13])+"]"; + } return s; |
From: <che...@us...> - 2003-07-30 22:16:13
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv11609 Modified Files: db_create.php table_select.php Log Message: add rss Index: db_create.php =================================================================== RCS file: /cvsroot/firebug/firebug/web/db_create.php,v retrieving revision 1.8 retrieving revision 1.9 diff -C2 -d -r1.8 -r1.9 *** db_create.php 18 Jul 2003 20:06:20 -0000 1.8 --- db_create.php 30 Jul 2003 22:16:10 -0000 1.9 *************** *** 38,45 **** mysql_query($statement) or die("Error: ".mysql_error()." in creating location atable"); ! $statement = "CREATE TABLE current (mote_id INTEGER, time TIMESTAMP, temp FLOAT, rel_hum FLOAT, baro_pres FLOAT, cnt INTEGER)"; mysql_query($statement) or die("Error: ".mysql_error()." in creating current atable"); ! $statement = "CREATE TABLE cumulative (mote_id INTEGER, time TIMESTAMP, temp FLOAT, rel_hum FLOAT, baro_pres FLOAT, cnt INTEGER)"; mysql_query($statement) or die("Error: ".mysql_error()." in creating cumulative atable"); --- 38,45 ---- mysql_query($statement) or die("Error: ".mysql_error()." in creating location atable"); ! $statement = "CREATE TABLE current (mote_id INTEGER, time TIMESTAMP, temp FLOAT, rel_hum FLOAT, baro_pres FLOAT, cnt INTEGER, rss INTEGER)"; mysql_query($statement) or die("Error: ".mysql_error()." in creating current atable"); ! $statement = "CREATE TABLE cumulative (mote_id INTEGER, time TIMESTAMP, temp FLOAT, rel_hum FLOAT, baro_pres FLOAT, cnt INTEGER, rss INTEGER)"; mysql_query($statement) or die("Error: ".mysql_error()." in creating cumulative atable"); *************** *** 53,57 **** for ($i = 2; $i <= $nummotes+1; $i++) { ! $statement = "insert into current values ($i,NULL,NULL,NULL,NULL,NULL);"; print "<br />"; print $statement; --- 53,57 ---- for ($i = 2; $i <= $nummotes+1; $i++) { ! $statement = "insert into current values ($i,NULL,NULL,NULL,NULL,NULL,NULL);"; print "<br />"; print $statement; Index: table_select.php =================================================================== RCS file: /cvsroot/firebug/firebug/web/table_select.php,v retrieving revision 1.8 retrieving revision 1.9 diff -C2 -d -r1.8 -r1.9 *** table_select.php 30 Jul 2003 22:04:03 -0000 1.8 --- table_select.php 30 Jul 2003 22:16:10 -0000 1.9 *************** *** 54,58 **** <td>Rel. Hum.</td> <td>Baro. Pres.</td> ! <td>cnt </td> </tr> --- 54,59 ---- <td>Rel. Hum.</td> <td>Baro. Pres.</td> ! <td>Cnt </td> ! <td>Rss </td> </tr> *************** *** 86,93 **** --- 87,100 ---- } + if ($rss == "") { + $rss = "%"; + } + + $result = mysql_query("select * from $tblname where mote_id like '$mote_id%' and time like '$time%' and cnt like '$cnt%' + and rss like '$rss%' and temp like '$temp%' and rel_hum like '$rel_hum%' *************** *** 125,128 **** --- 132,139 ---- print ("<td>"); print $row["cnt"]; + print ("</td>"); + + print ("<td>"); + print $row["rss"]; print ("</td>"); |
From: <do...@us...> - 2003-07-30 22:04:07
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv9758 Modified Files: db_select.php table_select.php Log Message: Improvements in web database php script interfaces. Index: db_select.php =================================================================== RCS file: /cvsroot/firebug/firebug/web/db_select.php,v retrieving revision 1.4 retrieving revision 1.5 diff -C2 -d -r1.4 -r1.5 *** db_select.php 30 Jul 2003 21:49:39 -0000 1.4 --- db_select.php 30 Jul 2003 22:04:03 -0000 1.5 *************** *** 15,22 **** <hr /> - <h1>FireBug Tables selected</h1> ! <center> <form action="table_select.php" method="post"> --- 15,22 ---- <hr /> ! ! <form action="table_select.php" method="post"> *************** *** 27,30 **** --- 27,37 ---- mysql_connect("localhost","root","") or die("Error: ".mysql_error()." in mysql_connect."); $dblink=mysql_select_db("$dbname") or die("Error: ".mysql_error()." in mysql_select_db."); + + + + print("<h1>Database $dbname tables</h1>"); + + + print("<center>\n"); print("<table class='db_schema'><tr><td>Table Name</td><td>Selected</td></tr>"); *************** *** 53,59 **** </form> </center> ! <?php ! echo "Database <strong>$dbname</strong> displayed."; ! ?> <br /> --- 60,64 ---- </form> </center> ! <br /> Index: table_select.php =================================================================== RCS file: /cvsroot/firebug/firebug/web/table_select.php,v retrieving revision 1.7 retrieving revision 1.8 diff -C2 -d -r1.7 -r1.8 *** table_select.php 10 Jul 2003 09:01:09 -0000 1.7 --- table_select.php 30 Jul 2003 22:04:03 -0000 1.8 *************** *** 16,20 **** <body> ! <h1>FireBug web client for mote activity</h1> --- 16,46 ---- <body> ! <?php ! include("nav_footer.php"); ! ?> ! ! <hr /> ! ! <p> ! Sensor data last updated: ! <?php ! echo date ("l dS F Y h:i:s A"); ! ?> ! </p> ! ! ! ! <?php ! //if (!isset($HTTP_SESSION_VARS["tblname"])) { ! if ($HTTP_POST_VARS["tbl1"]!=Null){ ! $HTTP_SESSION_VARS["tblname"] = $HTTP_POST_VARS["tbl1"]; ! $HTTP_SESSION_VARS["dbname"] = $HTTP_POST_VARS["db1"]; ! } ! ! $dbname = $HTTP_SESSION_VARS["dbname"]; ! $tblname = $HTTP_SESSION_VARS["tblname"]; ! ! print("<h1>Mote activity: Database $dbname, table $tblname</h1>"); ! ?> *************** *** 32,46 **** <?php - //if (!isset($HTTP_SESSION_VARS["tblname"])) { - if ($HTTP_POST_VARS["tbl1"]!=Null){ - $HTTP_SESSION_VARS["tblname"] = $HTTP_POST_VARS["tbl1"]; - $HTTP_SESSION_VARS["dbname"] = $HTTP_POST_VARS["db1"]; - } - - $dbname = $HTTP_SESSION_VARS["dbname"]; - $tblname = $HTTP_SESSION_VARS["tblname"]; - print $dbname; - print $tblname; - mysql_connect("localhost","root","") or die("Error: ".mysql_error()." in mysql_connect."); --- 58,61 ---- |
From: <do...@us...> - 2003-07-30 22:02:07
|
Update of /cvsroot/firebug/firebug/web In directory sc8-pr-cvs1:/tmp/cvs-serv6877 Modified Files: db_list.php db_select.php Log Message: Changing web database layout. Index: db_list.php =================================================================== RCS file: /cvsroot/firebug/firebug/web/db_list.php,v retrieving revision 1.1 retrieving revision 1.2 diff -C2 -d -r1.1 -r1.2 *** db_list.php 22 Jul 2003 15:38:45 -0000 1.1 --- db_list.php 30 Jul 2003 21:49:39 -0000 1.2 *************** *** 11,14 **** --- 11,19 ---- <h1>FireBug web client database selection</h1> + <?php + include("nav_footer.php"); + ?> + + <hr /> <center> *************** *** 60,68 **** <hr /> - <?php - include("nav_footer.php"); - ?> - - <hr /> <p> --- 65,68 ---- Index: db_select.php =================================================================== RCS file: /cvsroot/firebug/firebug/web/db_select.php,v retrieving revision 1.3 retrieving revision 1.4 diff -C2 -d -r1.3 -r1.4 *** db_select.php 14 May 2003 18:47:41 -0000 1.3 --- db_select.php 30 Jul 2003 21:49:39 -0000 1.4 *************** *** 8,12 **** --- 8,21 ---- <body> + + <?php + include("nav_footer.php"); + ?> + + <hr /> + <h1>FireBug Tables selected</h1> + + <center> <form action="table_select.php" method="post"> |
From: <do...@us...> - 2003-07-30 21:43:24
|
Update of /cvsroot/firebug/firebug/project/zaurus In directory sc8-pr-cvs1:/tmp/cvs-serv5788/project/zaurus Modified Files: build.xml Log Message: listenFB will now run from build.xml using ant if the build properties has the paths set correctly. Index: build.xml =================================================================== RCS file: /cvsroot/firebug/firebug/project/zaurus/build.xml,v retrieving revision 1.9 retrieving revision 1.10 diff -C2 -d -r1.9 -r1.10 *** build.xml 30 Jul 2003 16:42:05 -0000 1.9 --- build.xml 30 Jul 2003 21:43:21 -0000 1.10 *************** *** 97,100 **** --- 97,107 ---- </target> + <target name="runp" depends="jar"> + <echo message=".\dist\tosmc.jar;${COMM}/comm.jar" /> + <java classpath=".\dist\tosmc.jar;${COMM}/comm.jar" + classname="net.tinyos.tostools.PortLister" fork="yes"> + </java> + </target> + |
From: <do...@us...> - 2003-07-30 21:43:24
|
Update of /cvsroot/firebug/firebug/project/zaurus/net/tinyos/tostools In directory sc8-pr-cvs1:/tmp/cvs-serv5788/project/zaurus/net/tinyos/tostools Modified Files: Listener.java Added Files: PortLister.java Log Message: listenFB will now run from build.xml using ant if the build properties has the paths set correctly. --- NEW FILE: PortLister.java --- package net.tinyos.tostools; import java.io.*; import javax.comm.*; import java.util.*; class PortLister { public static void main (String[] args) { Enumeration pList = CommPortIdentifier.getPortIdentifiers(); CommPortIdentifier cpi = null; System.out.println("Elements: " + pList.hasMoreElements()); while (pList.hasMoreElements()) { cpi = (CommPortIdentifier) pList.nextElement(); System.out.println("Port " + cpi.getName()); System.out.println("PortType " + cpi.getPortType()); } } } Index: Listener.java =================================================================== RCS file: /cvsroot/firebug/firebug/project/zaurus/net/tinyos/tostools/Listener.java,v retrieving revision 1.1 retrieving revision 1.2 diff -C2 -d -r1.1 -r1.2 *** Listener.java 29 Jul 2003 23:33:16 -0000 1.1 --- Listener.java 30 Jul 2003 21:43:21 -0000 1.2 *************** *** 29,33 **** import javax.comm.*; - //import net.tinyos.util.*; public class Listener { --- 29,32 ---- |
From: <do...@us...> - 2003-07-30 21:43:24
|
Update of /cvsroot/firebug/firebug/project/java/src/org/firebug In directory sc8-pr-cvs1:/tmp/cvs-serv5788/project/java/src/org/firebug Modified Files: ListenFB.java Log Message: listenFB will now run from build.xml using ant if the build properties has the paths set correctly. Index: ListenFB.java =================================================================== RCS file: /cvsroot/firebug/firebug/project/java/src/org/firebug/ListenFB.java,v retrieving revision 1.11 retrieving revision 1.12 diff -C2 -d -r1.11 -r1.12 *** ListenFB.java 28 Jul 2003 03:13:14 -0000 1.11 --- ListenFB.java 30 Jul 2003 21:43:21 -0000 1.12 *************** *** 97,100 **** --- 97,105 ---- UnsupportedCommOperationException { + Enumeration pList = CommPortIdentifier.getPortIdentifiers(); + + System.out.println("Elements: " + pList.hasMoreElements()); + + System.out.println("Opening port " + portName); portId = CommPortIdentifier.getPortIdentifier(portName); *************** *** 208,215 **** static void handle_args(String [] args) { if (args.length != 3) { printUsage(); } ! /** None of the following is currently being used. */ --- 213,221 ---- static void handle_args(String [] args) { + if (args.length != 3) { printUsage(); } ! /** None of the following is currently being used. */ |