sonar.cpp
Go to the documentation of this file.
00001 /* -*- mode: C++ -*- */
00002 /*********************************************************************
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (C) 2015, Jack O'Quin
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the authors nor other contributors may be
00019 *     used to endorse or promote products derived from this software
00020 *     without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00045 #include <NewPing.h>
00046 #include <sonar.h>
00047 
00048 #define MAX_DISTANCE 200              ///< maximum distance to ping (cm)
00049 #define N_SONARS 3                    ///< number of sonars
00050 
00052 static NewPing sonar[N_SONARS] =
00053   {
00054     NewPing(30, 4, MAX_DISTANCE),
00055     NewPing(28, 3, MAX_DISTANCE),
00056     NewPing(26, 2, MAX_DISTANCE),
00057   };
00058 
00059 // These should be class variables, but they are static because the
00060 // NewPing and Arduino timer interfaces can only handle static
00061 // functions, not a class member functions.
00062 static uint8_t static_current = N_SONARS; 
00063 static unsigned int static_distance;      
00064 
00073 void timer_event()
00074 { 
00075   if (sonar[static_current].check_timer())
00076     {
00077       static_distance = sonar[static_current].ping_result / US_ROUNDTRIP_CM;
00078     }
00079 }
00080 
00086 void Sonar::poll(void)
00087 {
00088   if (static_current < N_SONARS)         // previous sonar was active?
00089     {
00090       // cancel previous timer
00091       sonar[static_current].timer_stop();
00092 
00093       // publish previous cycle results
00094       Serial.print("S");                // sonar message marker
00095       Serial.print(static_current);
00096       Serial.print("=");
00097       Serial.print(static_distance);
00098       Serial.println("cm ");
00099     }
00100 
00101   // next sonar in the rotation
00102   if (++static_current >= N_SONARS)
00103     static_current = 0;
00104 
00105   // start another ping
00106   static_distance = 0;                        // in case of no echo
00107   sonar[static_current].ping_timer(timer_event);
00108 }


segbot_firmware
Author(s): Jose Bigio, Jack O'Quin, Tim Eckel (NewPing library)
autogenerated on Thu Jun 6 2019 21:37:01