2021-01-05 03:51:08 -04:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program 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 General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
/*
Analogin . cpp : We loop through the 16 pins and output the analog voltage of the pins
*/
2015-08-11 03:28:43 -03:00
# include <AP_HAL/AP_HAL.h>
2012-09-10 23:05:22 -03:00
2021-01-05 03:51:08 -04:00
void setup ( ) ; //declaration of the setup() function
void loop ( ) ; //declaration of the loop() function
2017-04-13 08:31:16 -03:00
2021-01-05 03:51:08 -04:00
const AP_HAL : : HAL & hal = AP_HAL : : get_HAL ( ) ; //create a reference to AP_HAL::HAL object to get access to hardware specific functions. For more info see <https://ardupilot.org/dev/docs/learning-ardupilot-the-example-sketches.html/>
2012-09-10 23:05:22 -03:00
2023-10-11 04:41:53 -03:00
AP_HAL : : AnalogSource * chan ; //declare a pointer to AnalogSource object. AnalogSource class can be found in : AP_HAL->AnalogIn.h
2012-09-10 23:05:22 -03:00
2021-01-05 03:51:08 -04:00
// the setup function runs once when the board powers up
2017-04-13 08:31:16 -03:00
void setup ( void ) {
2021-01-05 03:51:08 -04:00
hal . console - > printf ( " Starting AP_HAL::AnalogIn test \r \n " ) ; //print a starting message
chan = hal . analogin - > channel ( 0 ) ; //initialization of chan variable. AnalogIn class can be found in : AP_HAL->AnalogIn.h
2012-09-10 23:05:22 -03:00
}
2021-01-05 03:51:08 -04:00
static int8_t pin ; //8 bit integer to hold the pin number.Pin number range is [0,15]
2013-05-02 08:31:55 -03:00
2021-01-05 03:51:08 -04:00
//the loop function runs over and over again forever
void loop ( void ) {
//get the average voltage reading
float v = chan - > voltage_average ( ) ; //note:the voltage value is divided into 1024 segments
//start a new line after going through the 16 pins
2013-05-02 08:31:55 -03:00
if ( pin = = 0 ) {
2017-04-13 08:31:16 -03:00
hal . console - > printf ( " \n " ) ;
2013-05-02 08:31:55 -03:00
}
2021-01-05 03:51:08 -04:00
//print the voltage value(3 decimal places) alongside the pin number
2015-10-25 17:10:41 -03:00
hal . console - > printf ( " [%u %.3f] " ,
2017-04-13 08:31:16 -03:00
( unsigned ) pin , ( double ) v ) ;
2021-01-05 03:51:08 -04:00
//increment the pin number
2013-05-02 08:31:55 -03:00
pin = ( pin + 1 ) % 16 ;
2021-01-05 03:51:08 -04:00
//set pin corresponding to the new pin value
2021-09-22 16:46:55 -03:00
IGNORE_RETURN ( chan - > set_pin ( pin ) ) ;
2021-01-05 03:51:08 -04:00
//give a delay of 100ms
2013-05-02 08:31:55 -03:00
hal . scheduler - > delay ( 100 ) ;
2012-09-10 23:05:22 -03:00
}
2021-01-05 03:51:08 -04:00
AP_HAL_MAIN ( ) ; //HAL Macro that declares the main function. For more info see <https://ardupilot.org/dev/docs/learning-ardupilot-the-example-sketches.html/>