diff --git a/Arduino/libraries/CodeRacer/CodeRacer.cpp b/Arduino/libraries/CodeRacer/CodeRacer.cpp index 009169b..c4dc5fe 100644 --- a/Arduino/libraries/CodeRacer/CodeRacer.cpp +++ b/Arduino/libraries/CodeRacer/CodeRacer.cpp @@ -1,496 +1,797 @@ // the compiler switch for an ESP8266 is looking like this: #elif defined(ARDUINO_ARCH_ESP8266) - #include "CodeRacer.h" -//Konstruktor ohne Pins ... alle Vorgaben kommen aus dem CodeRacer.h Header file +/** @brief CodeRace constructor without pins. All pins settings taken from the coderacer header file +* @return nothing +*/ CodeRacer::CodeRacer() { - _taster_pin = H_TASTERPIN; - _servopin = H_SERVOPIN; - _us_trigger_pin = H_US_TRIG; - _us_echo_pin = H_US_ECHO; - _motor_links_frwd_pin = H_MOTORLI_FWRD; - _motor_links_back_pin = H_MOTORLI_BACK; - _motor_links_enable_pin = H_MOTORLI_SPEED; - _motor_rechts_frwd_pin = H_MOTORRE_FWRD; - _motor_rechts_back_pin = H_MOTORRE_BACK; - _motor_rechts_enable_pin = H_MOTORRE_SPEED; - _led_frwd_pin = H_LED_VORWAERTS; - _led_stop_pin = H_LED_STOP; - _led_links_pin = H_LED_LINKS; - _led_rechts_pin = H_LED_RECHTS; - - _servo_dummy = new Servo(); - _servo = new Servo(); - - _servo_mitte = H_SERVO_MITTE; - _servo_links = H_SERVO_LINKS; - _servo_rechts = H_SERVO_RECHTS; - _schwenk_links = H_SERVO_SCHWENK_LINKS; - _schwenk_rechts = H_SERVO_SCHWENK_RECHTS; - - _schwenk_position = _servo_mitte; - _schwenk_richtung = SERVO_SCHWENK_LI; - _schwenk_millis = millis(); - - _motor_links_tempo = H_MOTORLI_TEMPO; - _motor_rechts_tempo = H_MOTORRE_TEMPO; - _drehung_links_ms = H_RACER_LINKS_MS; - _drehung_rechts_ms = H_RACER_RECHTS_MS; - - coderracer_activ = false; - _coderracer_activ = true; - _drive_forward = false; - _schwenk = false; - - _last_ledswitch_ms = millis(); - _last_led_on = 0; - _led_count = 1; - - _min_abstand_cm = 0; - - _servo_look_around_ms = millis(); - + _button_pin = H_BUTTON_PIN; + _servo_pin = H_SERVO_PIN; + _us_trigger_pin = H_US_TRIG_PIN; + _us_echo_pin = H_US_ECHO_PIN; + _drive_left_frwd_pin = H_DRIVE_LEFT_FWRD_PIN; + _drive_left_back_pin = H_DRIVE_LEFT_BACK_PIN; + _drive_left_enable_pin = H_DRIVE_LEFT_ENABLE_PIN; + _drive_right_frwd_pin = H_DRIVE_RIGHT_FWRD_PIN; + _drive_right_back_pin = H_DRIVE_RIGHT_BACK_PIN; + _drive_right_enable_pin = H_DRIVE_RIGHT_ENABLE_PIN; + _led_frwd_pin = H_LED_FRWD_PIN; + _led_stop_pin = H_LED_STOP_PIN; + _led_left_pin = H_LED_LEFT_PIN; + _led_right_pin = H_LED_RIGHT_PIN; } -// Konstruktor mit pin Übergaben ... - -CodeRacer::CodeRacer(int tasterpin , int servopin, - int us_trigger_pin, int us_echo_pin, - int motor_links_frwd_pin, int motor_links_back_pin, int motor_links_enable_pin, - int motor_rechts_frwd_pin, int motor_rechts_back_pin, int motor_rechts_enable_pin, - int led_frwd, int led_stop, int led_links, int led_rechts +/** @brief CodeRace constructor with pins.This will overwrite the default settings taken from the header file. +* @param button_pin Pin the external button is connected at +* @param servo_pin Pin the servo drive is connected at +* @param us_trigger_pin Pin the trigger signal of the ultrasonic sensor is connected at +* @param us_echo_pin Pin the echo signal of the ultrasonic sensor is connected at +* @param drive_left_frwd_pin Pin the forward pin of the left side drive device driver is connected at +* @param drive_left_back_pin Pin the backward pin of the left side drive device driver is connected at +* @param drive_left_enable_pin Pin the enable pin of the left side drive device driver is connected at +* @param drive_right_frwd_pin Pin the forward pin of the right side drive device driver is connected at +* @param drive_right_back_pin Pin the backward pin of the right side drive device driver is connected at +* @param drive_right_enable_pin Pin the enable pin of the right side drive device driver is connected at +* @param led_frwd_pin Pin the led that signals forward direction is connected at +* @param led_stop_pin Pin the led that signals that the drives are stopped is connected at +* @param led_left_pin Pin the led that signals left side direction is connected at +* @param led_right_pin Pin the led that signals right side direction is connected at +* @return nothing +*/ +CodeRacer::CodeRacer(uint8_t button_pin , uint8_t servo_pin, + uint8_t us_trigger_pin, uint8_t us_echo_pin, + uint8_t drive_left_frwd_pin, uint8_t drive_left_back_pin, uint8_t drive_left_enable_pin, + uint8_t drive_right_frwd_pin, uint8_t drive_right_back_pin, uint8_t drive_right_enable_pin, + uint8_t led_frwd_pin, uint8_t led_stop_pin, uint8_t led_left_pin, uint8_t led_right_pin ) { - _taster_pin = tasterpin; - _servopin = servopin; + _button_pin = button_pin; + _servo_pin = servo_pin; _us_trigger_pin = us_trigger_pin; _us_echo_pin = us_echo_pin; - _motor_links_frwd_pin = motor_links_frwd_pin; - _motor_links_back_pin = motor_links_back_pin; - _motor_links_enable_pin = motor_links_enable_pin; - _motor_rechts_frwd_pin = motor_rechts_frwd_pin; - _motor_rechts_back_pin = motor_rechts_back_pin; - _motor_rechts_enable_pin = motor_rechts_enable_pin; - _led_frwd_pin = led_frwd; - _led_stop_pin = led_stop; - _led_links_pin = led_links; - _led_rechts_pin = led_rechts; + _drive_left_frwd_pin = drive_left_frwd_pin; + _drive_left_back_pin = drive_left_back_pin; + _drive_left_enable_pin = drive_left_enable_pin; + _drive_right_frwd_pin = drive_right_frwd_pin; + _drive_right_back_pin = drive_right_back_pin; + _drive_right_enable_pin = drive_right_enable_pin; + _led_frwd_pin = led_frwd_pin; + _led_stop_pin = led_stop_pin; + _led_left_pin = led_left_pin; + _led_right_pin = led_right_pin; +} - _servo_dummy = new Servo(); +/** @brief Initialisation of all attributes and settings of the coderacer. Defaults are taken from the header file. +* @return nothing +*/ +void CodeRacer::begin() { + + // init of variables and objects + + _servo_dummy = new Servo(); // the dummy is needed so far to avoid conflicts with analog write _servo = new Servo(); + servo_center_pos = H_SERVO_CENTER_POS; + servo_left_pos = H_SERVO_LEFT_POS; + servo_right_pos = H_SERVO_RIGHT_POS; + servo_sweep_left_pos = H_SERVO_SWEEP_LEFT_POS; + servo_sweep_right_pos = H_SERVO_SWEEP_RIGHT_POS; + _servo_position = servo_center_pos; + _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP; + _servo_position_set_at_ms = millis(); + _servo_position_eta_in_ms = 0; - _servo_mitte = H_SERVO_MITTE; - _servo_links = H_SERVO_LINKS; - _servo_rechts = H_SERVO_RECHTS; - _schwenk_links = H_SERVO_SCHWENK_LINKS; - _schwenk_rechts = H_SERVO_SCHWENK_RECHTS; + _drive_left_speed = H_DRIVE_LEFT_SPEED; + _drive_right_speed = H_DRIVE_RIGHT_SPEED; - _schwenk_position = _servo_mitte; - _schwenk_richtung = SERVO_SCHWENK_LI; - _schwenk_millis = millis(); - - _motor_links_tempo = H_MOTORLI_TEMPO; - _motor_rechts_tempo = H_MOTORRE_TEMPO; - _drehung_links_ms = H_RACER_LINKS_MS; - _drehung_rechts_ms = H_RACER_RECHTS_MS; + _turn_left_for_ms = H_RACER_TURN_LEFT_FOR_MS; + _turn_right_for_ms = H_RACER_TURN_RIGHT_FOR_MS; coderracer_activ = false; _coderracer_activ = true; - _drive_forward = false; - _schwenk = false; + _drive = false; + _drive_set_at_ms = millis(); + _servo_sweep = false; - _last_ledswitch_ms = millis(); + _last_led_switched_at_ms = millis(); _last_led_on = 0; - _led_count = 1; + _led_count = 3; - _servo_look_around_ms = millis(); + _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS); - _min_abstand_cm = 0; + _usonic_stop_distance_cm = H_US_STOP_DISTANCE_CM; + usonic_set_stop_distance_cm(_usonic_stop_distance_cm); + _coderacer_stopped_at_min_distance = false; -} - - - -void CodeRacer::begin() { - - // Ultraschallsensor - pinMode(_us_trigger_pin, OUTPUT); // Ultraschallsensor: TRIG ist ein Ausgangspin. Es wird ein Signal zum Ultraschallsensor gesendet - pinMode(_us_echo_pin, INPUT); // Ultraschallsensor: ECHO ist ein Eingangspin. Es wird ein Signal vom Ultraschallsensor empfangen + // Ultrasonic sensor + pinMode(_us_trigger_pin, OUTPUT); + pinMode(_us_echo_pin, INPUT); - // Servo - _servo->attach(_servopin); // dem Servo Objekt "sagen" an welchen Pin am Schaltkreis der Server angeschlossen ist + // Servo drive + _servo->attach(_servo_pin); - // Linker Motor - pinMode(_motor_links_frwd_pin, OUTPUT); // Linker Motor FORWARD ist ein Ausgang. - pinMode(_motor_links_back_pin, OUTPUT); // Linker Motor BACKWARD ist ein Ausgang. - ledcSetup(MOTORPWM_LINKS, 5000, 8); // channel 1, 50 Hz, 8-bit width - ledcAttachPin(_motor_links_enable_pin, MOTORPWM_LINKS); // Linker Motor SPEED mit Kanal 1 verbunden - analog_write(_motor_links_enable_pin, 0); // Linken Motor sicherheitshalber ausschalten :-) + // Left drive + pinMode(_drive_left_frwd_pin, OUTPUT); + pinMode(_drive_left_back_pin, OUTPUT); + set_drive_left_state(DRIVESTOP); + ledcSetup(DRIVE_PWM_LEFT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width + ledcAttachPin(_drive_left_enable_pin, DRIVE_PWM_LEFT_CHANNEL); // connect left drive enable with PWM channel - // Rechter Motor - pinMode(_motor_rechts_frwd_pin, OUTPUT); // Rechter Motor FORWARD ist ein Ausgang. - pinMode(_motor_rechts_back_pin, OUTPUT); // Rechter Motor BACKWARD ist ein Ausgang. - ledcSetup(MOTORPWM_RECHTS, 5000, 8); // channel 2, 50 Hz, 8-bit width - ledcAttachPin(_motor_rechts_enable_pin, MOTORPWM_RECHTS); // Rechter Motor SPEED mit Kanal 2 verbunden - analog_write(_motor_rechts_enable_pin, 0); // Rechten Motor sicherheitshalber ausschalten :-) + // Right drive + pinMode(_drive_right_frwd_pin, OUTPUT); + pinMode(_drive_right_back_pin, OUTPUT); + set_drive_right_state(DRIVESTOP); + ledcSetup(DRIVE_PWM_RIGHT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width + ledcAttachPin(_drive_right_enable_pin, DRIVE_PWM_RIGHT_CHANNEL); // connect right drive enable pin with PWM channel - // LEDs - pinMode(_led_frwd_pin, OUTPUT); // LED Vorwärts ist ein Ausgang - pinMode(_led_stop_pin, OUTPUT); // LED Stop ist ein Ausgang - pinMode(_led_links_pin, OUTPUT); // LED Links ist ein Ausgang - pinMode(_led_rechts_pin, OUTPUT); // LED Rechts ist ein Ausgang - // alle LEDS aus - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); + // LEDs + pinMode(_led_frwd_pin, OUTPUT); + pinMode(_led_stop_pin, OUTPUT); + pinMode(_led_left_pin, OUTPUT); + pinMode(_led_right_pin, OUTPUT); + // all LEDS off + set_leds_all_off(); - // Taster - taster_last_pressed_ms = 0; - pinMode(_taster_pin, INPUT_PULLUP); - attachInterrupt(digitalPinToInterrupt(_taster_pin), set_taster_state, FALLING); + // Button & -interrupt + button_last_pressed_at_ms = 0; + pinMode(_button_pin, INPUT_PULLUP); + attachInterrupt(digitalPinToInterrupt(_button_pin), _set_button_state, FALLING); // Random randomSeed(analogRead(0)); - Serial.println("CodeRacer initialisiert ... "); + //fun stuff + coderacer_fun_enabled = false; + } -void CodeRacer::servo_einstellungen(int winkel_mitte, int winkel_links, int winkel_rechts, int schwenk_links, int schwenk_rechts) +//************************************** +//*** Coderacer hihger level methods *** +//************************************** +/** @defgroup higherlevel Higher level methods, setters and getters +* @{ +*/ +/** @defgroup higherlevelmeths Methods +* @{ +*/ + +/** @brief Stops the racer and sets status LEDs. +* @return nothing +*/ +void CodeRacer::stop_driving() { + _servo_sweep = false; + _drive = false; + set_drives_stop_left_right(); + set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF); +} + +/** @brief Sets the speed and the directions of both drives so that it will move forward. +* +* The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section +* @return nothing +*/ +void CodeRacer::drive_forward() { - _servo_mitte = winkel_mitte; - _servo_links = winkel_links; - _servo_rechts = winkel_rechts; - _schwenk_links = schwenk_links; - _schwenk_rechts = schwenk_rechts; - - _schwenk_position = _servo_mitte; - _schwenk_richtung = SERVO_SCHWENK_LI; - _schwenk_millis = millis(); - - Serial.println("CodeRacer Servo eingestellt ... "); - + drive_forward(_drive_left_speed, _drive_right_speed); } -void CodeRacer::motor_einstellungen(int motor_links_tempo, int motor_rechts_tempo, int drehung_links_ms, int drehung_rechts_ms) +/** @brief Sets the speed as specified for both drives and the directions of both drives so that it will move forward. +* +* The specified speed values for both drives will be stored internaly so next time if you use e.g. drive_forward() exactly the here specified values will be taken. +* @param left_speed speed for the left side drive. 0<=speed<=255 +* @param right_speed speed for the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::drive_forward(uint8_t left_speed, uint8_t right_speed) { - _motor_links_tempo = motor_links_tempo; - _motor_rechts_tempo = motor_rechts_tempo; - _drehung_links_ms = drehung_links_ms; - _drehung_rechts_ms = drehung_rechts_ms; + set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD); + set_drives_speed_left_right(left_speed, right_speed); + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF); + _drive = true; + _drive_set_at_ms = millis(); } -void CodeRacer::analog_write(int pin, int speed) { - if (pin == _motor_links_enable_pin) { ledcWrite(MOTORPWM_LINKS, speed); } - if (pin == _motor_rechts_enable_pin) { ledcWrite(MOTORPWM_RECHTS, speed); } -} - -void CodeRacer::anhalten() { - Serial.println("RACER_ANHALTEN"); // Meldung am Monitor ausgeben - _schwenk = false; - _drive_forward = false; - _drive_normal_forward = false; - //Rechten Motor abschalten - digitalWrite(_motor_rechts_frwd_pin, LOW); - digitalWrite(_motor_rechts_back_pin, LOW); - // Linken Motor abschalten - digitalWrite(_motor_links_frwd_pin, LOW); - digitalWrite(_motor_links_back_pin, LOW); - // Motoren beide ausschalten - analog_write(_motor_rechts_enable_pin, 0); - analog_write(_motor_links_enable_pin, 0); - // LEDs setzen - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_stop_pin, HIGH); - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); - delay(1000); -} - - -void CodeRacer::normal_tempo() +/** @brief Sets the speed and the directions of both drives so that it will move backward. +* +* The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section +* @return nothing +*/ +void CodeRacer::drive_backward() { - //Serial.println("RACER_NORMAL_TEMPO"); // Meldung am Monitor ausgeben - analog_write(_motor_rechts_enable_pin, _motor_rechts_tempo); - analog_write(_motor_links_enable_pin, _motor_links_tempo); - _drive_forward = true; - _drive_normal_forward = true; + drive_backward(_drive_left_speed, _drive_right_speed); } -void CodeRacer::vorwaerts() +/** @brief Sets the speed as specified for both drives and the directions of both drives so that it will move backward. +* +* The specified speed values for both drives will be stored internaly so next time if you use e.g. drive_backward() exactly the here specified values will be taken. +* @param left_speed speed for the left side drive. 0<=speed<=255 +* @param right_speed speed for the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::drive_backward(uint8_t left_speed, uint8_t right_speed) { + set_drives_states_left_right(DRIVEBACK, DRIVEBACK); + set_drives_speed_left_right(left_speed, right_speed); + set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDON, LEDOFF); + _drive = true; + _drive_set_at_ms = millis(); +} - Serial.println("RACER_VORWAERTS"); // Meldung am Monitor ausgeben +/** @brief Will turn the racer to the left for the internally stroe time in ms and with the internally stored speed. +* +* The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to left time can be set by thoose methods as well. +* The method is delayed until the racer has turned. +* @return nothing +*/ +void CodeRacer::turn_left() +{ + turn_left(_turn_left_for_ms, _drive_left_speed, _drive_right_speed); +} - if (false == _drive_forward) { - // Rechten Motor auf vorwärts stellen - digitalWrite(_motor_rechts_frwd_pin, HIGH); - digitalWrite(_motor_rechts_back_pin, LOW); - // Linken Motor auf vorwärts stellen - digitalWrite(_motor_links_frwd_pin, HIGH); - digitalWrite(_motor_links_back_pin, LOW); - // Motoren beide anschalten - analog_write(_motor_rechts_enable_pin, MOTORRE_MAX_TEMPO); - analog_write(_motor_links_enable_pin, MOTORLI_MAX_TEMPO); - // LEDs setzen - digitalWrite(_led_frwd_pin, HIGH); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); +/** @brief Will turn the racer to the left for the specified time in ms and with the internally stored speed. +* +* The specified duration of time is stored internally and will be used next time by e.g. turn_left() +* @param turn_for_ms duration of time in ms to turn the racer +* @return nothing +*/ +void CodeRacer::turn_left(unsigned long turn_for_ms) +{ + turn_left(turn_for_ms, _drive_left_speed, _drive_right_speed); +} - _drive_forward = true; - _drive_normal_forward = false; - _drive_forward_ms = millis(); +/** @brief Will turn the racer to the left for the specified time in ms and with the specified speed. +* +* The specified duration of time and the specified speeds are stored internally and will be used next time by e.g. turn_left() +* @param turn_for_ms duration of time in ms to turn the racer +* @param left_speed speed for the left side drive +* @param right_speed speed for the right side drive +* @return nothing +*/ +void CodeRacer::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed) +{ + _drive = false; + set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen + set_drives_states_left_right(DRIVEBACK, DRIVEFRWD); + set_drives_speed_left_right(left_speed, right_speed); + // wait set delay for the timed turn + _turn_left_for_ms = turn_for_ms; + delay(_turn_left_for_ms); + // stop drives again + set_drives_stop_left_right(); +} - } else { - if (false == _drive_normal_forward) { - if ((millis() - _drive_forward_ms) > MOTOR_MAX_SPEED_START_MS) { - normal_tempo(); - } - } +/** @brief Will turn the racer to the right for the internally stroe time in ms and with the internally stored speed. +* +* The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to right time can be set by thoose methods as well. +* The method is delayed until the racer has turned. +* @return nothing +*/ +void CodeRacer::turn_right() +{ + turn_right(_turn_right_for_ms, _drive_left_speed, _drive_right_speed); +} + +/** @brief Will turn the racer to the right for the specified time in ms and with the internally stored speed. +* +* The specified duration of time is stored internally and will be used next time by e.g. turn_right() +* @param turn_for_ms duration of time in ms to turn the racer +* @return nothing +*/ +void CodeRacer::turn_right(unsigned long turn_for_ms) +{ + turn_right(turn_for_ms, _drive_left_speed, _drive_right_speed); +} + +/** @brief Will turn the racer to the right for the specified time in ms and with the specified speed. +* +* The specified duration of time and the specified speeds are stored internally and will be used next time by e.g. turn_right() +* @param turn_for_ms duration of time in ms to turn the racer +* @param left_speed speed for the left side drive +* @param right_speed speed for the right side drive +* @return nothing +*/ +void CodeRacer::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed) +{ + _drive = false; + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); // LEDs setzen + set_drives_states_left_right(DRIVEFRWD, DRIVEBACK); + set_drives_speed_left_right(left_speed, right_speed); + // wait set delay for the timed turn + _turn_right_for_ms = turn_for_ms; + delay(_turn_right_for_ms); + // stop drives again + set_drives_stop_left_right(); +} + +/** @brief Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance. +* +* This allow all of the none-single shot ultra sonic measurement methods to stopp the racer in the case the measured distance is smaller than minimal distance. This is just the enablement - you have to call one of the none-single-shot ultra sonic measurement methods continously while driving and maybe sweeping the servo. +* If the racer was stopped can be checked with stopped_at_min_distance() - it will return true in that case. +* The minimal distance can be set by the ultrasonic sensor setter methods. +* There is an example coming with the coderacer libary that you can load and get an idea how that works. +* @return nothing +*/ +void CodeRacer::start_stop_at_min_distance() { + start_stop_at_min_distance(_usonic_stop_distance_cm); +} + +/** @brief Enables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. +* +* This is almos the same as described for start_stop_at_min_distance(). You can specify the distance in cm here - this value will be stored internally and used by start_stop_at_min_distance() next time. +* @param min_distance_cm the minimal disctance in cm +* @return nothing +*/ +void CodeRacer::start_stop_at_min_distance(unsigned long min_distance_cm) { + if (false == _coderacer_stop_at_distance_enabled) { + _coderacer_stopped_at_min_distance = false; + usonic_set_stop_distance_cm(min_distance_cm); + _coderacer_stop_at_distance_enabled = true; } } -void CodeRacer::rueckwaerts() -{ +/** @brief Disables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. +* @return nothing +*/ +void CodeRacer::stop_stop_at_min_distance() { + _coderacer_stop_at_distance_enabled = false; +} - Serial.println("RACER_RUECKWAERTS"); // Meldung am Monitor ausgeben - - if (false == _drive_forward) { - // Rechten Motor auf rückwärts stellen - digitalWrite(_motor_rechts_frwd_pin, LOW); - digitalWrite(_motor_rechts_back_pin, HIGH); - // Linken Motor auf rückwärts stellen - digitalWrite(_motor_links_frwd_pin, LOW); - digitalWrite(_motor_links_back_pin, HIGH); - // Motoren beide anschalten - analog_write(_motor_rechts_enable_pin, MOTORRE_MAX_TEMPO); - analog_write(_motor_links_enable_pin, MOTORLI_MAX_TEMPO); - // LEDs setzen - digitalWrite(_led_frwd_pin, HIGH); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); - - _drive_forward = true; - _drive_normal_forward = false; - _drive_forward_ms = millis(); - - } - else { - if (false == _drive_normal_forward) { - if ((millis() - _drive_forward_ms) > MOTOR_MAX_SPEED_START_MS) { - normal_tempo(); - } +/** @brief This will return if the codracer is in active mode or not. +* +* There is a button used to toogle between active and inactive each time it is pressed This may help you to start driving and scanning the distance by pressing the button - and as well to stop the racer by pressing the button. +* This method will set the LEDs depending on the mode and sets the servo back to center and stopps the racer when leaving the active mode. You can leave or enter the active mode as well by setting using set_active() and set_inactive(). +* The button itself triggers and internall interrupt event and sets the active state - but you have to continously call that method to switch between inactive and active mode depending on the active state. +* If in inactive mode and fun is enabeld by just setting the coderacer_fun_enabled = true ... some fun will happen :-) +* +* @return True if the coderacer is in active mode. False if in inactive mode. +*/ +bool CodeRacer::start_stop() { + if (_coderracer_activ != coderracer_activ) { + _coderracer_activ = coderracer_activ; + if (true == _coderracer_activ) { + set_leds_all_off(); + delay(500); } + else { + stop_driving(); + set_leds_all_on(); + delay(200); + servo_set_to_center(); + _servo_look_around_at_ms = millis() + random(20000, 120000); + } + } + + if ((false == _coderracer_activ) && (true == coderacer_fun_enabled)) { + kitt(); + look_around(); + } + + return(_coderracer_activ); +} + +/** @} */ // end of group higherlevelmeths + /** @defgroup higherlevelgetters Getters and setters + * @{ + */ + +/** @brief Returns true if the racer was stopped at minimum distance. This set to false each time start_stop_at_min_distance() is called. +* @return True if stopped. +*/ +bool CodeRacer::stopped_at_min_distance() { + return(_coderacer_stopped_at_min_distance); +} + +/** @brief Return true if the racer is driving - forward or backward +* @return True if driving forward or backward +*/ +bool CodeRacer::is_driving() { + return(_drive); +} + +/** @brief Returns the duration of time that is internally stored and used for turning the racer left +* @return Time to turn left in ms +*/ +unsigned long CodeRacer::turn_left_for_ms() { + return(_turn_left_for_ms); +} + +/** @brief Returns the duration of time that is internally stored and used for turning the racer left +* @return Time to turn left in ms +*/ +unsigned long CodeRacer::turn_right_for_ms() { + return(_turn_right_for_ms); +} + +/** @brief Sets the coderracer_active state to inactive. If start_stop() is used - the inactive mode will be entered. +* @return nothing +*/ +void CodeRacer::set_inactive() { + coderracer_activ = false; +} + +/** @brief Sets the coderracer_active state to active. If start_stop() is used - the active mode will be entered. +* @return nothing +*/ +void CodeRacer::set_active() { + coderracer_activ = true; +} + +/** @brief Checks if coderracer_activ is set. +* +* coderracer_activ is toggled each time the button is pressed. After power on coderracer_activ is set to False. +* @return True id coderracer_activ is set - False if not. +*/ +bool CodeRacer::is_active() { + return(coderracer_activ); +} + +/** @} */ // end of group higherlevelgetters +/** @} */ // end of group higherlevel + +//************************************** +//*** Just for fun *** +//************************************** +/** @defgroup lowerlevelfun Lower level fun stuff methods +* @{ +*/ +/** @brief Fun stuff - will move the servo around after a random amount of time +* @return nothing +*/ +void CodeRacer::look_around() +{ + if (_servo_look_around_at_ms < millis()) { + _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS); + servo_set_to_left(); + delay(500); + servo_set_to_right(); + delay(800); + servo_set_to_center(); + delay(300); + servo_set_to_left(); + delay(100); + servo_set_to_center(); } } -void CodeRacer::links() +/** @brief Fun stuff - you know Knightrider... +* @return nothing +*/ +void CodeRacer::kitt() { - Serial.println("RACER_LINKS"); // Meldung am Monitor ausgeben - _drive_forward = false; - // LEDs setzen - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_links_pin, HIGH); - digitalWrite(_led_rechts_pin, LOW); - // Rechten Motor auf vorwärts stellen - digitalWrite(_motor_rechts_frwd_pin, HIGH); - digitalWrite(_motor_rechts_back_pin, LOW); - // Linken Motor auf rückwärts stellen - digitalWrite(_motor_links_frwd_pin, LOW); - digitalWrite(_motor_links_back_pin, HIGH); - // Motoren beide anschalten - analog_write(_motor_rechts_enable_pin, MOTORRE_MAX_TEMPO); - analog_write(_motor_links_enable_pin, MOTORLI_MAX_TEMPO); - // Warten bis der RAcer sich gedreht hat - delay(_drehung_links_ms); - // Motoren wieder auschalten - analog_write(_motor_rechts_enable_pin, 0); - analog_write(_motor_links_enable_pin, 0); -} - -void CodeRacer::rechts() -{ - Serial.println("RACER_RECHTS"); // Meldung am Monitor ausgeben - _drive_forward = false; - // LEDs setzen - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_rechts_pin, HIGH); - // Rechten Motor auf rückwärts stellen - digitalWrite(_motor_rechts_frwd_pin, LOW); - digitalWrite(_motor_rechts_back_pin, HIGH); - // Linken Motor auf vorwärts stellen - digitalWrite(_motor_links_frwd_pin, HIGH); - digitalWrite(_motor_links_back_pin, LOW); - // Motoren beide anschalten - analog_write(_motor_rechts_enable_pin, MOTORRE_MAX_TEMPO); - analog_write(_motor_links_enable_pin, MOTORLI_MAX_TEMPO); - // Warten bis der RAcer sich gedreht hat - delay(_drehung_rechts_ms); - // Motoren wieder auschalten - analog_write(_motor_rechts_enable_pin, 0); - analog_write(_motor_links_enable_pin, 0); -} - -void CodeRacer::servo_rechts() -{ - Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben - _schwenk = false; - _servo->write(_servo_rechts); // Servo auf den Winkel rechts drehen - _schwenk_position = _servo_rechts; // Servo schaut nach rechts - delay(1000); // Kurz warten, dass der Servo die Stellung erreicht -} - -void CodeRacer::servo_links() -{ - Serial.println("SERVO_LINKS"); // Meldung am Monitor ausgeben - _schwenk = false; - _servo->write(_servo_links); // Servo auf den Winkel links drehen - _schwenk_position = _servo_links; // Servo schaut nach links - delay(1000); // Kurz warten, dass der Servo die Stellung erreicht -} - -void CodeRacer::servo_mitte() -{ - Serial.println("SERVO_MITTE"); // Meldung am Monitor ausgeben - _schwenk = false; - _servo->write(_servo_mitte); // Servo auf den Winkel links drehen - _schwenk_position = _servo_mitte; // Servo schaut direkt nach vorn - _schwenk_millis = millis(); - delay(1000); // Kurz warten, dass der Servo die Stellung erreicht -} - -void CodeRacer::servo_schwenk() -{ - _schwenk = true; - if (millis() - _schwenk_millis > SERVO_SCHWENK_MS) { - _schwenk_position = _schwenk_position + _schwenk_richtung; - if (_schwenk_position >= _schwenk_links) { - _schwenk_position = _schwenk_links; - _schwenk_richtung = SERVO_SCHWENK_RE; - } - if (_schwenk_position <= _schwenk_rechts) { - _schwenk_position = _schwenk_rechts; - _schwenk_richtung = SERVO_SCHWENK_LI; - } - _servo->write(_schwenk_position); // Servo auf den Winkel links drehen - _schwenk_millis = millis(); - } -} - -void CodeRacer::knight_rider() -{ - if (millis() - _last_ledswitch_ms > LED_SWITCH_MS) { - _last_ledswitch_ms = millis(); + if (millis() - _last_led_switched_at_ms > LED_SWITCH_MS) { + _last_led_switched_at_ms = millis(); if (_last_led_on >= 5) { _led_count = -1; } - if(_last_led_on <= 0) { + else if (_last_led_on <= 0) { _led_count = 1; } _last_led_on = _last_led_on + _led_count; switch (_last_led_on) { case 0: - digitalWrite(_led_links_pin, HIGH); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); + set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); break; case 1: - digitalWrite(_led_links_pin, HIGH); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); + set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); break; case 2: - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_stop_pin, HIGH); - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); + set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF); break; case 3: - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_frwd_pin, HIGH); - digitalWrite(_led_rechts_pin, LOW); + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF); break; case 4: - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_rechts_pin, HIGH); - break; case 5: - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_stop_pin, LOW); - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_rechts_pin, HIGH); + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); break; } } } -long CodeRacer::abstand_messen() +/** @} */ // end of group lowerlevelfun + +//************************************** +//*** Servo drive lower level control *** +//************************************** +/** @defgroup lowerlevelservo Lower level servo drive methods and getters +* @{ +*/ +/** @defgroup lowerlevelservomeths Methods +* @{ +*/ +/** @brief Overwrites the default settings taken from header file by the parameters given to this method +* @param pos_center The postion at which the servo moves to straight forward. Default is 90. Allowed 10 <= pos_center <= 170. +* @param pos_left The postion at which the servo moves to the left. Default is 170. Allowed 10 <= pos_center <= 170. +* @param pos_right The postion at which the servo moves to the right. Default is 10. Allowed 10 <= pos_center <= 170. +* @param sweep_left_pos If the servo is sweeping from left to the right - this defines the most left postion. Default is 140. Allowed 10 <= pos_center <= 170. +* @param sweep_right_pos If the servo is sweeping from left to the right - this defines the most right postion. Default is 40. Allowed 10 <= pos_center <= 170. +* @return nothing +*/ +void CodeRacer::servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos) { - long abstand_cm = 0; - long min_abstand_cm = 1000; - int servo_drehrichtung = 0; - - //Serial.print("ABSTAND_MESSEN. Aktuelle Servo position:"); - //Serial.println(_schwenk_position); - // wenn der Racer nicht fährt, dann wird mehrfach gemessen und der Servo um die aktuelle Positin gedreht ... wenn er faährt oder schwenk aktiv ist , wird einfach nur gemessen - if (((true == _drive_forward) || (true == _drive_normal_forward) || (H_SERVO_MITTE == _schwenk_position) || _schwenk == true)) { - // messen beim fahren ... - //Serial.println("ABSTAND_MESSEN im fahren, direkt nach vorn oder Schwenk() ist aktiv ..."); - min_abstand_cm = abstand_messen_intern(); - } else { - // messen im Stand und ohne schwenk ... - //Serial.println("ABSTAND_MESSEN im Stand nach links oder rechts..."); - // sind wir links oder rechts ? - if (H_SERVO_LINKS == _schwenk_position) { - //Serial.println("ABSTAND_MESSEN. Linke Seite."); - //links ... - servo_drehrichtung = SERVO_SCHWENK_RE; - } - if (H_SERVO_RECHTS == _schwenk_position) { - //rechts ... - //Serial.println("ABSTAND_MESSEN rechte Seite."); - servo_drehrichtung = SERVO_SCHWENK_LI; - } - // drehen und messen ... kleinsten Wert merken - do { - _schwenk_position = _schwenk_position + servo_drehrichtung; - _servo->write(_schwenk_position); - //Serial.print("ABSTAND_MESSEN. Servo position:"); - //Serial.println(_schwenk_position); - delay(50); - abstand_cm = abstand_messen_intern(); - if (abstand_cm < min_abstand_cm) { - min_abstand_cm = abstand_cm; - } - } while ((_schwenk_position > H_SERVO_MITTE_LINKS) || (_schwenk_position < H_SERVO_MITTE_RECHTS)); - } - - Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):"); - Serial.println(min_abstand_cm); - _min_abstand_cm = min_abstand_cm; - - return(min_abstand_cm); + servo_center_pos = pos_center; + servo_left_pos = pos_left; + servo_right_pos = pos_right; + servo_sweep_left_pos = sweep_left_pos; + servo_sweep_right_pos = sweep_right_pos; } -long CodeRacer::abstand_messen_intern() +/** @brief Turns sweeping of the servo from left to right and back on. +* +* The sweeping range is defind by #servo_sweep_left_pos and #servo_sweep_right_pos attributes. Both can be set by either servo_settings() or as public members. +* Every time servo_sweep() is called the servo is driven by 5 steps until either #servo_sweep_left_pos or #servo_sweep_right_pos is reached. Then it will turn the +* direction and step to the other side every time this method is called. +* @return nothing +*/ +void CodeRacer::servo_sweep() { - long abstand_cm; - long long echo_dauer_us[3] = { 0,0,0 }; - int messnr = 0; + uint8_t position; + _servo_sweep = true; + if (millis() - _servo_position_set_at_ms > SERVO_SWEEP_MS) { + position = _servo_position + _servo_sweep_step; + //sprintf(_debugmsg,"[%s] current position=%ld newpostion=%ld", __func__, _servo_position, position); + if ((position >= servo_sweep_left_pos) || (position >= SERVO_MAX_POSITION)) { + position = servo_sweep_left_pos; + _servo_sweep_step = SERVO_SWEEP_TO_RIGHT_STEP; + } + if ((position <= servo_sweep_right_pos) || (position <= SERVO_MIN_POSITION)) { + position = servo_sweep_right_pos; + _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP; + } + _servo_set_position(position); + } +} - do{ - // Messung starten - ein kurzer Pulse "HIGH" wird zum TRIG pin des Ultraschallsensors geschickt +/** @brief Drives the servo to the postion that is defined by #servo_right_pos +* @return nothing +*/ +void CodeRacer::servo_set_to_right() +{ + servo_set_position_wait(servo_right_pos); +} + +/** @brief Drives the servo to the postion that is defined by #servo_left_pos +* @return nothing +*/ +void CodeRacer::servo_set_to_left() +{ + servo_set_position_wait(servo_left_pos); +} + +/** @brief Drives the servo to the postion that is defined by #servo_center_pos +* @return nothing +*/ +void CodeRacer::servo_set_to_center() +{ + servo_set_position_wait(servo_center_pos); +} + +/** @brief Drive the servo to the postion given to this method +* +* The method will wait until the servo has reached its new position. +* @param position Position the servo will be drived to. Allowed are values 10<=postion<=170. 10 is at the right hand side, 170 at the left hand side. +* @return The new servo position +*/ +uint8_t CodeRacer::servo_set_position_wait(uint8_t position) +{ + _servo_sweep = false; + unsigned long wait_time_ms = _servo_set_position(position); + delay(wait_time_ms); + return(_servo_position); +} + +/** @brief Drive the servo to the postion given to this method +* +* The method will not wait until the servo has reached its new position. +* @param position Position the servo will be drived to. Allowed are values 10<=postion<=170. 10 is at the right hand side, 170 at the left hand side. +* @return The time in ms the servo will need to reach the new position +*/ +unsigned long CodeRacer::servo_set_position(uint8_t position) +{ + _servo_sweep = false; + unsigned long wait_time_ms = _servo_set_position(position); + return(wait_time_ms); +} + +unsigned long CodeRacer::_servo_set_position(uint8_t position) +{ + uint8_t _position = position; + uint8_t absdiff; + + if (position < SERVO_MIN_POSITION) { + _position = SERVO_MIN_POSITION; + } + else if (position > SERVO_MAX_POSITION) { + _position = SERVO_MAX_POSITION; + } + _servo->write(_position); + // wait minimal delay to avoid code collaps + delay(SERVO_SET_1TICK_POSITION_DELAY_MS); + absdiff = abs(_servo_position - _position); + if (absdiff > 1) { + _servo_position_eta_in_ms = absdiff * SERVO_SET_1TICK_POSITION_DELAY_MS; + } + else { + _servo_position_eta_in_ms = 0; + } + + _servo_position_set_at_ms = millis(); + _servo_position = _position; + + return(_servo_position_eta_in_ms); +} + +/** @} */ // end of group lowerlevelservomeths +/** @defgroup lowerlevelservogetters Getters +* @{ +*/ + +/** @brief Get the actual position of the servo +* @return Actual position of the servo +*/ +uint8_t CodeRacer::servo_position() { + return(_servo_position); +} + +/** @brief Get the system time in ms the servo was set to the actual position +* @return System time in ms the servo was set +*/ +unsigned long CodeRacer::servo_position_set_at_ms() { + return(_servo_position_set_at_ms); +} + +/** @brief Get the system time in ms the servo will reach its position +* This is an estimated time. +* If this is a time in the future, the servo may still moving. +* If this is a time in the past , the servo should have reached its postion already. +* @return System time in ms the servo will reach its position +*/ +unsigned long CodeRacer::servo_position_eta_in_ms() { + return(_servo_position_eta_in_ms); +} + +/** @} */ // end of group lowerlevelservogetters +/** @} */ // end of group lowerlevelservo + + +//************************************** +//*** Ultrasonic lower level control *** +//************************************** +/** @defgroup lowerlevelus Lower level ultra sonic methods and getters +* @{ +*/ +/** @defgroup lowerlevelusmeths Methods +* @{ +*/ + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is the medium one out of 3 measurements. The maximum measured distance is about 100cm and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_cm() +{ + return(usonic_measure_cm(US_MAX_ECHO_TIME_US)); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is the medium one out of 3 measurements. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_us() + { + return(usonic_measure_us(US_MAX_ECHO_TIME_US)); + } + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is the medium one out of 3 measurements. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time and by that the maximum of distance that can be measured. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_cm(unsigned long max_echo_run_time_us) +{ + unsigned long echo_runtime_us = usonic_measure_us(max_echo_run_time_us); + unsigned long distance_cm = echo_runtime_us * 0.0172; + //Serial.print("MEASURE_DISTANCE. Distance in cm is: "); + //Serial.println(distance_cm); + _usonic_distance_cm = distance_cm; + return(distance_cm); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is the medium one out of 3 measurements. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_us(unsigned long max_echo_run_time_us) +{ + unsigned long echo_runtime_us[3] = { 0,0,0 }; + uint8_t measnr = 0; + + do { + echo_runtime_us[measnr] = usonic_measure_single_shot_us(max_echo_run_time_us); + if (echo_runtime_us[measnr] > 200) { + measnr++; + } + } while (measnr < 3); + + // we will take the medium out of 3 values ... + if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); } + if (echo_runtime_us[1] > echo_runtime_us[2]) { std::swap(echo_runtime_us[1], echo_runtime_us[2]); } + if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); } + + //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: "); + //Serial.println(echo_runtime_us[1]); + + // if the stop at minimal distance is enabeled - check for minimal distance is reached + if (true == _coderacer_stop_at_distance_enabled) { + if (echo_runtime_us[1] <= _usonic_stop_distance_us) { + _coderacer_stopped_at_min_distance = true; + stop_driving(); + _coderacer_stop_at_distance_enabled = false; + } + } + _usonic_distance_us = echo_runtime_us[1]; + return(echo_runtime_us[1]); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_cm() +{ + return(usonic_measure_single_shot_cm(US_MAX_ECHO_TIME_US)); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_us() +{ + return(usonic_measure_single_shot_us(US_MAX_ECHO_TIME_US)); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is a one shot measurement. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us) +{ + // convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec + // the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one + // distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172 + // distance_cm = (echo_duration/2) / 29.1; + unsigned long echo_runtime_us = usonic_measure_single_shot_us(max_echo_run_time_us); + unsigned long distance_cm = echo_runtime_us * 0.0172; + //Serial.print("MEASURE_DISTANCE. Distance in cm is: "); + //Serial.println(distance_cm); + _usonic_distance_cm = distance_cm; + return(distance_cm); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is a one shot measurement. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_us(unsigned long max_echo_run_time_us) + { + unsigned long echo_runtime_us; + // start measurement - send a short pulse "HIGH" to the TRIG pin of the ultrasonic sensor pinMode(_us_echo_pin, OUTPUT); pinMode(_us_echo_pin, INPUT); digitalWrite(_us_trigger_pin, LOW); @@ -498,92 +799,404 @@ long CodeRacer::abstand_messen_intern() digitalWrite(_us_trigger_pin, HIGH); delayMicroseconds(10); digitalWrite(_us_trigger_pin, LOW); - - // Messung der Dauer in Mikrosekundenmeasure bis das ECHO Pin vom Ultraschallsensor HIGH wird - echo_dauer_us[messnr] = pulseIn(_us_echo_pin, HIGH, US_MAX_ECHO_TIME_US); - if (echo_dauer_us[messnr] == 0) { - echo_dauer_us[messnr] = US_MAX_ECHO_TIME_US; - messnr++; - } else { - if (echo_dauer_us[messnr] > 200) { - messnr++; - } + // measure runtime in microseconds until the ECHO pin aof the sensor goes HIGH + echo_runtime_us = pulseInLong(_us_echo_pin, HIGH, max_echo_run_time_us); + if (echo_runtime_us == 0) { + echo_runtime_us = max_echo_run_time_us; // US_MAX_ECHO_TIME_US; } - } while (messnr < 3); + //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: "); + //Serial.println(echo_runtime_us); + _usonic_distance_us = echo_runtime_us; + return(echo_runtime_us); + } - // the largest and the smallest values will be ignored ... - if (echo_dauer_us[0] > echo_dauer_us[1]) - { - std::swap(echo_dauer_us[0], echo_dauer_us[1]); +/** @} */ // end of group lowerlevelusmethods +/** @defgroup lowerlevelusgetters Setters and getters +* @{ +*/ + +/** @brief Sets the stop distance in cm. +* +* If start_stop_at_min_distance() is used and distance measured with one of the measurement methods - the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. +* Internally the stop distance will be set as both - in cm and in microseconds. +* @param stop_distance_cm Distance in cm the racer will be stopped if that features was enabled by start_stop_at_min_distance() before. +* @return nothing +*/ +void CodeRacer::usonic_set_stop_distance_cm(unsigned long stop_distance_cm) +{ + _usonic_stop_distance_us = stop_distance_cm * 58.14; +} + +/** @brief Sets the stop distance in cm. +* +* If start_stop_at_min_distance() is used and distance measured with one of the measurement methods - the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. +* Internally the stop distance will be set as both - in cm and in microseconds. +* @param stop_distance_us Distance in cm the racer will be stopped if that features was enabled by start_stop_at_min_distance() before. +* @return nothing +*/ +void CodeRacer::usonic_set_stop_distance_us(unsigned long stop_distance_us) +{ + _usonic_stop_distance_us = stop_distance_us; +} + +/** @brief Returns the last measured distance in microseconds +* @return Distance in microseconds +*/ +unsigned long CodeRacer::usonic_distance_us() { + return(_usonic_distance_us); +} + +/** @brief Returns the last measured distance in cm +* @return Distance in cm +*/ +unsigned long CodeRacer::usonic_distance_cm() { + return(_usonic_distance_cm); +} + +/** @} */ // end of group lowerlevelusgetters +/** @} */ // end of group lowerlevelus + + +//************************************** +//*** Drives lower level control *** +//************************************** + +/** @defgroup lowerleveldrives Lower level drives methods and getters +* @{ +*/ +/** @defgroup lowerleveldrivesmeths Methods +* @{ +*/ + +/** @brief Overwrites some drive settings. This will replace the defaults set by the values in the header file. +* @param drive_left_speed Speed of the left side drive +* @param drive_right_speed Speed of the right side drive +* @param turn_left_for_ms Time in ms the racer will turn to the left around its center if turn_left() is called +* @param turn_right_for_ms Time in ms the racer will turn to the right around its center if turn_right() is called +* @return nothing +*/ +void CodeRacer::drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_for_ms, unsigned long turn_right_for_ms) +{ + _drive_left_speed = drive_left_speed; + _drive_right_speed = drive_right_speed; + _turn_left_for_ms = turn_left_for_ms; + _turn_right_for_ms = turn_right_for_ms; +} + +/** @brief Stopps both drives +* @return nothing +*/ +void CodeRacer::set_drives_stop_left_right() { + set_drive_left_state(DRIVESTOP); + set_drive_right_state(DRIVESTOP); +} + +/** @brief Sets both of the drives to a specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param stateleft drivestate to set for the left side drive +* @param stateright drivestate to set for the right side drive +* @return nothing +*/ +void CodeRacer::set_drives_states_left_right(drivestate stateleft, drivestate stateright) { + set_drive_left_state(stateleft); + set_drive_right_state(stateright); +} + +/** @brief Sets the left side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param state drivestate to set for the left side drive +* @return nothing +*/ +void CodeRacer::set_drive_left_state(drivestate state) { + set_drive_state(state, _drive_left_frwd_pin, _drive_left_back_pin); +} + +/** @brief Sets the right side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param state drivestate to set for the right side drive +* @return nothing +*/ +void CodeRacer::set_drive_right_state(drivestate state) { + set_drive_state(state, _drive_right_frwd_pin, _drive_right_back_pin); +} + +/** @brief Sets the specified drivestate for the drive connected to the sepecified pins (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param state drivestate to set for the connected drive +* @param frwdpin Pin the forward signal of the drive device driver is connected at +* @param backpin Pin the backward signal of the drive device driver is connected at +* @return nothing +*/ +void CodeRacer::set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin) { + switch (state) { + case DRIVESTOP: + digitalWrite(frwdpin, LOW); + digitalWrite(backpin, LOW); + break; + case DRIVEFRWD: + digitalWrite(frwdpin, HIGH); + digitalWrite(backpin, LOW); + break; + case DRIVEBACK: + digitalWrite(frwdpin, LOW); + digitalWrite(backpin, HIGH); + break; } - if (echo_dauer_us[1] > echo_dauer_us[2]) - { - std::swap(echo_dauer_us[1],echo_dauer_us[2]); +} + +/** @brief Sets the speed for both of the drives. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speedleft speed of the left side drive. 0<=speed<=255 +* @param speedright speed of the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright) { + set_drive_left_speed(speedleft); + set_drive_right_speed(speedright); +} + +/** @brief Sets the speed for the left side drive. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speed speed of the left side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::set_drive_left_speed(uint8_t speed) { + set_drive_speed(speed, _drive_left_enable_pin); +} + +/** @brief Sets the speed for the right side drive. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speed speed of the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::set_drive_right_speed(uint8_t speed) { + set_drive_speed(speed, _drive_right_enable_pin); +} + +/** @brief Sets the speed for the drive of the enable pin connected to the specified pin. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speed speed of the drive. 0<=speed<=255 +* @param enablepin Pin the drives device driver enable pin is connected at +* @return nothing +*/ +void CodeRacer::set_drive_speed(uint8_t speed, uint8_t enablepin) { + _analog_write(enablepin, (int)speed); +} + +/** @} */ // end of group lowerleveldrivesmethods +/** @defgroup lowerleveldrivesgetters Getters +* @{ +*/ + +/** @brief Get the setting for the speed of the right side drive +* @return Speed of the right side drive +*/ +uint8_t CodeRacer::drive_right_speed() { + return _drive_right_speed; +} + +/** @brief Get the setting for the speed of the left side drive +* @return Speed of the left side drive +*/ +uint8_t CodeRacer::drive_left_speed() { + return(_drive_left_speed); +} + +void CodeRacer::_analog_write(uint8_t pin, uint8_t speed) { + if (pin == _drive_left_enable_pin) { + _drive_left_speed = speed; + ledcWrite(DRIVE_PWM_LEFT_CHANNEL, speed); } - if (echo_dauer_us[0] > echo_dauer_us[1]) - { - std::swap(echo_dauer_us[0], echo_dauer_us[1]); + if (pin == _drive_right_enable_pin) { + _drive_right_speed = speed; + ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed); } - // convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec - // the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one - // distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172 - // distance_cm = (echo_duration/2) / 29.1; - abstand_cm = echo_dauer_us[1] * 0.0172; +} + +/** @} */ // end of group lowerleveldrivesgetters +/** @} */ // end of group lowerleveldrives + + +//************************************** +//*** LED lower level control *** +//************************************** +/** @defgroup lowerlevelled Lower level LED methods +* @{ +*/ +/** @defgroup lowerlevelledmeths Methods +* @{ +*/ + +/** @brief Sets all of the 4 LEDs to a ledstate (LEDON, LEDOFF) +* @param leftled set state of status left LED (most left yellow led) +* @param stopled set state of status stop LED (red led) +* @param frwdled set state of status forward LED (green or blue led) +* @param rightled set state of status right LED (most right yellow led) +* @return nothing +*/ +void CodeRacer::set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled) { + digitalWrite(_led_left_pin, leftled); + digitalWrite(_led_frwd_pin, frwdled); + digitalWrite(_led_right_pin, rightled); + digitalWrite(_led_stop_pin, stopled); +} + +/** @brief Sets all of the 4 LEDs to the same ledstate (LEDON, LEDOFF) +* @param alleds set state to all status LEDs +* @return nothing +*/ +void CodeRacer::set_leds_all(ledstate alleds) { + digitalWrite(_led_left_pin, alleds); + digitalWrite(_led_frwd_pin, alleds); + digitalWrite(_led_right_pin, alleds); + digitalWrite(_led_stop_pin, alleds); +} + +/** @brief Sets all of the 4 LEDs to the ledstate LEDOFF +* @return nothing +*/ +void CodeRacer::set_leds_all_off() { + set_leds_all(LEDOFF); +} + +/** @brief Sets all of the 4 LEDs to the ledstate LEDON +* @return nothing +*/ +void CodeRacer::set_leds_all_on() { + set_leds_all(LEDON); +} + +/** @} */ // end of group lowerlevelledmets +/** @} */ // end of group lowerlevelled + + +//************************************** +//*** ISRs *** +//************************************** +//IRAM_ATTR is used to load the code into DRAM and not to Flash to make it faster - required for ISRs +void IRAM_ATTR CodeRacer::_set_button_state() { + if ((millis() - button_last_pressed_at_ms) > BUTTON_BOUNCING_TIME_MS) { + button_last_pressed_at_ms = millis(); // simplest debouncing - just wait ;-) + coderracer_activ = !coderracer_activ; + } +} + + +//********************************************************************************************************************** +//** Methods below this are obsolete and only in here for compatiblity to other projects - do not use them anymore !!! +//********************************************************************************************************************** +void CodeRacer::motor_einstellungen(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_for_ms, unsigned long turn_right_for_ms) +{ + drives_settings(drive_left_speed, drive_right_speed, turn_left_for_ms, turn_right_for_ms); +} + +void CodeRacer::servo_einstellungen(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos) +{ + servo_settings(pos_center, pos_left, pos_right, sweep_left_pos, sweep_right_pos); +} + +void CodeRacer::servo_rechts() +{ + Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben + servo_set_to_right(); // Servo auf den Winkel rechts drehen +} + +void CodeRacer::servo_links() +{ + Serial.println("SERVO_LINKS"); // Meldung am Monitor ausgeben + servo_set_to_left(); // Servo auf den Winkel links drehen +} + +void CodeRacer::servo_mitte() +{ + Serial.println("SERVO_MITTE"); + servo_set_to_center(); +} + +void CodeRacer::servo_schwenk() +{ + servo_sweep(); +} + +void CodeRacer::links() +{ + Serial.println("CODERACER_LINKS"); + turn_left(); +} + +void CodeRacer::rechts() +{ + Serial.println("CODERACER_RECHTS"); + turn_right(); +} + +void CodeRacer::anhalten() +{ + Serial.println("CODERACER_ANHALTEN"); + stop_driving(); +} + +void CodeRacer::vorwaerts() +{ + Serial.println("CODERACER_VORWAERTS"); + drive_forward(); +} + +void CodeRacer::rueckwaerts() +{ + Serial.println("CODERACER_RUECKWAERTS"); + drive_backward(); +} + +unsigned long CodeRacer::abstand_messen() +{ + return(0); - //Messwert am Monitor anzeigen - //Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):"); - //Serial.println(abstand_cm); + unsigned long distance_cm = 0; + unsigned long min_distance_cm = 1000; + int8_t servo_turn_direction = 0; - return(abstand_cm); -} -bool CodeRacer::start_stop() { - if (_coderracer_activ != coderracer_activ) { - _coderracer_activ = coderracer_activ; - if (true == _coderracer_activ) { - digitalWrite(_led_links_pin, LOW); - digitalWrite(_led_frwd_pin, LOW); - digitalWrite(_led_rechts_pin, LOW); - digitalWrite(_led_stop_pin, LOW); - servo_rechts(); - servo_links(); - servo_mitte(); - delay(500); + // while driving or sweeping there will be only one value be measured - else there will be mutiple measurements and the servor will be turning + if (((true == _drive) || (servo_center_pos == _servo_position) || _servo_sweep == true)) { + // while driving ... + //Serial.println("ABSTAND_MESSEN im fahren, direkt nach vorn oder Schwenk() ist aktiv ..."); + min_distance_cm = usonic_measure_cm(); + } else { + // no sweep, not driving ... + //Serial.println("ABSTAND_MESSEN im Stand nach links oder rechts..."); + // are we already ath left or right with the servo ? + if (servo_left_pos == _servo_position) { + //Serial.println("ABSTAND_MESSEN. Linke Seite."); + //left ... + servo_turn_direction = SERVO_SWEEP_TO_RIGHT_STEP; } - else { - anhalten(); - servo_mitte(); - _servo_look_around_ms = millis() + random(5000, 120000); + if (servo_right_pos == _servo_position) { + //right ... + //Serial.println("ABSTAND_MESSEN rechte Seite."); + servo_turn_direction = SERVO_SWEEP_TO_LEFT_STEP; } + // trun the servo and do measuring ... remember the smallest value + do { + _servo_set_position(_servo_position + servo_turn_direction); + //Serial.print("ABSTAND_MESSEN. Servo position:"); + //Serial.println(_servo_position); + distance_cm = usonic_measure_cm(); + if (distance_cm < min_distance_cm) { + min_distance_cm = distance_cm; + } + } while ((_servo_position > H_SERVO_CENTER_LEFT) || (_servo_position < H_SERVO_CENTER_RIGHT)); } - if (false == _coderracer_activ) { - knight_rider(); - if (_servo_look_around_ms < millis()) { - _servo_look_around_ms = millis() + random(5000, 120000); - servo_links(); - delay(500); - servo_rechts(); - delay(800); - servo_mitte(); - delay(300); - servo_links(); - delay(100); - servo_mitte(); - } - } - - return(_coderracer_activ); + Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):"); + Serial.println(min_distance_cm); + //_min_distance_cm = min_distance_cm; + + return(min_distance_cm); + } -void IRAM_ATTR CodeRacer::set_taster_state() { - if ((millis() - taster_last_pressed_ms) > 200) { - taster_last_pressed_ms = millis(); - if (false == coderracer_activ) { - coderracer_activ = true; - } - else { - coderracer_activ = false; - } - } -} +//********************************************************************************************************************** +//** Helper methods +//********************************************************************************************************************** + diff --git a/Arduino/libraries/CodeRacer/CodeRacer.h b/Arduino/libraries/CodeRacer/CodeRacer.h index 633be30..a690f08 100644 --- a/Arduino/libraries/CodeRacer/CodeRacer.h +++ b/Arduino/libraries/CodeRacer/CodeRacer.h @@ -1,141 +1,241 @@ #include "Arduino.h" -#include //// std::swap -#include -#include "esp32-hal-ledc.h" +#include // std::swap +#include // Servo drive support for ESP32 +#include "esp32-hal-ledc.h" // Part of ESP32 board files - Analog output #ifndef __CodeRacer_H__ #define __CodeRacer_H__ -//----- Taster ------------ -#define H_TASTERPIN 17 +//----- Fun stuff --------- +#define FUN_MIN_PAUSE_MS 120000 // minimum and maximum pause between to rounds fun +#define FUN_MAX_PAUSE_MS 300000 +#define LED_SWITCH_MS 50 // speed of knight rider lights +//----- Button ------------ +#define H_BUTTON_PIN 17 +#define BUTTON_BOUNCING_TIME_MS 200 // bouncing delay //----- Servo ----- -#define H_SERVOPIN 16 // Pin an dem der Servomotor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_SERVO_LINKS 145 // Wert um den Servo 45 Grad nach links zu drehen ... der kann je nach Servo anders sein -#define H_SERVO_MITTE_LINKS 100 // Bis hier geht die Entfernungsmessung im Stand links -#define H_SERVO_RECHTS 35 // Wert um den Servo 45 Grad nach rechtss zu drehen ... der kann je nach Servo anders sein -#define H_SERVO_MITTE_RECHTS 80 // Bis hier geht die Entfernungsmessung im Stand rechts -#define H_SERVO_MITTE 90 // Wert um den Servo in die Mitte zu drehen ... der kann je nach Servo anders sein -#define H_SERVO_SCHWENK_LINKS 140 -#define H_SERVO_SCHWENK_RECHTS 40 +#define H_SERVO_PIN 16 +#define H_SERVO_LEFT_POS 145 // left position of the servo +#define H_SERVO_CENTER_LEFT 100 // left-center position of the servo +#define H_SERVO_RIGHT_POS 35 // right position of the servo +#define H_SERVO_CENTER_RIGHT 80 // right-center position of the servo +#define H_SERVO_CENTER_POS 90 // center position of the servo +#define H_SERVO_SWEEP_LEFT_POS 140 // most left sweep position of the servo +#define H_SERVO_SWEEP_RIGHT_POS 40 // most right sweep position of the servo +#define SERVO_SWEEP_TO_LEFT_STEP 5 // sweep step to the left +#define SERVO_SWEEP_TO_RIGHT_STEP -5 // sweep step to the right +#define SERVO_SWEEP_MS 10 // duration of time betwee to sweep steps +#define SERVO_MAX_POSITION 170 // maximum servo position +#define SERVO_MIN_POSITION 10 // minimum servo position +#define SERVO_SET_1TICK_POSITION_DELAY_MS 3 // minimum duration of time between two servo steps -#define SERVO_SCHWENK_LI 5 -#define SERVO_SCHWENK_RE -5 -#define SERVO_SCHWENK_MS 10 +//----- Ultrasonic sensor ----- +#define H_US_TRIG_PIN 12 +#define H_US_ECHO_PIN 14 +#define H_US_STOP_DISTANCE_CM 25 // if the measured distance is smaller the racer maybe stopped +#define US_MAX_ECHO_TIME_US 6000 // timeout for ultrasonic sensor measurements - this is about 100cm -//----- Ultraschallsensor ----- -#define H_US_TRIG 12 // Pin an dem der TRIG Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_US_ECHO 14 // Pin an dem der ECHO Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_US_STOP_ABSTAND_CM 5 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an -#define US_MAX_ECHO_TIME_US 6000 // Wenn die Zeit für das Echo länger dauert als diese Zeit, ist der Racer weit genug weg und wir müssen nicht weiter warten. +//----- Drives ----- +#define H_DRIVE_RIGHT_SPEED 255 // default speed of right side drive. 0 ...255 +#define H_DRIVE_LEFT_SPEED 255 // default speed of left side drive. 0 ...255 +#define H_DRIVE_RIGHT_ENABLE_PIN 2 +#define H_DRIVE_RIGHT_FWRD_PIN 4 +#define H_DRIVE_RIGHT_BACK_PIN 15 +#define H_DRIVE_LEFT_ENABLE_PIN 21 +#define H_DRIVE_LEFT_FWRD_PIN 22 +#define H_DRIVE_LEFT_BACK_PIN 23 +#define H_RACER_TURN_LEFT_FOR_MS 400 // duration of time the racer will turn to left +#define H_RACER_TURN_RIGHT_FOR_MS 400 // duration of time the racer will turn to right -//----- Motoren ----- -#define H_MOTORRE_TEMPO 215 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255 -#define H_MOTORLI_TEMPO 212 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255 -#define H_MOTORRE_SPEED 2 // Pin an dem der SPEED/ENABLE Pin des rechten Motors angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_MOTORRE_FWRD 4 // Pin an dem der FORWÄRTS Pin des rechten Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_MOTORRE_BACK 15 // Pin an dem der RÜCKWÄRTS Pin des rechten Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_MOTORLI_SPEED 21 // Pin an dem der SPEED/ENABLE Pin des linken Motors angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_MOTORLI_FWRD 22 // Pin an dem der FORWÄRTS Pin des linken Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_MOTORLI_BACK 23 // Pin an dem der RÜCKWÄRTS Pin des linken Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_RACER_LINKS_MS 200 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach links zu drehen -#define H_RACER_RECHTS_MS 200 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach rechts zu drehen +#define DRIVE_PWM_LEFT_CHANNEL 5 // PWM-channel for left side drive +#define DRIVE_PWM_RIGHT_CHANNEL 6 // PWM-channel for right side drive -#define MOTORPWM_LINKS 5 // PWM-Kanal für linken Motor -#define MOTORPWM_RECHTS 6 // PWM-Kanal für rechten Motor -#define MOTORRE_MAX_TEMPO 244 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255 -#define MOTORLI_MAX_TEMPO 240 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255 +//----- LEDs ----- +#define H_LED_FRWD_PIN 26 +#define H_LED_STOP_PIN 25 +#define H_LED_LEFT_PIN 33 +#define H_LED_RIGHT_PIN 27 -#define MOTOR_MAX_SPEED_START_MS 10 +static volatile bool coderracer_activ = false;; +static volatile unsigned long button_last_pressed_at_ms = millis(); -//----- Werte für die LEDs ----- -#define H_LED_VORWAERTS 26 // Pin an dem die VORWÄRTS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_LED_STOP 25 // Pin an dem die STOP LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_LED_LINKS 33 // Pin an dem die LINKS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. -#define H_LED_RECHTS 27 // Pin an dem die RECHTS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88. +enum ledstate { + LEDOFF, + LEDON +}; -#define LED_SWITCH_MS 50 - -static volatile bool coderracer_activ; -static volatile unsigned long taster_last_pressed_ms; +enum drivestate { + DRIVESTOP, + DRIVEFRWD, + DRIVEBACK +}; //--- this is as preparation of the class creation class CodeRacer { private: - int _taster_pin; - int _servopin; - int _us_trigger_pin; - int _us_echo_pin; - int _motor_links_frwd_pin; - int _motor_links_back_pin; - int _motor_links_enable_pin; - int _motor_rechts_frwd_pin; - int _motor_rechts_back_pin; - int _motor_rechts_enable_pin; - int _led_frwd_pin; - int _led_stop_pin; - int _led_links_pin; - int _led_rechts_pin; - int _servo_mitte; - int _servo_links; - int _servo_rechts; - int _schwenk_links; - int _schwenk_rechts; + //pins + uint8_t _button_pin; + uint8_t _servo_pin; + uint8_t _us_trigger_pin; + uint8_t _us_echo_pin; + uint8_t _drive_left_frwd_pin; + uint8_t _drive_left_back_pin; + uint8_t _drive_left_enable_pin; + uint8_t _drive_right_frwd_pin; + uint8_t _drive_right_back_pin; + uint8_t _drive_right_enable_pin; + uint8_t _led_frwd_pin; + uint8_t _led_stop_pin; + uint8_t _led_left_pin; + uint8_t _led_right_pin; - int _schwenk_position; - int _schwenk_richtung; - long _schwenk_millis; + //servo variables + int8_t _servo_sweep_step; + uint8_t _servo_position; + unsigned long _servo_position_set_at_ms; + unsigned long _servo_position_eta_in_ms; - int _motor_links_tempo; - int _motor_rechts_tempo; - int _drehung_links_ms; - int _drehung_rechts_ms; + //drives variables + uint8_t _drive_left_speed; + uint8_t _drive_right_speed; + unsigned long _turn_left_for_ms; + unsigned long _turn_right_for_ms; - bool _drive_forward; - long _drive_forward_ms; - bool _drive_normal_forward; - bool _schwenk; + // ultrasonic variables + bool _coderacer_stopped_at_min_distance; + bool _coderacer_stop_at_distance_enabled; + unsigned long _usonic_stop_distance_cm; + unsigned long _usonic_stop_distance_us; + unsigned long _usonic_distance_us; + unsigned long _usonic_distance_cm; - long _min_abstand_cm; + //fun stuff variables + unsigned long _last_led_switched_at_ms; + uint8_t _led_count; + uint8_t _last_led_on; + unsigned long _servo_look_around_at_ms; - static void set_taster_state(); + unsigned long _min_distance_cm; + bool _drive; + unsigned long _drive_set_at_ms; + bool _servo_sweep; + bool _coderracer_activ; + //objects Servo* _servo; Servo* _servo_dummy; - void analog_write(int pin, int speed); - int _coderracer_activ; - - long abstand_messen_intern(); - - long _last_ledswitch_ms; - int _led_count; - int _last_led_on; - - long _servo_look_around_ms; + static void _set_button_state(); + void _analog_write(uint8_t pin, uint8_t speed); + unsigned long _servo_set_position(uint8_t position); public: + //properties + bool coderacer_fun_enabled; + uint8_t servo_center_pos; /**< The position the servo is looking straight forward. Default is 90 . Allowed are values 10<=pos<=170 */ + uint8_t servo_left_pos; /**< The position the servo is looking to the left. Default is 170 . Allowed are values 10<=pos<=170 */ + uint8_t servo_right_pos; /**< The position the servo is looking to the right. Default is 0 . Allowed are values 10<=pos<=170 */ + uint8_t servo_sweep_left_pos; /**< When the servo is sweeping this is the left most position */ + uint8_t servo_sweep_right_pos; /**< When the servo is sweeping this is the right most position */ + //methods CodeRacer(); - CodeRacer(int tasterpin, int servopin, - int us_trigger_pin, int us_echo_pin, - int motor_links_frwd_pin, int motor_links_back_pin, int motor_links_enable_pin, - int motor_rechts_frwd_pin, int motor_rechts_back_pin, int motor_rechts_enable_pin, - int led_frwd, int led_stop, int led_links, int led_rechts - ); + CodeRacer(uint8_t button_pin, uint8_t servo_pin, + uint8_t us_trigger_pin, uint8_t us_echo_pin, + uint8_t drive_left_frwd_pin, uint8_t drive_left_back_pin, uint8_t drive_left_enable_pin, + uint8_t drive_right_frwd_pin, uint8_t drive_right_back_pin, uint8_t drive_right_enable_pin, + uint8_t led_frwd_pin, uint8_t led_stop_pin, uint8_t led_left_pin, uint8_t led_right_pin); + void set_inactive(); + void set_active(); void begin(); - void servo_einstellungen(int winkel_mitte, int winkel_links, int winkel_rechts, int schwenk_links, int schwenk_rechts); - void motor_einstellungen(int motor_links_tempo, int motor_rechts_tempo, int drehung_links_ms, int drehung_rechts_ms); + // getters + bool is_active(); + bool is_driving(); + bool stopped_at_min_distance(); + unsigned long usonic_distance_cm(); + unsigned long usonic_distance_us(); + uint8_t servo_position(); + unsigned long servo_position_set_at_ms(); + unsigned long servo_position_eta_in_ms(); + uint8_t drive_left_speed(); + uint8_t drive_right_speed(); + unsigned long turn_left_for_ms(); + unsigned long turn_right_for_ms(); + // higher level {code}racer services + void stop_driving(); + void drive_forward(); + void drive_forward(uint8_t left_speed, uint8_t right_speed); + void drive_backward(); + void drive_backward(uint8_t left_speed, uint8_t right_speed); + void turn_left(); + void turn_left(unsigned long turn_for_ms); + void turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed); + void turn_right(); + void turn_right(unsigned long turn_for_ms); + void turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed); + + void start_stop_at_min_distance(); + void start_stop_at_min_distance(unsigned long min_distance_cm); + void stop_stop_at_min_distance(); + + + // LEDs + void set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled); + void set_leds_all(ledstate alleds); + void set_leds_all_off(); + void set_leds_all_on(); + + // Drives + void drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_ms, unsigned long turn_right_ms); + void set_drives_states_left_right(drivestate stateleft, drivestate stateright); + void set_drive_left_state(drivestate state); + void set_drive_right_state(drivestate state); + void set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin); + void set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright); + void set_drive_left_speed(uint8_t speed); + void set_drive_right_speed(uint8_t speed); + void set_drive_speed(uint8_t speed, uint8_t enablepin); + void set_drives_stop_left_right(); + + // Ultrasonic sensor + unsigned long usonic_measure_cm(); + unsigned long usonic_measure_us(); + unsigned long usonic_measure_cm(unsigned long max_echo_run_time_us); + unsigned long usonic_measure_us(unsigned long max_echo_run_time_us); + unsigned long usonic_measure_single_shot_cm(); + unsigned long usonic_measure_single_shot_us(); + unsigned long usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us); + unsigned long usonic_measure_single_shot_us(unsigned long max_echo_run_time_us); + void usonic_set_stop_distance_cm(unsigned long stop_distance_cm); + void usonic_set_stop_distance_us(unsigned long stop_distance_us); + + // Servo drive + void servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos); + uint8_t servo_set_position_wait(uint8_t position); + unsigned long servo_set_position(uint8_t position); + void servo_set_to_right(); + void servo_set_to_left(); + void servo_set_to_center(); + void servo_sweep(); + + // just for fun + void kitt(); + void look_around(); + + // previous OBSOLETE german language definitions of the methods - still needed to support MakerLab Murnau {code}racer project + // - but use the english ones for new implementations + void servo_einstellungen(uint8_t winkel_mitte, uint8_t winkel_links, uint8_t winkel_rechts, uint8_t schwenk_links, uint8_t schwenk_rechts); + void motor_einstellungen(uint8_t motor_links_tempo, uint8_t motor_rechts_tempo, unsigned long drehung_links_ms, unsigned long drehung_rechts_ms); void anhalten(); - void normal_tempo(); void vorwaerts(); void rueckwaerts(); void links(); @@ -143,11 +243,9 @@ class CodeRacer { void servo_rechts(); void servo_links(); void servo_mitte(); - long abstand_messen(); + unsigned long abstand_messen(); void servo_schwenk(); - void knight_rider(); bool start_stop(); - }; diff --git a/Arduino/libraries/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino b/Arduino/libraries/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino index 2d22744..c16a436 100644 --- a/Arduino/libraries/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino +++ b/Arduino/libraries/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino @@ -1,56 +1,97 @@ #include -//----- Werte für den Ultraschallsensor ----- -#define US_STOP_ABSTAND_CM 15 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an +//----- settings for the ultrasonic sensor ----- +#define US_STOP_ABSTAND_CM 20 // if distance goes below that - stop the racer -//----- Variablen, die wir brauchen um uns Werte zu merken ---- -long abstand_vorn_cm, abstand_links_cm, abstand_rechts_cm; +//----- {CODES}RACER API -> online: https://doc.itsblue.de/Fenoglio/coderacer/Doku/Doxygen/html/ +//-- Some main higher level methods listed below +// void CodeRacer::stop_driving () Stops the racer and sets status LEDs +// void CodeRacer::drive_forward () Sets the speed and the directions of both drives so that it will move forward. +// void CodeRacer::drive_backward () Sets the speed and the directions of both drives so that it will move backward. +// void CodeRacer::turn_left () Will turn the racer to the left for the internally stored time in ms and with the internally stored speed. +// void CodeRacer::turn_right () Will turn the racer to the right for the internally stored time in ms and with the internally stored speed. +// void CodeRacer::start_stop_at_min_distance () Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance. +// void CodeRacer::stop_stop_at_min_distance () Disables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. +// bool CodeRacer::start_stop () This will return if the codracer is in active mode or not. +// void CodeRacer::servo_set_to_right () Drives the servo to the postion that is defined by #servo_right_pos. +// void CodeRacer::servo_set_to_left () Drives the servo to the postion that is defined by #servo_left_pos. +// void CodeRacer::servo_set_to_center () Drives the servo to the postion that is defined by #servo_center_pos. +// uint8_t CodeRacer::servo_position () Get the actual position of the servo. +// unsigned long CodeRacer::usonic_measure_cm () Measures the distance to the next object in front of the ultra sonic sensor in cm. +// +// ... there are much more ... read the online API for more details. +//----- variables we need +unsigned long distance_cm = 0; + +//---- construct the coderacer object CodeRacer coderacer; -// Das kann der coderacer: -// coderacer.start_stop() Abfragen ob der Racer fahren soll oder nicht ... wenn er fahren soll kommt der Wert 'true' zurück, wenn er stopppen soll der Wert 'false' -// coderacer.servo_schwenk() Abstandssensor hin und her verstellen -// coderacer.abstand_messen(); Abstand messen - es kommt ein Wert in cm zurück -// coderacer.servo_mitte(); nach vorn "schauen" -// coderacer.servo_rechts(); nach rechts "schauen" -// coderacer.servo_links(); nach links "schauen" -// coderacer.links(); nach links drehen -// coderacer.rechts(); nach rechts drehen -// coderacer.vorwaerts(); Vorwaerts fahren -// coderacer.anhalten(); Racer anhalten -//---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ---- +//---- set up code - executed ones void setup() { - // Monitor - Serial.begin(115200); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen. - - // CodeRacer initialisieren + // start serial monitor + Serial.begin(115200); + // initialize the coderacer coderacer.begin(); - - // nach links und rechts schauen ... :-) - coderacer.servo_links(); - delay(10); - coderacer.servo_rechts(); - delay(10); - coderacer.servo_mitte(); - + // enable fun stuff + coderacer.coderacer_fun_enabled = true; + // look to the left, to the right and to center... :-) + coderacer.servo_set_to_left(); + delay(100); + coderacer.servo_set_to_right(); + delay(100); + coderacer.servo_set_to_center(); + delay(100); } -//---- Hier startet unsere endlose Schleife - die immer wieder von vorn angefangen wird, wenn wir am Ende angekommen sind. Da ist unser "Fahr"Code drin, der den CodeRacer steuert +//---- 'endless' loop void loop() { - // Abstand messen -> dort wo der coderacer gerade "hinschaut". Der gemessene Abstand ist in abstand_vorn_cm gespeichert - abstand_vorn_cm = coderacer.abstand_messen(); - - // Abfragen ob der Racer fahren soll oder nicht ... + // check if the racer was started (button was toggled to coderacer active state if(true == coderacer.start_stop()){ + + Serial.print("Speed of right side drive: "); + Serial.println(coderacer.drive_right_speed()); + Serial.print("Speed of left side drive: "); + Serial.println(coderacer.drive_left_speed()); + + // measure the distance - at the position of the servo + distance_cm = coderacer.usonic_measure_cm(); - // Abstandssensor verstellen ... - coderacer.servo_schwenk(); + coderacer.start_stop_at_min_distance(US_STOP_ABSTAND_CM); + while(!coderacer.stopped_at_min_distance()){ - // hier kommt Euer Code zu steuern des coderacers hinein ... + Serial.print("Distanc in cm: "); + Serial.println(distance_cm); + + if(distance_cm > 50){ + coderacer.drive_forward(); + coderacer.servo_sweep(); + } + else if(distance_cm > 40){ + coderacer.turn_right(); + } + else if(distance_cm > 30){ + coderacer.turn_left(); + } + else { - + coderacer.drive_backward(); + } + + // measure the distance - at the position of the servo + distance_cm = coderacer.usonic_measure_cm(); + + } + + Serial.println("***** STOPPED ***** "); + Serial.print("Measured stop distanc of cm: "); + Serial.println(distance_cm); + Serial.print("Measured at servo position of: "); + Serial.println(coderacer.servo_position()); + + coderacer.set_inactive(); + } } diff --git a/Arduino/libraries/CodeRacer/keywords.txt b/Arduino/libraries/CodeRacer/keywords.txt deleted file mode 100644 index f498ec9..0000000 --- a/Arduino/libraries/CodeRacer/keywords.txt +++ /dev/null @@ -1,15 +0,0 @@ -CodeRacer KEYWORD1 -begin KEYWORD2 -servo_einstellungen KEYWORD2 -motor_einstellungen KEYWORD2 -anhalten KEYWORD2 -normal_tempo KEYWORD2 -vorwaerts KEYWORD2 -links KEYWORD2 -rechts KEYWORD2 -servo_rechts KEYWORD2 -servo_links KEYWORD2 -servo_mitte KEYWORD2 -abstand_messen KEYWORD2 -servo_schwenk KEYWORD2 -start_stop KEYWORD2 \ No newline at end of file diff --git a/Arduino/libraries/ESP32Servo/README.md b/Arduino/libraries/ESP32Servo/README.md new file mode 100644 index 0000000..b3de6a4 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/README.md @@ -0,0 +1,87 @@ +# Servo Library for ESP32 + +This library attempts to faithfully replicate the semantics of the +Arduino Servo library (see http://www.arduino.cc/en/Reference/Servo) +for the ESP32, with two (optional) additions. The two new functions +expose the ability of the ESP32 PWM timers to vary timer width. + +## License + +Copyright (c) 2017 John K. Bennett. All right reserved. + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + +## Library Description: +``` +   Servo - Class for manipulating servo motors connected to ESP32 pins. + + int attach(pin ) - Attaches the given GPIO pin to the next free channel + (channels that have previously been detached are used first), + returns channel number or 0 if failure. All pin numbers are allowed, + but only pins 2,4,12-19,21-23,25-27,32-33 are recommended. + + int attach(pin, min, max ) - Attaches to a pin setting min and max + values in microseconds; enforced minimum min is 500, enforced max + is 2500. Other semantics are the same as attach(). + + void write () - Sets the servo angle in degrees; a value below 500 is + treated as a value in degrees (0 to 180). These limit are enforced, + i.e., values are constrained as follows: + Value Becomes + ----- ------- + < 0 0 + 0 - 180 value (treated as degrees) + 181 - 499 180 + 500 - (min-1) min + min-max (from attach or default) value (treated as microseconds) + (max+1) - 2500 max + + void writeMicroseconds() - Sets the servo pulse width in microseconds. + min and max are enforced (see above). + + int read() - Gets the last written servo pulse width as an angle between 0 and 180. + + int readMicroseconds() - Gets the last written servo pulse width in microseconds. + + bool attached() - Returns true if this servo instance is attached to a pin. + + void detach() - Stops an the attached servo, frees the attached pin, and frees + its channel for reuse. +``` + +### **New ESP32-specific functions** + +``` +   setTimerWidth(value) - Sets the PWM timer width (must be 16-20) (ESP32 ONLY); + as a side effect, the pulse width is recomputed. + +   int readTimerWidth() - Gets the PWM timer width (ESP32 ONLY) +``` + +### Useful Defaults: + +default min pulse width for attach(): 544us + +default max pulse width for attach(): 2400us + +default timer width 16 (if timer width is not set) + +default pulse width 1500us (servos are initialized with this value) + +MINIMUM pulse with: 500us + +MAXIMUM pulse with: 2500us + +MAXIMUM number of servos: 16 (this is the number of PWM channels in the ESP32) diff --git a/Arduino/libraries/ESP32Servo/examples/Knob/Knob.ino b/Arduino/libraries/ESP32Servo/examples/Knob/Knob.ino new file mode 100644 index 0000000..3c62f56 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/examples/Knob/Knob.ino @@ -0,0 +1,69 @@ +/* + Controlling a servo position using a potentiometer (variable resistor) + by Michal Rinott + + modified on 8 Nov 2013 + by Scott Fitzgerald + + modified for the ESP32 on March 2017 + by John Bennett + + see http://www.arduino.cc/en/Tutorial/Knob for a description of the original code + + * Different servos require different pulse widths to vary servo angle, but the range is + * an approximately 500-2500 microsecond pulse every 20ms (50Hz). In general, hobbyist servos + * sweep 180 degrees, so the lowest number in the published range for a particular servo + * represents an angle of 0 degrees, the middle of the range represents 90 degrees, and the top + * of the range represents 180 degrees. So for example, if the range is 1000us to 2000us, + * 1000us would equal an angle of 0, 1500us would equal 90 degrees, and 2000us would equal 1800 + * degrees. + * + * Circuit: (using an ESP32 Thing from Sparkfun) + * Servo motors have three wires: power, ground, and signal. The power wire is typically red, + * the ground wire is typically black or brown, and the signal wire is typically yellow, + * orange or white. Since the ESP32 can supply limited current at only 3.3V, and servos draw + * considerable power, we will connect servo power to the VBat pin of the ESP32 (located + * near the USB connector). THIS IS ONLY APPROPRIATE FOR SMALL SERVOS. + * + * We could also connect servo power to a separate external + * power source (as long as we connect all of the grounds (ESP32, servo, and external power). + * In this example, we just connect ESP32 ground to servo ground. The servo signal pins + * connect to any available GPIO pins on the ESP32 (in this example, we use pin 18. + * + * In this example, we assume a Tower Pro SG90 small servo connected to VBat. + * The published min and max for this servo are 500 and 2400, respectively. + * These values actually drive the servos a little past 0 and 180, so + * if you are particular, adjust the min and max values to match your needs. + */ + +// Include the ESP32 Arduino Servo Library instead of the original Arduino Servo Library +#include + +Servo myservo; // create servo object to control a servo + +// Possible PWM GPIO pins on the ESP32: 0(used by on-board button),2,4,5(used by on-board LED),12-19,21-23,25-27,32-33 +int servoPin = 18; // GPIO pin used to connect the servo control (digital out) +// Possible ADC pins on the ESP32: 0,2,4,12-15,32-39; 34-39 are recommended for analog input +int potPin = 34; // GPIO pin used to connect the potentiometer (analog in) +int ADC_Max = 4096; // This is the default ADC max value on the ESP32 (12 bit ADC width); + // this width can be set (in low-level oode) from 9-12 bits, for a + // a range of max values of 512-4096 + +int val; // variable to read the value from the analog pin + +void setup() +{ + myservo.attach(servoPin, 500, 2400); // attaches the servo on pin 18 to the servo object + // using SG90 servo min/max of 500us and 2400us + // for MG995 large servo, use 1000us and 2000us, + // which are the defaults, so this line could be + // "myservo.attach(servoPin);" +} + +void loop() { + val = analogRead(potPin); // read the value of the potentiometer (value between 0 and 1023) + val = map(val, 0, ADC_Max, 0, 180); // scale it to use it with the servo (value between 0 and 180) + myservo.write(val); // set the servo position according to the scaled value + delay(200); // wait for the servo to get there +} + diff --git a/Arduino/libraries/ESP32Servo/examples/Multiple-Servo-Example-Arduino/Multiple-Servo-Example-Arduino.ino b/Arduino/libraries/ESP32Servo/examples/Multiple-Servo-Example-Arduino/Multiple-Servo-Example-Arduino.ino new file mode 100644 index 0000000..c60e174 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/examples/Multiple-Servo-Example-Arduino/Multiple-Servo-Example-Arduino.ino @@ -0,0 +1,106 @@ +/* + * ESP32 Servo Example Using Arduino ESP32 Servo Library + * John K. Bennett + * March, 2017 + * + * This sketch uses the Arduino ESP32 Servo Library to sweep 4 servos in sequence. + * + * Different servos require different pulse widths to vary servo angle, but the range is + * an approximately 500-2500 microsecond pulse every 20ms (50Hz). In general, hobbyist servos + * sweep 180 degrees, so the lowest number in the published range for a particular servo + * represents an angle of 0 degrees, the middle of the range represents 90 degrees, and the top + * of the range represents 180 degrees. So for example, if the range is 1000us to 2000us, + * 1000us would equal an angle of 0, 1500us would equal 90 degrees, and 2000us would equal 1800 + * degrees. + * + * Circuit: + * Servo motors have three wires: power, ground, and signal. The power wire is typically red, + * the ground wire is typically black or brown, and the signal wire is typically yellow, + * orange or white. Since the ESP32 can supply limited current at only 3.3V, and servos draw + * considerable power, we will connect servo power to the VBat pin of the ESP32 (located + * near the USB connector). THIS IS ONLY APPROPRIATE FOR SMALL SERVOS. + * + * We could also connect servo power to a separate external + * power source (as long as we connect all of the grounds (ESP32, servo, and external power). + * In this example, we just connect ESP32 ground to servo ground. The servo signal pins + * connect to any available GPIO pins on the ESP32 (in this example, we use pins + * 22, 19, 23, & 18). + * + * In this example, we assume four Tower Pro SG90 small servos. + * The published min and max for this servo are 500 and 2400, respectively. + * These values actually drive the servos a little past 0 and 180, so + * if you are particular, adjust the min and max values to match your needs. + * Experimentally, 550 and 2350 are pretty close to 0 and 180. + */ + +#include + +// create four servo objects +Servo servo1; +Servo servo2; +Servo servo3; +Servo servo4; + +// Published values for SG90 servos; adjust if needed +int minUs = 500; +int maxUs = 2400; + +// These are all GPIO pins on the ESP32 +// Recommended pins include 2,4,12-19,21-23,25-27,32-33 +int servo1Pin = 18; +int servo2Pin = 19; +int servo3Pin = 22; +int servo4Pin = 23; + +int pos = 0; // position in degrees + +void setup() +{ + servo1.attach(servo1Pin, minUs, maxUs); + servo2.attach(servo2Pin, minUs, maxUs); + servo3.attach(servo3Pin, minUs, maxUs); + servo4.attach(servo4Pin, minUs, maxUs); +} + +void loop() { + for (pos = 0; pos <= 180; pos += 1) { // sweep from 0 degrees to 180 degrees + // in steps of 1 degree + servo1.write(pos); + delay(20); // waits 20ms for the servo to reach the position + } + for (pos = 180; pos >= 0; pos -= 1) { // sweep from 180 degrees to 0 degrees + servo1.write(pos); + delay(20); + } + + for (pos = 0; pos <= 180; pos += 1) { // sweep from 0 degrees to 180 degrees + // in steps of 1 degree + servo2.write(pos); + delay(20); // waits 20ms for the servo to reach the position + } + for (pos = 180; pos >= 0; pos -= 1) { // sweep from 180 degrees to 0 degrees + servo2.write(pos); + delay(20); + } + + for (pos = 0; pos <= 180; pos += 1) { // sweep from 0 degrees to 180 degrees + // in steps of 1 degree + servo3.write(pos); + delay(20); // waits 20ms for the servo to reach the position + } + for (pos = 180; pos >= 0; pos -= 1) { // sweep from 180 degrees to 0 degrees + servo3.write(pos); + delay(20); + } + + for (pos = 0; pos <= 180; pos += 1) { // sweep from 0 degrees to 180 degrees + // in steps of 1 degree + servo4.write(pos); + delay(20); // waits 20ms for the servo to reach the position + } + for (pos = 180; pos >= 0; pos -= 1) { // sweep from 180 degrees to 0 degrees + servo4.write(pos); + delay(20); + } +} + diff --git a/Arduino/libraries/ESP32Servo/examples/Multiple-Servo-Example-ESP32/Multiple-Servo-Example-ESP32.ino b/Arduino/libraries/ESP32Servo/examples/Multiple-Servo-Example-ESP32/Multiple-Servo-Example-ESP32.ino new file mode 100644 index 0000000..e92e9f6 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/examples/Multiple-Servo-Example-ESP32/Multiple-Servo-Example-ESP32.ino @@ -0,0 +1,109 @@ +/* + * ESP32 Servo Example + * John K. Bennett + * March, 2017 + * + * This sketch uses low-level ESP32 PWM functionality to sweep 4 servos in sequence. + * It does NOT use the ESP32_Servo library for Arduino. + * + * The ESP32 supports 16 hardware LED PWM channels that are intended + * to be used for LED brightness control. The low level ESP32 code allows us to set the + * PWM frequency and bit-depth, and then control them by setting bits in the relevant control + * register. The core files esp32-hal-ledc.* provides helper functions to make this set up + * straightforward. + * + * Different servos require different pulse widths to vary servo angle, but the range is + * an approximately 500-2500 microsecond pulse every 20ms (50Hz). In general, hobbyist servos + * sweep 180 degrees, so the lowest number in the published range for a particular servo + * represents an angle of 0 degrees, the middle of the range represents 90 degrees, and the top + * of the range represents 180 degrees. So for example, if the range is 1000us to 2000us, + * 1000us would equal an angle of 0, 1500us would equal 90 degrees, and 2000us would equal 1800 + * degrees. + * + * The ESP32 PWM timers allow us to set the timer width (max 20 bits). Thus + * the timer "tick" length is (pulse_period/2**timer_width), and the equation for pulse_high_width + * (the portion of cycle (20ms in our case) that the signal is high) becomes: + * + * pulse_high_width = count * tick_length + * = count * (pulse_period/2**timer_width) + * + * and count = (pulse_high_width / (pulse_period/2**timer_width)) + * + * For example, if we want a 1500us pulse_high_width, we set pulse_period to 20ms (20000us) + * (this value is set in the ledcSetup call), and count (used in the ledcWrite call) to + * 1500/(20000/65655), or 4924. This is the value we write to the timer in the ledcWrite call. + * + * As a concrete example, suppose we want to repeatedly sweep four Tower Pro SG90 servos + * from 0 to 180 degrees. The published pulse width range for the SG90 is 500-2400us. Thus, + * we should vary the count used in ledcWrite from 1638 to 7864. + * + * Circuit: + * Servo motors have three wires: power, ground, and signal. The power wire is typically red, + * the ground wire is typically black or brown, and the signal wire is typically yellow, + * orange or white. Since the ESP32 can supply limited current at only 3.3V, and servos draw + * considerable power, we will connect servo power to the VBat pin of the ESP32 (located + * near the USB connector). THIS IS ONLY APPROPRIATE FOR SMALL SERVOS. + * + * We could also connect servo power to a separate external + * power source (as long as we connect all of the grounds (ESP32, servo, and external power). + * In this example, we just connect ESP32 ground to servo ground. The servo signal pins + * connect to any available GPIO pins on the ESP32 (in this example, we use pins + * 22, 19, 23, & 18). + * + * In this example, we assume four Tower Pro SG90 small servos. + * The published min and max for this servo are 500 and 2400, respectively. + * These values actually drive the servos a little past 0 and 180, so + * if you are particular, adjust the min and max values to match your needs. + * Experimentally, 550us and 2350us are pretty close to 0 and 180. + * + * This code was inspired by a post on Hackaday by Elliot Williams. + */ + + // Values for TowerPro SG90 small servos; adjust if needed + #define COUNT_LOW 1638 + #define COUNT_HIGH 7864 + + #define TIMER_WIDTH 16 + +#include "esp32-hal-ledc.h" + +void setup() { + ledcSetup(1, 50, TIMER_WIDTH); // channel 1, 50 Hz, 16-bit width + ledcAttachPin(22, 1); // GPIO 22 assigned to channel 1 + + ledcSetup(2, 50, TIMER_WIDTH); // channel 2, 50 Hz, 16-bit width + ledcAttachPin(19, 2); // GPIO 19 assigned to channel 2 + + ledcSetup(3, 50, TIMER_WIDTH); // channel 3, 50 Hz, 16-bit width + ledcAttachPin(23, 3); // GPIO 23 assigned to channel 3 + + ledcSetup(4, 50, TIMER_WIDTH); // channel 4, 50 Hz, 16-bit width + ledcAttachPin(18, 4); // GPIO 18 assigned to channel 4 +} + +void loop() { + for (int i=COUNT_LOW ; i < COUNT_HIGH ; i=i+100) + { + ledcWrite(1, i); // sweep servo 1 + delay(200); + } + + for (int i=COUNT_LOW ; i < COUNT_HIGH ; i=i+100) + { + ledcWrite(2, i); // sweep servo 2 + delay(200); + } + + for (int i=COUNT_LOW ; i < COUNT_HIGH ; i=i+100) + { + ledcWrite(3, i); // sweep the servo + delay(200); + } + + for (int i=COUNT_LOW ; i < COUNT_HIGH ; i=i+100) + { + ledcWrite(4, i); // sweep the servo + delay(200); + } +} + diff --git a/Arduino/libraries/ESP32Servo/examples/Sweep/Sweep.ino b/Arduino/libraries/ESP32Servo/examples/Sweep/Sweep.ino new file mode 100644 index 0000000..4e90018 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/examples/Sweep/Sweep.ino @@ -0,0 +1,66 @@ +/* Sweep + by BARRAGAN + This example code is in the public domain. + + modified 8 Nov 2013 + by Scott Fitzgerald + + modified for the ESP32 on March 2017 + by John Bennett + + see http://www.arduino.cc/en/Tutorial/Sweep for a description of the original code + + * Different servos require different pulse widths to vary servo angle, but the range is + * an approximately 500-2500 microsecond pulse every 20ms (50Hz). In general, hobbyist servos + * sweep 180 degrees, so the lowest number in the published range for a particular servo + * represents an angle of 0 degrees, the middle of the range represents 90 degrees, and the top + * of the range represents 180 degrees. So for example, if the range is 1000us to 2000us, + * 1000us would equal an angle of 0, 1500us would equal 90 degrees, and 2000us would equal 1800 + * degrees. + * + * Circuit: (using an ESP32 Thing from Sparkfun) + * Servo motors have three wires: power, ground, and signal. The power wire is typically red, + * the ground wire is typically black or brown, and the signal wire is typically yellow, + * orange or white. Since the ESP32 can supply limited current at only 3.3V, and servos draw + * considerable power, we will connect servo power to the VBat pin of the ESP32 (located + * near the USB connector). THIS IS ONLY APPROPRIATE FOR SMALL SERVOS. + * + * We could also connect servo power to a separate external + * power source (as long as we connect all of the grounds (ESP32, servo, and external power). + * In this example, we just connect ESP32 ground to servo ground. The servo signal pins + * connect to any available GPIO pins on the ESP32 (in this example, we use pin 18. + * + * In this example, we assume a Tower Pro MG995 large servo connected to an external power source. + * The published min and max for this servo is 1000 and 2000, respectively, so the defaults are fine. + * These values actually drive the servos a little past 0 and 180, so + * if you are particular, adjust the min and max values to match your needs. + */ + +#include + +Servo myservo; // create servo object to control a servo + // 16 servo objects can be created on the ESP32 + +int pos = 0; // variable to store the servo position +// Recommended PWM GPIO pins on the ESP32 include 2,4,12-19,21-23,25-27,32-33 +int servoPin = 18; + +void setup() { + myservo.attach(servoPin); // attaches the servo on pin 18 to the servo object + // using default min/max of 1000us and 2000us + // different servos may require different min/max settings + // for an accurate 0 to 180 sweep +} + +void loop() { + for (pos = 0; pos <= 180; pos += 1) { // goes from 0 degrees to 180 degrees + // in steps of 1 degree + myservo.write(pos); // tell servo to go to position in variable 'pos' + delay(15); // waits 15ms for the servo to reach the position + } + for (pos = 180; pos >= 0; pos -= 1) { // goes from 180 degrees to 0 degrees + myservo.write(pos); // tell servo to go to position in variable 'pos' + delay(15); // waits 15ms for the servo to reach the position + } +} + diff --git a/Arduino/libraries/ESP32Servo/keywords.txt b/Arduino/libraries/ESP32Servo/keywords.txt new file mode 100644 index 0000000..da07789 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/keywords.txt @@ -0,0 +1,26 @@ +####################################### +# Syntax Coloring Map ESP32_Servo +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +Servo KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### +attach KEYWORD2 +detach KEYWORD2 +write KEYWORD2 +read KEYWORD2 +attached KEYWORD2 +writeMicroseconds KEYWORD2 +readMicroseconds KEYWORD2 +setTimerWidth KEYWORD2 +readTimerWidth KEYWORD2 + +####################################### +# Constants (LITERAL1) +####################################### \ No newline at end of file diff --git a/Arduino/libraries/ESP32Servo/library.properties b/Arduino/libraries/ESP32Servo/library.properties new file mode 100644 index 0000000..110298b --- /dev/null +++ b/Arduino/libraries/ESP32Servo/library.properties @@ -0,0 +1,11 @@ +name=ESP32Servo +version=0.0.4 +author=John K. Bennett,Kevin Harrington +maintainer=Kevin Harrington +sentence=Allows ESP32 boards to control servo motors using Arduino semantics. +paragraph=This library can control a many types of servos.
It makes use of the ESP32 PWM timers: the library can control up to 16 servos on individual channels
No attempt has been made to support multiple servos per channel.
+category=Device Control +url=http://www.arduino.cc/en/Reference/Servo +architectures=* +includes=ESP32Servo.h + diff --git a/Arduino/libraries/ESP32Servo/src/ESP32Servo.cpp b/Arduino/libraries/ESP32Servo/src/ESP32Servo.cpp new file mode 100644 index 0000000..2d037f9 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/src/ESP32Servo.cpp @@ -0,0 +1,275 @@ +/* +Copyright (c) 2017 John K. Bennett. All right reserved. + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + +* Notes on the implementation: +* The ESP32 supports 16 hardware LED PWM channels that are intended +* to be used for LED brightness control. The low level ESP32 code +* (esp32-hal-ledc.*) allows us to set the PWM frequency and bit-depth, +* and then manipulate them by setting bits in the relevant control +* registers. +* +* Different servos require different pulse widths to vary servo angle, but the range is +* an approximately 500-2500 microsecond pulse every 20ms (50Hz). In general, hobbyist servos +* sweep 180 degrees, so the lowest number in the published range for a particular servo +* represents an angle of 0 degrees, the middle of the range represents 90 degrees, and the top +* of the range represents 180 degrees. So for example, if the range is 1000us to 2000us, +* 1000us would equal an angle of 0, 1500us would equal 90 degrees, and 2000us would equal 180 +* degrees. We vary pulse width (recall that the pulse period is already set to 20ms) as follows: +* +* The ESP32 PWM timers allow us to set the timer width (max 20 bits). Thus +* the timer "tick" length is (pulse_period/2**timer_width), and the equation for pulse_high_width +* (the portion of the 20ms cycle that the signal is high) becomes: +* +* pulse_high_width = count * tick_length +* = count * (pulse_period/2**timer_width) +* +* and count = (pulse_high_width / (pulse_period/2**timer_width)) +* +* So, for example, if I want a 1500us pulse_high_width, I set pulse_period to 20ms (20000us) +* (this value is set in the ledcSetup call), and count (used in the ledcWrite call) to +* 1500/(20000/65536), or 4924. This is the value we write to the timer in the ledcWrite call. +* If we increase the timer_width, the timer_count values need to be adjusted. +* +* The servo signal pins connect to any available GPIO pins on the ESP32, but not all pins are +* GPIO pins. +* +* The ESP32 is a 32 bit processor that includes FP support; this code reflects that fact. +*/ + +#include +#include "esp32-hal-ledc.h" +#include "Arduino.h" + +// + +// initialize the class variable ServoCount +int Servo::ServoCount = 0; + +// The ChannelUsed array elements are 0 if never used, 1 if in use, and -1 if used and disposed +// (i.e., available for reuse) +int Servo::ChannelUsed[MAX_SERVOS+1] = {0}; // we ignore the zeroth element + +Servo::Servo() +{ + this->servoChannel = 0; + // see if there is a servo channel available for reuse + bool foundChannelForReuse = false; + for (int i = 1; i < MAX_SERVOS+1; i++) + { + if (ChannelUsed[i] == -1) + { + // reclaim this channel + ChannelUsed[i] = 1; + this->servoChannel = i; + foundChannelForReuse = true; + break; + } + } + if (!foundChannelForReuse) + { + // no channels available for reuse; get a new one if we can + if (ServoCount < MAX_SERVOS) + { + this->servoChannel = ++ServoCount; // assign a servo channel number to this instance + ChannelUsed[this->servoChannel] = 1; + } + else + { + this->servoChannel = 0; // too many servos in use + } + } + // if we got a channel either way, finish initializing it + if (this->servoChannel > 0) + { + // initialize this channel with plausible values, except pin # (we set pin # when attached) + this->ticks = DEFAULT_PULSE_WIDTH_TICKS; + this->timer_width = DEFAULT_TIMER_WIDTH; + this->pinNumber = -1; // make it clear that we haven't attached a pin to this channel + this->min = DEFAULT_uS_LOW; + this->max = DEFAULT_uS_HIGH; + this->timer_width_ticks = pow(2,this->timer_width); + } +} + +int Servo::attach(int pin) +{ + return (this->attach(pin, DEFAULT_uS_LOW, DEFAULT_uS_HIGH)); +} + +int Servo::attach(int pin, int min, int max) +{ + if ((this->servoChannel <= MAX_SERVOS) && (this->servoChannel > 0)) + { +#ifdef ENFORCE_PINS + // Recommend only the following pins 2,4,12-19,21-23,25-27,32-33 + if ((pin == 2) || (pin ==4) || ((pin >= 12) && (pin <= 19)) || ((pin >= 21) && (pin <= 23)) || + ((pin >= 25) && (pin <= 27)) || (pin == 32) || (pin == 33)) + { +#endif + // OK to proceed; first check for new/reuse + if (this->pinNumber < 0) // we are attaching to a new or previously detached pin; we need to initialize/reinitialize + { + // claim/reclaim this channel + ChannelUsed[this->servoChannel] = 1; + this->ticks = DEFAULT_PULSE_WIDTH_TICKS; + this->timer_width = DEFAULT_TIMER_WIDTH; + this->timer_width_ticks = pow(2,this->timer_width); + } + this->pinNumber = pin; +#ifdef ENFORCE_PINS + } + else + { + Serial.println("This pin can not be a servo: "+String(pin)+"\r\nOnly use: 2,4,12-19,21-23,25-27,32-33"); + return 0; + } +#endif + + // min/max checks + if (min < MIN_PULSE_WIDTH) // ensure pulse width is valid + min = MIN_PULSE_WIDTH; + if (max > MAX_PULSE_WIDTH) + max = MAX_PULSE_WIDTH; + this->min = min; //store this value in uS + this->max = max; //store this value in uS + // Set up this channel + // if you want anything other than default timer width, you must call setTimerWidth() before attach + ledcSetup(this->servoChannel, REFRESH_CPS, this->timer_width); // channel #, 50 Hz, timer width + ledcAttachPin(this->pinNumber, this->servoChannel); // GPIO pin assigned to channel + return 1; + } + else return 0; +} + +void Servo::detach() +{ + if (this->attached()) + { + ledcDetachPin(this->pinNumber); + //keep track of detached servos channels so we can reuse them if needed + ChannelUsed[this->servoChannel] = -1; + this->pinNumber = -1; + } +} + +void Servo::write(int value) +{ + // treat values less than MIN_PULSE_WIDTH (500) as angles in degrees (valid values in microseconds are handled as microseconds) + if (value < MIN_PULSE_WIDTH) + { + if (value < 0) + value = 0; + else if (value > 180) + value = 180; + + value = map(value, 0, 180, this->min, this->max); + } + this->writeMicroseconds(value); +} + +void Servo::writeMicroseconds(int value) +{ + // calculate and store the values for the given channel + if ((this->servoChannel <= MAX_SERVOS) && (this->attached())) // ensure channel is valid + { + if (value < this->min) // ensure pulse width is valid + value = this->min; + else if (value > this->max) + value = this->max; + + value = usToTicks(value); // convert to ticks + this->ticks = value; + // do the actual write + ledcWrite(this->servoChannel, this->ticks); + } +} + +int Servo::read() // return the value as degrees +{ + return (map(readMicroseconds()+1, this->min, this->max, 0, 180)); +} + +int Servo::readMicroseconds() +{ + int pulsewidthUsec; + if ((this->servoChannel <= MAX_SERVOS) && (this->attached())) + { + pulsewidthUsec = ticksToUs(this->ticks); + } + else + { + pulsewidthUsec = 0; + } + + return (pulsewidthUsec); +} + +bool Servo::attached() +{ + return (ChannelUsed[this->servoChannel]); +} + +void Servo::setTimerWidth(int value) +{ + // only allow values between 16 and 20 + if (value < 16) + value = 16; + else if (value > 20) + value = 20; + + // Fix the current ticks value after timer width change + // The user can reset the tick value with a write() or writeUs() + int widthDifference = this->timer_width - value; + // if positive multiply by diff; if neg, divide + if (widthDifference > 0) + { + this->ticks = widthDifference * this->ticks; + } + else + { + this->ticks = this->ticks/-widthDifference; + } + + this->timer_width = value; + this->timer_width_ticks = pow(2,this->timer_width); + + // If this is an attached servo, clean up + if ((this->servoChannel <= MAX_SERVOS) && (this->attached())) + { + // detach, setup and attach again to reflect new timer width + ledcDetachPin(this->pinNumber); + ledcSetup(this->servoChannel, REFRESH_CPS, this->timer_width); + ledcAttachPin(this->pinNumber, this->servoChannel); + } +} + +int Servo::readTimerWidth() +{ + return (this->timer_width); +} + +int Servo::usToTicks(int usec) +{ + return (int)((float)usec / ((float)REFRESH_USEC / (float)this->timer_width_ticks)); +} + +int Servo::ticksToUs(int ticks) +{ + return (int)((float)ticks * ((float)REFRESH_USEC / (float)this->timer_width_ticks)); +} + + diff --git a/Arduino/libraries/ESP32Servo/src/ESP32Servo.h b/Arduino/libraries/ESP32Servo/src/ESP32Servo.h new file mode 100644 index 0000000..bdb0d41 --- /dev/null +++ b/Arduino/libraries/ESP32Servo/src/ESP32Servo.h @@ -0,0 +1,149 @@ +/* + Copyright (c) 2017 John K. Bennett. All right reserved. + + ESP32_Servo.h - Servo library for ESP32 - Version 1 + + Original Servo.h written by Michael Margolis in 2009 + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* + A servo is activated by creating an instance of the Servo class, and passing + the desired GPIO pin to the attach() method. + The servos are pulsed in the background using the value most recently + written using the write() method. + + The class methods are: + + Servo - Class for manipulating servo motors connected to ESP32 pins. + int attach(pin ) - Attaches the given GPIO pin to the next free channel + (channels that have previously been detached are used first), + returns channel number or 0 if failure. All pin numbers are allowed, + but only pins 2,4,12-19,21-23,25-27,32-33 are recommended. + int attach(pin, min, max ) - Attaches to a pin setting min and max + values in microseconds; enforced minimum min is 500, enforced max + is 2500. Other semantics same as attach(). + void write () - Sets the servo angle in degrees; a value below 500 is + treated as a value in degrees (0 to 180). These limit are enforced, + i.e., values are treated as follows: + Value Becomes + ----- ------- + < 0 0 + 0 - 180 value (treated as degrees) + 181 - 499 180 + 500 - (min-1) min + min-max (from attach or default) value (treated as microseconds) + (max+1) - 2500 max + + void writeMicroseconds() - Sets the servo pulse width in microseconds. + min and max are enforced (see above). + int read() - Gets the last written servo pulse width as an angle between 0 and 180. + int readMicroseconds() - Gets the last written servo pulse width in microseconds. + bool attached() - Returns true if this servo instance is attached. + void detach() - Stops an the attached servo, frees its attached pin, and frees + its channel for reuse). + + *** ESP32-specific functions ** + setTimerWidth(value) - Sets the PWM timer width (must be 16-20) (ESP32 ONLY); + as a side effect, the pulse width is recomputed. + int readTimerWidth() - Gets the PWM timer width (ESP32 ONLY) + */ + +#ifndef ESP32_Servo_h +#define ESP32_Servo_h +//Enforce only using PWM pins on the ESP32 +#define ENFORCE_PINS +// Default Arduino Servo.h +#define DEFAULT_uS_LOW 544 +#define DEFAULT_uS_HIGH 2400 + +// Values for TowerPro MG995 large servos (and many other hobbyist servos) +//#define DEFAULT_uS_LOW 1000 // 1000us +//#define DEFAULT_uS_HIGH 2000 // 2000us + +// Values for TowerPro SG90 small servos +//#define DEFAULT_uS_LOW 400 +//#define DEFAULT_uS_HIGH 2400 + +#define DEFAULT_TIMER_WIDTH 16 +#define DEFAULT_TIMER_WIDTH_TICKS 65536 + +#define ESP32_Servo_VERSION 1 // software version of this library + +#define MIN_PULSE_WIDTH 500 // the shortest pulse sent to a servo +#define MAX_PULSE_WIDTH 2500 // the longest pulse sent to a servo +#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached +#define DEFAULT_PULSE_WIDTH_TICKS 4825 +#define REFRESH_CPS 50 +#define REFRESH_USEC 20000 + +#define MAX_SERVOS 16 // no. of PWM channels in ESP32 + +/* +* This group/channel/timmer mapping is for information only; +* the details are handled by lower-level code +* +* LEDC Chan to Group/Channel/Timer Mapping +** ledc: 0 => Group: 0, Channel: 0, Timer: 0 +** ledc: 1 => Group: 0, Channel: 1, Timer: 0 +** ledc: 2 => Group: 0, Channel: 2, Timer: 1 +** ledc: 3 => Group: 0, Channel: 3, Timer: 1 +** ledc: 4 => Group: 0, Channel: 4, Timer: 2 +** ledc: 5 => Group: 0, Channel: 5, Timer: 2 +** ledc: 6 => Group: 0, Channel: 6, Timer: 3 +** ledc: 7 => Group: 0, Channel: 7, Timer: 3 +** ledc: 8 => Group: 1, Channel: 0, Timer: 0 +** ledc: 9 => Group: 1, Channel: 1, Timer: 0 +** ledc: 10 => Group: 1, Channel: 2, Timer: 1 +** ledc: 11 => Group: 1, Channel: 3, Timer: 1 +** ledc: 12 => Group: 1, Channel: 4, Timer: 2 +** ledc: 13 => Group: 1, Channel: 5, Timer: 2 +** ledc: 14 => Group: 1, Channel: 6, Timer: 3 +** ledc: 15 => Group: 1, Channel: 7, Timer: 3 +*/ + +class Servo +{ +public: + Servo(); + // Arduino Servo Library calls + int attach(int pin); // attach the given pin to the next free channel, returns channel number or 0 if failure + int attach(int pin, int min, int max); // as above but also sets min and max values for writes. + void detach(); + void write(int value); // if value is < MIN_PULSE_WIDTH its treated as an angle, otherwise as pulse width in microseconds + void writeMicroseconds(int value); // Write pulse width in microseconds + int read(); // returns current pulse width as an angle between 0 and 180 degrees + int readMicroseconds(); // returns current pulse width in microseconds for this servo + bool attached(); // return true if this servo is attached, otherwise false + + // ESP32 only functions + void setTimerWidth(int value); // set the PWM timer width (ESP32 ONLY) + int readTimerWidth(); // get the PWM timer width (ESP32 ONLY) + + private: + int usToTicks(int usec); + int ticksToUs(int ticks); + static int ServoCount; // the total number of attached servos + static int ChannelUsed[]; // used to track whether a channel is in service + int servoChannel = 0; // channel number for this servo + int min = DEFAULT_uS_LOW; // minimum pulse width for this servo + int max = DEFAULT_uS_HIGH; // maximum pulse width for this servo + int pinNumber = 0; // GPIO pin assigned to this channel + int timer_width = DEFAULT_TIMER_WIDTH; // ESP32 allows variable width PWM timers + int ticks = DEFAULT_PULSE_WIDTH_TICKS; // current pulse width on this channel + int timer_width_ticks = DEFAULT_TIMER_WIDTH_TICKS; // no. of ticks at rollover; varies with width +}; +#endif diff --git a/Doku/Doxygen/Doxyfile b/Doku/Doxygen/Doxyfile index d4d1b35..b12e371 100644 --- a/Doku/Doxygen/Doxyfile +++ b/Doku/Doxygen/Doxyfile @@ -51,7 +51,7 @@ PROJECT_BRIEF = "... better know the details." # pixels and the maximum width should not exceed 200 pixels. Doxygen will copy # the logo to the output directory. -PROJECT_LOGO = ../Doku/Bilder/coderace_logo.JPG +PROJECT_LOGO = C:/Users/jnoack/Documents/GITs/coderacer/Doku/Bilder/coderace_logo.JPG # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path # into which the generated documentation will be written. If a relative path is @@ -435,7 +435,7 @@ LOOKUP_CACHE_SIZE = 0 # normally produced when WARNINGS is set to YES. # The default value is: NO. -EXTRACT_ALL = NO +EXTRACT_ALL = YES # If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will # be included in the documentation. @@ -461,7 +461,7 @@ EXTRACT_STATIC = NO # for Java sources. # The default value is: YES. -EXTRACT_LOCAL_CLASSES = NO +EXTRACT_LOCAL_CLASSES = YES # This flag is only useful for Objective-C code. If set to YES, local methods, # which are defined in the implementation section but not in the interface are @@ -544,7 +544,7 @@ HIDE_COMPOUND_REFERENCE= NO # the files that are included by a file in the documentation of that file. # The default value is: YES. -SHOW_INCLUDE_FILES = NO +SHOW_INCLUDE_FILES = YES # If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each # grouped member an include statement to the documentation, telling the reader @@ -666,21 +666,21 @@ MAX_INITIALIZER_LINES = 30 # list will mention the files that were used to generate the documentation. # The default value is: YES. -SHOW_USED_FILES = NO +SHOW_USED_FILES = YES # Set the SHOW_FILES tag to NO to disable the generation of the Files page. This # will remove the Files entry from the Quick Index and from the Folder Tree View # (if specified). # The default value is: YES. -SHOW_FILES = NO +SHOW_FILES = YES # Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces # page. This will remove the Namespaces entry from the Quick Index and from the # Folder Tree View (if specified). # The default value is: YES. -SHOW_NAMESPACES = NO +SHOW_NAMESPACES = YES # The FILE_VERSION_FILTER tag can be used to specify a program or script that # doxygen should invoke to get the current version for each file (typically from @@ -790,7 +790,7 @@ WARN_LOGFILE = # spaces. See also FILE_PATTERNS and EXTENSION_MAPPING # Note: If this tag is empty the current directory is searched. -INPUT = C:\Users\jnoack\Documents\Arduino\libraries\CodeRacer +INPUT = ../../Arduino/libraries/CodeRacer # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses @@ -2343,7 +2343,7 @@ CALL_GRAPH = YES # The default value is: NO. # This tag requires that the tag HAVE_DOT is set to YES. -CALLER_GRAPH = NO +CALLER_GRAPH = YES # If the GRAPHICAL_HIERARCHY tag is set to YES then doxygen will graphical # hierarchy of all classes instead of a textual one. diff --git a/Doku/Doxygen/html/bc_s.png b/Doku/Doxygen/html/bc_s.png deleted file mode 100644 index 224b29a..0000000 Binary files a/Doku/Doxygen/html/bc_s.png and /dev/null differ diff --git a/Doku/Doxygen/html/bdwn.png b/Doku/Doxygen/html/bdwn.png deleted file mode 100644 index 940a0b9..0000000 Binary files a/Doku/Doxygen/html/bdwn.png and /dev/null differ diff --git a/Doku/Doxygen/html/closed.png b/Doku/Doxygen/html/closed.png deleted file mode 100644 index 98cc2c9..0000000 Binary files a/Doku/Doxygen/html/closed.png and /dev/null differ diff --git a/Doku/Doxygen/html/coderace_get_in_contact_pic.png b/Doku/Doxygen/html/coderace_get_in_contact_pic.png deleted file mode 100644 index 2ed634a..0000000 Binary files a/Doku/Doxygen/html/coderace_get_in_contact_pic.png and /dev/null differ diff --git a/Doku/Doxygen/html/coderace_logo.JPG b/Doku/Doxygen/html/coderace_logo.JPG deleted file mode 100644 index 0b58ee1..0000000 Binary files a/Doku/Doxygen/html/coderace_logo.JPG and /dev/null differ diff --git a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.html b/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.html deleted file mode 100644 index 84ff2b1..0000000 --- a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.html +++ /dev/null @@ -1,157 +0,0 @@ - - - - - - - -Arduino {code}racer API: Getters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - -

-Functions

uint8_t CodeRacer::drive_right_speed ()
 Get the setting for the speed of the right side drive. More...
 
uint8_t CodeRacer::drive_left_speed ()
 Get the setting for the speed of the left side drive. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ drive_right_speed()

- -
-
- - - - - - - -
uint8_t CodeRacer::drive_right_speed ()
-
- -

Get the setting for the speed of the right side drive.

-
Returns
Speed of the right side drive
- -

Definition at line 994 of file CodeRacer.cpp.

-
994  {
995  return _drive_right_speed;
996 }
-
-
- -

◆ drive_left_speed()

- -
-
- - - - - - - -
uint8_t CodeRacer::drive_left_speed ()
-
- -

Get the setting for the speed of the left side drive.

-
Returns
Speed of the left side drive
- -

Definition at line 1001 of file CodeRacer.cpp.

-
1001  {
1002  return(_drive_left_speed);
1003 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.js b/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.js deleted file mode 100644 index 7b830a1..0000000 --- a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.js +++ /dev/null @@ -1,5 +0,0 @@ -var group__lowerleveldrivesgetters = -[ - [ "drive_right_speed", "d0/d0a/group__lowerleveldrivesgetters.html#ga09359a792e3299b1c20f6b99939ea7b3", null ], - [ "drive_left_speed", "d0/d0a/group__lowerleveldrivesgetters.html#ga804a45724f3788fd2fdb9631c66d1377", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.map b/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.map deleted file mode 100644 index cfb1656..0000000 --- a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.md5 b/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.md5 deleted file mode 100644 index 88a8697..0000000 --- a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.md5 +++ /dev/null @@ -1 +0,0 @@ -27209861500fd81db6dccdd2984f5d4a \ No newline at end of file diff --git a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.png b/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.png deleted file mode 100644 index 9a59f9c..0000000 Binary files a/Doku/Doxygen/html/d0/d0a/group__lowerleveldrivesgetters.png and /dev/null differ diff --git a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.html b/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.html deleted file mode 100644 index b7b1e7b..0000000 --- a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.html +++ /dev/null @@ -1,496 +0,0 @@ - - - - - - - -Arduino {code}racer API: Methods - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Functions

void CodeRacer::drives_settings (uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_ms, unsigned long turn_right_ms)
 Overwrites some drive settings. This will replace the defaults set by the values in the header file. More...
 
void CodeRacer::set_drives_stop_left_right ()
 Stopps both drives. More...
 
void CodeRacer::set_drives_states_left_right (drivestate stateleft, drivestate stateright)
 Sets both of the drives to a specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) More...
 
void CodeRacer::set_drive_left_state (drivestate state)
 Sets the left side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) More...
 
void CodeRacer::set_drive_right_state (drivestate state)
 Sets the right side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) More...
 
void CodeRacer::set_drive_state (drivestate state, uint8_t frwdpin, uint8_t backpin)
 Sets the specified drivestate for the drive connected to the sepecified pins (DRIVESTOP, DRIVEFRWD, DRIVEBACK) More...
 
void CodeRacer::set_drives_speed_left_right (uint8_t speedleft, uint8_t speedright)
 Sets the speed for both of the drives. More...
 
void CodeRacer::set_drive_left_speed (uint8_t speed)
 Sets the speed for the left side drive. More...
 
void CodeRacer::set_drive_right_speed (uint8_t speed)
 Sets the speed for the right side drive. More...
 
void CodeRacer::set_drive_speed (uint8_t speed, uint8_t enablepin)
 Sets the speed for the drive of the enable pin connected to the specified pin. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ drives_settings()

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
void CodeRacer::drives_settings (uint8_t drive_left_speed,
uint8_t drive_right_speed,
unsigned long turn_left_for_ms,
unsigned long turn_right_for_ms 
)
-
- -

Overwrites some drive settings. This will replace the defaults set by the values in the header file.

-
Parameters
- - - - - -
drive_left_speedSpeed of the left side drive
drive_right_speedSpeed of the right side drive
turn_left_for_msTime in ms the racer will turn to the left around its center if turn_left() is called
turn_right_for_msTime in ms the racer will turn to the right around its center if turn_right() is called
-
-
-
Returns
nothing
- -

Definition at line 878 of file CodeRacer.cpp.

-
879 {
880  _drive_left_speed = drive_left_speed;
881  _drive_right_speed = drive_right_speed;
882  _turn_left_for_ms = turn_left_for_ms;
883  _turn_right_for_ms = turn_right_for_ms;
884 }
-
-
- -

◆ set_drives_stop_left_right()

- -
-
- - - - - - - -
void CodeRacer::set_drives_stop_left_right ()
-
- -

Stopps both drives.

-
Returns
nothing
- -

Definition at line 889 of file CodeRacer.cpp.

-
889  {
890  set_drive_left_state(DRIVESTOP);
891  set_drive_right_state(DRIVESTOP);
892 }
-
-
- -

◆ set_drives_states_left_right()

- -
-
- - - - - - - - - - - - - - - - - - -
void CodeRacer::set_drives_states_left_right (drivestate stateleft,
drivestate stateright 
)
-
- -

Sets both of the drives to a specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK)

-
Parameters
- - - -
stateleftdrivestate to set for the left side drive
staterightdrivestate to set for the right side drive
-
-
-
Returns
nothing
- -

Definition at line 899 of file CodeRacer.cpp.

-
899  {
900  set_drive_left_state(stateleft);
901  set_drive_right_state(stateright);
902 }
-
-
- -

◆ set_drive_left_state()

- -
-
- - - - - - - - -
void CodeRacer::set_drive_left_state (drivestate state)
-
- -

Sets the left side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK)

-
Parameters
- - -
statedrivestate to set for the left side drive
-
-
-
Returns
nothing
- -

Definition at line 908 of file CodeRacer.cpp.

-
908  {
909  set_drive_state(state, _drive_left_frwd_pin, _drive_left_back_pin);
910 }
-
-
- -

◆ set_drive_right_state()

- -
-
- - - - - - - - -
void CodeRacer::set_drive_right_state (drivestate state)
-
- -

Sets the right side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK)

-
Parameters
- - -
statedrivestate to set for the right side drive
-
-
-
Returns
nothing
- -

Definition at line 916 of file CodeRacer.cpp.

-
916  {
917  set_drive_state(state, _drive_right_frwd_pin, _drive_right_back_pin);
918 }
-
-
- -

◆ set_drive_state()

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - -
void CodeRacer::set_drive_state (drivestate state,
uint8_t frwdpin,
uint8_t backpin 
)
-
- -

Sets the specified drivestate for the drive connected to the sepecified pins (DRIVESTOP, DRIVEFRWD, DRIVEBACK)

-
Parameters
- - - - -
statedrivestate to set for the connected drive
frwdpinPin the forward signal of the drive device driver is connected at
backpinPin the backward signal of the drive device driver is connected at
-
-
-
Returns
nothing
- -

Definition at line 926 of file CodeRacer.cpp.

-
926  {
927  switch (state) {
928  case DRIVESTOP:
929  digitalWrite(frwdpin, LOW);
930  digitalWrite(backpin, LOW);
931  break;
932  case DRIVEFRWD:
933  digitalWrite(frwdpin, HIGH);
934  digitalWrite(backpin, LOW);
935  break;
936  case DRIVEBACK:
937  digitalWrite(frwdpin, LOW);
938  digitalWrite(backpin, HIGH);
939  break;
940  }
941 }
-
-
- -

◆ set_drives_speed_left_right()

- -
-
- - - - - - - - - - - - - - - - - - -
void CodeRacer::set_drives_speed_left_right (uint8_t speedleft,
uint8_t speedright 
)
-
- -

Sets the speed for both of the drives.

-

The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before

Parameters
- - - -
speedleftspeed of the left side drive. 0<=speed<=255
speedrightspeed of the right side drive. 0<=speed<=255
-
-
-
Returns
nothing
- -

Definition at line 950 of file CodeRacer.cpp.

-
950  {
951  set_drive_left_speed(speedleft);
952  set_drive_right_speed(speedright);
953 }
-
-
- -

◆ set_drive_left_speed()

- -
-
- - - - - - - - -
void CodeRacer::set_drive_left_speed (uint8_t speed)
-
- -

Sets the speed for the left side drive.

-

The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before

Parameters
- - -
speedspeed of the left side drive. 0<=speed<=255
-
-
-
Returns
nothing
- -

Definition at line 961 of file CodeRacer.cpp.

-
961  {
962  set_drive_speed(speed, _drive_left_enable_pin);
963 }
-
-
- -

◆ set_drive_right_speed()

- -
-
- - - - - - - - -
void CodeRacer::set_drive_right_speed (uint8_t speed)
-
- -

Sets the speed for the right side drive.

-

The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before

Parameters
- - -
speedspeed of the right side drive. 0<=speed<=255
-
-
-
Returns
nothing
- -

Definition at line 971 of file CodeRacer.cpp.

-
971  {
972  set_drive_speed(speed, _drive_right_enable_pin);
973 }
-
-
- -

◆ set_drive_speed()

- -
-
- - - - - - - - - - - - - - - - - - -
void CodeRacer::set_drive_speed (uint8_t speed,
uint8_t enablepin 
)
-
- -

Sets the speed for the drive of the enable pin connected to the specified pin.

-

The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before

Parameters
- - - -
speedspeed of the drive. 0<=speed<=255
enablepinPin the drives device driver enable pin is connected at
-
-
-
Returns
nothing
- -

Definition at line 982 of file CodeRacer.cpp.

-
982  {
983  _analog_write(enablepin, (int)speed);
984 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.js b/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.js deleted file mode 100644 index 5e1597f..0000000 --- a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.js +++ /dev/null @@ -1,13 +0,0 @@ -var group__lowerleveldrivesmeths = -[ - [ "drives_settings", "d1/d8a/group__lowerleveldrivesmeths.html#ga5812df751da5b480240ccd633c515b83", null ], - [ "set_drives_stop_left_right", "d1/d8a/group__lowerleveldrivesmeths.html#ga61ed9e0415a62a290cc5c59a0f740304", null ], - [ "set_drives_states_left_right", "d1/d8a/group__lowerleveldrivesmeths.html#ga802d2646d9cc0d766e1ac799c7917fa8", null ], - [ "set_drive_left_state", "d1/d8a/group__lowerleveldrivesmeths.html#ga1eeb3cb47503c3011562f9c42828fab9", null ], - [ "set_drive_right_state", "d1/d8a/group__lowerleveldrivesmeths.html#ga1b34ec9cee1f21cd15db310167a2faa5", null ], - [ "set_drive_state", "d1/d8a/group__lowerleveldrivesmeths.html#ga3b69cf4a718c842fbe758d3f4267214e", null ], - [ "set_drives_speed_left_right", "d1/d8a/group__lowerleveldrivesmeths.html#ga3d3ffb41783d34589e33cf61fed46c70", null ], - [ "set_drive_left_speed", "d1/d8a/group__lowerleveldrivesmeths.html#ga1ee3da20ec98a821ab97ced070974861", null ], - [ "set_drive_right_speed", "d1/d8a/group__lowerleveldrivesmeths.html#gaf8805d0d620a2fb78c576f36a2c81073", null ], - [ "set_drive_speed", "d1/d8a/group__lowerleveldrivesmeths.html#ga5d67c84606d5b39996a99fcd6e7eb314", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.map b/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.map deleted file mode 100644 index 14dbabc..0000000 --- a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.md5 b/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.md5 deleted file mode 100644 index 1c53b05..0000000 --- a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.md5 +++ /dev/null @@ -1 +0,0 @@ -f031a65379fe10c49a2f5864707d7064 \ No newline at end of file diff --git a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.png b/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.png deleted file mode 100644 index 44ef0c1..0000000 Binary files a/Doku/Doxygen/html/d1/d8a/group__lowerleveldrivesmeths.png and /dev/null differ diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.html b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.html deleted file mode 100644 index 0313cb5..0000000 --- a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.html +++ /dev/null @@ -1,597 +0,0 @@ - - - - - - - -Arduino {code}racer API: Methods - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Functions

void CodeRacer::stop_driving ()
 Stops the racer and sets status LEDs. More...
 
void CodeRacer::drive_forward ()
 Sets the speed and the directions of both drives so that it will move forward. More...
 
void CodeRacer::drive_forward (uint8_t left_speed, uint8_t right_speed)
 Sets the speed as specified for both drives and the directions of both drives so that it will move forward. More...
 
void CodeRacer::drive_backward ()
 Sets the speed and the directions of both drives so that it will move backward. More...
 
void CodeRacer::drive_backward (uint8_t left_speed, uint8_t right_speed)
 Sets the speed as specified for both drives and the directions of both drives so that it will move backward. More...
 
void CodeRacer::turn_left ()
 Will turn the racer to the left for the internally stroe time in ms and with the internally stored speed. More...
 
void CodeRacer::turn_left (unsigned long turn_for_ms)
 Will turn the racer to the left for the specified time in ms and with the internally stored speed. More...
 
void CodeRacer::turn_left (unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
 Will turn the racer to the left for the specified time in ms and with the specified speed. More...
 
void CodeRacer::turn_right ()
 Will turn the racer to the right for the internally stroe time in ms and with the internally stored speed. More...
 
void CodeRacer::turn_right (unsigned long turn_for_ms)
 Will turn the racer to the right for the specified time in ms and with the internally stored speed. More...
 
void CodeRacer::turn_right (unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
 Will turn the racer to the right for the specified time in ms and with the specified speed. More...
 
void CodeRacer::start_stop_at_min_distance ()
 Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance. More...
 
void CodeRacer::start_stop_at_min_distance (unsigned long min_distance_cm)
 Enables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. More...
 
void CodeRacer::stop_stop_at_min_distance ()
 Disables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. More...
 
bool CodeRacer::start_stop ()
 This will return if the codracer is in active mode or not. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ stop_driving()

- -
-
- - - - - - - -
void CodeRacer::stop_driving ()
-
- -

Stops the racer and sets status LEDs.

-
Returns
nothing
- -

Definition at line 161 of file CodeRacer.cpp.

-
161  {
162  _servo_sweep = false;
163  _drive = false;
164  set_drives_stop_left_right();
165  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
166 }
-
-
- -

◆ drive_forward() [1/2]

- -
-
- - - - - - - -
void CodeRacer::drive_forward ()
-
- -

Sets the speed and the directions of both drives so that it will move forward.

-

The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section

Returns
nothing
- -

Definition at line 173 of file CodeRacer.cpp.

-
174 {
175  drive_forward(_drive_left_speed, _drive_right_speed);
176 }
- + Here is the call graph for this function:
-
-
- - -
-
- -

◆ drive_forward() [2/2]

- -
-
- - - - - - - - - - - - - - - - - - -
void CodeRacer::drive_forward (uint8_t left_speed,
uint8_t right_speed 
)
-
- -

Sets the speed as specified for both drives and the directions of both drives so that it will move forward.

-

The specified speed values for both drives will be stored internaly so next time if you use e.g. drive_forward() exactly the here specified values will be taken.

Parameters
- - - -
left_speedspeed for the left side drive. 0<=speed<=255
right_speedspeed for the right side drive. 0<=speed<=255
-
-
-
Returns
nothing
- -

Definition at line 185 of file CodeRacer.cpp.

-
186 {
187  set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD);
188  set_drives_speed_left_right(left_speed, right_speed);
189  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
190  _drive = true;
191  _drive_set_at_ms = millis();
192 }
-
-
- -

◆ drive_backward() [1/2]

- -
-
- - - - - - - -
void CodeRacer::drive_backward ()
-
- -

Sets the speed and the directions of both drives so that it will move backward.

-

The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section

Returns
nothing
- -

Definition at line 199 of file CodeRacer.cpp.

-
200 {
201  drive_backward(_drive_left_speed, _drive_right_speed);
202 }
-
-
- -

◆ drive_backward() [2/2]

- -
-
- - - - - - - - - - - - - - - - - - -
void CodeRacer::drive_backward (uint8_t left_speed,
uint8_t right_speed 
)
-
- -

Sets the speed as specified for both drives and the directions of both drives so that it will move backward.

-

The specified speed values for both drives will be stored internaly so next time if you use e.g. drive_backward() exactly the here specified values will be taken.

Parameters
- - - -
left_speedspeed for the left side drive. 0<=speed<=255
right_speedspeed for the right side drive. 0<=speed<=255
-
-
-
Returns
nothing
- -

Definition at line 211 of file CodeRacer.cpp.

-
212 {
213  set_drives_states_left_right(DRIVEBACK, DRIVEBACK);
214  set_drives_speed_left_right(left_speed, right_speed);
215  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDON, LEDOFF);
216  _drive = true;
217  _drive_set_at_ms = millis();
218 }
-
-
- -

◆ turn_left() [1/3]

- -
-
- - - - - - - -
void CodeRacer::turn_left ()
-
- -

Will turn the racer to the left for the internally stroe time in ms and with the internally stored speed.

-

The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to left time can be set by thoose methods as well. The method is delayed until the racer has turned.

Returns
nothing
- -

Definition at line 226 of file CodeRacer.cpp.

-
227 {
228  turn_left(_turn_left_for_ms, _drive_left_speed, _drive_right_speed);
229 }
-
-
- -

◆ turn_left() [2/3]

- -
-
- - - - - - - - -
void CodeRacer::turn_left (unsigned long turn_for_ms)
-
- -

Will turn the racer to the left for the specified time in ms and with the internally stored speed.

-

The specified duration of time is stored internally and will be used next time by e.g. turn_left()

Parameters
- - -
turn_for_msduration of time in ms to turn the racer
-
-
-
Returns
nothing
- -

Definition at line 237 of file CodeRacer.cpp.

-
238 {
239  turn_left(turn_for_ms, _drive_left_speed, _drive_right_speed);
240 }
-
-
- -

◆ turn_left() [3/3]

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - -
void CodeRacer::turn_left (unsigned long turn_for_ms,
uint8_t left_speed,
uint8_t right_speed 
)
-
- -

Will turn the racer to the left for the specified time in ms and with the specified speed.

-

The specified duration of time and the specified speeds are stored internally and will be used next time by e.g. turn_left()

Parameters
- - - - -
turn_for_msduration of time in ms to turn the racer
left_speedspeed for the left side drive
right_speedspeed for the right side drive
-
-
-
Returns
nothing
- -

Definition at line 250 of file CodeRacer.cpp.

-
251 {
252  _drive = false;
253  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
254  set_drives_states_left_right(DRIVEBACK, DRIVEFRWD);
255  set_drives_speed_left_right(left_speed, right_speed);
256  // wait set delay for the timed turn
257  _turn_left_for_ms = turn_for_ms;
258  delay(_turn_left_for_ms);
259  // stop drives again
260  set_drives_stop_left_right();
261 }
-
-
- -

◆ turn_right() [1/3]

- -
-
- - - - - - - -
void CodeRacer::turn_right ()
-
- -

Will turn the racer to the right for the internally stroe time in ms and with the internally stored speed.

-

The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to right time can be set by thoose methods as well. The method is delayed until the racer has turned.

Returns
nothing
- -

Definition at line 269 of file CodeRacer.cpp.

-
270 {
271  turn_right(_turn_right_for_ms, _drive_left_speed, _drive_right_speed);
272 }
-
-
- -

◆ turn_right() [2/3]

- -
-
- - - - - - - - -
void CodeRacer::turn_right (unsigned long turn_for_ms)
-
- -

Will turn the racer to the right for the specified time in ms and with the internally stored speed.

-

The specified duration of time is stored internally and will be used next time by e.g. turn_right()

Parameters
- - -
turn_for_msduration of time in ms to turn the racer
-
-
-
Returns
nothing
- -

Definition at line 280 of file CodeRacer.cpp.

-
281 {
282  turn_right(turn_for_ms, _drive_left_speed, _drive_right_speed);
283 }
-
-
- -

◆ turn_right() [3/3]

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - -
void CodeRacer::turn_right (unsigned long turn_for_ms,
uint8_t left_speed,
uint8_t right_speed 
)
-
- -

Will turn the racer to the right for the specified time in ms and with the specified speed.

-

The specified duration of time and the specified speeds are stored internally and will be used next time by e.g. turn_right()

Parameters
- - - - -
turn_for_msduration of time in ms to turn the racer
left_speedspeed for the left side drive
right_speedspeed for the right side drive
-
-
-
Returns
nothing
- -

Definition at line 293 of file CodeRacer.cpp.

-
294 {
295  _drive = false;
296  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); // LEDs setzen
297  set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
298  set_drives_speed_left_right(left_speed, right_speed);
299  // wait set delay for the timed turn
300  _turn_right_for_ms = turn_for_ms;
301  delay(_turn_right_for_ms);
302  // stop drives again
303  set_drives_stop_left_right();
304 }
-
-
- -

◆ start_stop_at_min_distance() [1/2]

- -
-
- - - - - - - -
void CodeRacer::start_stop_at_min_distance ()
-
- -

Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance.

-

This allow all of the none-single shot ultra sonic measurement methods to stopp the racer in the case the measured distance is smaller than minimal distance. This is just the enablement - you have to call one of the none-single-shot ultra sonic measurement methods continously while driving and maybe sweeping the servo. If the racer was stopped can be checked with stopped_at_min_distance() - it will return true in that case. The minimal distance can be set by the ultrasonic sensor setter methods. There is an example coming with the coderacer libary that you can load and get an idea how that works.

Returns
nothing
- -

Definition at line 314 of file CodeRacer.cpp.

-
314  {
315  start_stop_at_min_distance(_usonic_stop_distance_cm);
316 }
-
-
- -

◆ start_stop_at_min_distance() [2/2]

- -
-
- - - - - - - - -
void CodeRacer::start_stop_at_min_distance (unsigned long min_distance_cm)
-
- -

Enables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance.

-

This is almos the same as described for start_stop_at_min_distance(). You can specify the distance in cm here - this value will be stored internally and used by start_stop_at_min_distance() next time.

Parameters
- - -
min_distance_cmthe minimal disctance in cm
-
-
-
Returns
nothing
- -

Definition at line 324 of file CodeRacer.cpp.

-
324  {
325  if (false == _coderacer_stop_at_distance_enabled) {
326  _coderacer_stopped_at_min_distance = false;
327  usonic_set_stop_distance_cm(min_distance_cm);
328  _coderacer_stop_at_distance_enabled = true;
329  }
330 }
-
-
- -

◆ stop_stop_at_min_distance()

- -
-
- - - - - - - -
void CodeRacer::stop_stop_at_min_distance ()
-
- -

Disables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance.

-
Returns
nothing
- -

Definition at line 335 of file CodeRacer.cpp.

-
335  {
336  _coderacer_stop_at_distance_enabled = false;
337 }
-
-
- -

◆ start_stop()

- -
-
- - - - - - - -
bool CodeRacer::start_stop ()
-
- -

This will return if the codracer is in active mode or not.

-

There is a button used to toogle between active and inactive each time it is pressed This may help you to start driving and scanning the distance by pressing the button - and as well to stop the racer by pressing the button. This method will set the LEDs depending on the mode and sets the servo back to center and stopps the racer when leaving the active mode. You can leave or enter the active mode as well by setting using set_active() and set_inactive(). The button itself triggers and internall interrupt event and sets the active state - but you have to continously call that method to switch between inactive and active mode depending on the active state. If in inactive mode and fun is enabeld by just setting the coderacer_fun_enabled = true ... some fun will happen :-)

-
Returns
True if the coderacer is in active mode. False if in inactive mode.
- -

Definition at line 348 of file CodeRacer.cpp.

-
348  {
349  if (_coderracer_activ != coderracer_activ) {
350  _coderracer_activ = coderracer_activ;
351  if (true == _coderracer_activ) {
352  set_leds_all_off();
353  delay(500);
354  }
355  else {
356  stop_driving();
357  set_leds_all_on();
358  delay(200);
359  servo_set_to_center();
360  _servo_look_around_at_ms = millis() + random(20000, 120000);
361  }
362  }
363 
364  if ((false == _coderracer_activ) && (true == coderacer_fun_enabled)) {
365  kitt();
366  look_around();
367  }
368 
369  return(_coderracer_activ);
370 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.js b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.js deleted file mode 100644 index 4107571..0000000 --- a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.js +++ /dev/null @@ -1,18 +0,0 @@ -var group__higherlevelmeths = -[ - [ "stop_driving", "d2/d40/group__higherlevelmeths.html#ga71df7ac5e41ae776a6c786d3dc36f35a", null ], - [ "drive_forward", "d2/d40/group__higherlevelmeths.html#ga8be6a850099812153dcf5768d7fc8b8c", null ], - [ "drive_forward", "d2/d40/group__higherlevelmeths.html#gaae6fc379ec43cbe2cb2f63fbd12dbe0d", null ], - [ "drive_backward", "d2/d40/group__higherlevelmeths.html#ga98aa8a5a46f769d59e6c1067c8418cfb", null ], - [ "drive_backward", "d2/d40/group__higherlevelmeths.html#ga6cd8356ac76360b014db6170276b6b30", null ], - [ "turn_left", "d2/d40/group__higherlevelmeths.html#ga86b7caf6ff46e9d1ad90ed507864b175", null ], - [ "turn_left", "d2/d40/group__higherlevelmeths.html#ga30e1ec3fbbc206f93ea66dbf91b5fd95", null ], - [ "turn_left", "d2/d40/group__higherlevelmeths.html#gae6daa587199e5bf95b1aac675de53b0e", null ], - [ "turn_right", "d2/d40/group__higherlevelmeths.html#ga8969fb2d6e2b5ac44a99197931e6b8da", null ], - [ "turn_right", "d2/d40/group__higherlevelmeths.html#gae1f175aad98d773b0206f483ae0bb4ea", null ], - [ "turn_right", "d2/d40/group__higherlevelmeths.html#gad10b3457489cc7e25ffb4d64c539528a", null ], - [ "start_stop_at_min_distance", "d2/d40/group__higherlevelmeths.html#ga128683caea019a89bce06f722ba92556", null ], - [ "start_stop_at_min_distance", "d2/d40/group__higherlevelmeths.html#ga64bc1b2a8ed5bc3ec5e706fa70a1385d", null ], - [ "stop_stop_at_min_distance", "d2/d40/group__higherlevelmeths.html#gac664109241d08b8dc52db5721f394b22", null ], - [ "start_stop", "d2/d40/group__higherlevelmeths.html#ga34e2fe2123e76fd844482dfef6c5a9c8", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.map b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.map deleted file mode 100644 index 51f5bdc..0000000 --- a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.md5 b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.md5 deleted file mode 100644 index 6cd42f5..0000000 --- a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.md5 +++ /dev/null @@ -1 +0,0 @@ -14fcbf5ea95fbca4940db3735dae3e20 \ No newline at end of file diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.png b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.png deleted file mode 100644 index 1fcdd7c..0000000 Binary files a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths.png and /dev/null differ diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.map b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.map deleted file mode 100644 index 0d345a1..0000000 --- a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.map +++ /dev/null @@ -1,2 +0,0 @@ - - diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.md5 b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.md5 deleted file mode 100644 index 257acdd..0000000 --- a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -88ea8cb2a7473284c7f30fcb34c5462f \ No newline at end of file diff --git a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.png b/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.png deleted file mode 100644 index fd01ac4..0000000 Binary files a/Doku/Doxygen/html/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.png and /dev/null differ diff --git a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.html b/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.html deleted file mode 100644 index 5cd2e10..0000000 --- a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -Arduino {code}racer API: Lower level servo drive methods and getters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
- -
-
Lower level servo drive methods and getters
-
-
- - - - - - -

-Modules

 Methods
 
 Getters
 
-

Detailed Description

-
-
- - - - diff --git a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.js b/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.js deleted file mode 100644 index 09ed28b..0000000 --- a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.js +++ /dev/null @@ -1,5 +0,0 @@ -var group__lowerlevelservo = -[ - [ "Methods", "db/dd5/group__lowerlevelservomeths.html", "db/dd5/group__lowerlevelservomeths" ], - [ "Getters", "d4/df4/group__lowerlevelservogetters.html", "d4/df4/group__lowerlevelservogetters" ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.map b/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.map deleted file mode 100644 index 1282428..0000000 --- a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.map +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.md5 b/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.md5 deleted file mode 100644 index c2b7c49..0000000 --- a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.md5 +++ /dev/null @@ -1 +0,0 @@ -580a059516c5c4bee6990866828766d5 \ No newline at end of file diff --git a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.png b/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.png deleted file mode 100644 index 517e734..0000000 Binary files a/Doku/Doxygen/html/d3/d17/group__lowerlevelservo.png and /dev/null differ diff --git a/Doku/Doxygen/html/d4/da7/_code_racer_8cpp_source.html b/Doku/Doxygen/html/d4/da7/_code_racer_8cpp_source.html deleted file mode 100644 index d7adb1b..0000000 --- a/Doku/Doxygen/html/d4/da7/_code_racer_8cpp_source.html +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - -Arduino {code}racer API: C:/Users/jnoack/Documents/Arduino/libraries/CodeRacer/CodeRacer.cpp Source File - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
-
-
CodeRacer.cpp
-
-
-
1 // the compiler switch for an ESP8266 is looking like this: #elif defined(ARDUINO_ARCH_ESP8266)
2 #include "CodeRacer.h"
3 
7 CodeRacer::CodeRacer()
8 {
9  _button_pin = H_BUTTON_PIN;
10  _servo_pin = H_SERVO_PIN;
11  _us_trigger_pin = H_US_TRIG_PIN;
12  _us_echo_pin = H_US_ECHO_PIN;
13  _drive_left_frwd_pin = H_DRIVE_LEFT_FWRD_PIN;
14  _drive_left_back_pin = H_DRIVE_LEFT_BACK_PIN;
15  _drive_left_enable_pin = H_DRIVE_LEFT_ENABLE_PIN;
16  _drive_right_frwd_pin = H_DRIVE_RIGHT_FWRD_PIN;
17  _drive_right_back_pin = H_DRIVE_RIGHT_BACK_PIN;
18  _drive_right_enable_pin = H_DRIVE_RIGHT_ENABLE_PIN;
19  _led_frwd_pin = H_LED_FRWD_PIN;
20  _led_stop_pin = H_LED_STOP_PIN;
21  _led_left_pin = H_LED_LEFT_PIN;
22  _led_right_pin = H_LED_RIGHT_PIN;
23 }
24 
42 CodeRacer::CodeRacer(uint8_t button_pin , uint8_t servo_pin,
43  uint8_t us_trigger_pin, uint8_t us_echo_pin,
44  uint8_t drive_left_frwd_pin, uint8_t drive_left_back_pin, uint8_t drive_left_enable_pin,
45  uint8_t drive_right_frwd_pin, uint8_t drive_right_back_pin, uint8_t drive_right_enable_pin,
46  uint8_t led_frwd_pin, uint8_t led_stop_pin, uint8_t led_left_pin, uint8_t led_right_pin
47 )
48 {
49  _button_pin = button_pin;
50  _servo_pin = servo_pin;
51  _us_trigger_pin = us_trigger_pin;
52  _us_echo_pin = us_echo_pin;
53  _drive_left_frwd_pin = drive_left_frwd_pin;
54  _drive_left_back_pin = drive_left_back_pin;
55  _drive_left_enable_pin = drive_left_enable_pin;
56  _drive_right_frwd_pin = drive_right_frwd_pin;
57  _drive_right_back_pin = drive_right_back_pin;
58  _drive_right_enable_pin = drive_right_enable_pin;
59  _led_frwd_pin = led_frwd_pin;
60  _led_stop_pin = led_stop_pin;
61  _led_left_pin = led_left_pin;
62  _led_right_pin = led_right_pin;
63 }
64 
68 void CodeRacer::begin() {
69 
70  // init of variables and objects
71 
72  _servo_dummy = new Servo(); // the dummy is needed so far to avoid conflicts with analog write
73  _servo = new Servo();
74  servo_center_pos = H_SERVO_CENTER_POS;
75  servo_left_pos = H_SERVO_LEFT_POS;
76  servo_right_pos = H_SERVO_RIGHT_POS;
77  servo_sweep_left_pos = H_SERVO_SWEEP_LEFT_POS;
78  servo_sweep_right_pos = H_SERVO_SWEEP_RIGHT_POS;
79  _servo_position = servo_center_pos;
80  _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP;
81  _servo_position_set_at_ms = millis();
82  _servo_position_eta_in_ms = 0;
83 
84  _drive_left_speed = H_DRIVE_LEFT_SPEED;
85  _drive_right_speed = H_DRIVE_RIGHT_SPEED;
86 
87  _turn_left_for_ms = H_RACER_TURN_LEFT_FOR_MS;
88  _turn_right_for_ms = H_RACER_TURN_RIGHT_FOR_MS;
89 
90  coderracer_activ = false;
91  _coderracer_activ = true;
92  _drive = false;
93  _drive_set_at_ms = millis();
94  _servo_sweep = false;
95 
96  _last_led_switched_at_ms = millis();
97  _last_led_on = 0;
98  _led_count = 3;
99 
100  _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
101 
102  _usonic_stop_distance_cm = H_US_STOP_DISTANCE_CM;
103  usonic_set_stop_distance_cm(_usonic_stop_distance_cm);
104  _coderacer_stopped_at_min_distance = false;
105 
106  // Ultrasonic sensor
107  pinMode(_us_trigger_pin, OUTPUT);
108  pinMode(_us_echo_pin, INPUT);
109 
110  // Servo drive
111  _servo->attach(_servo_pin);
112 
113  // Left drive
114  pinMode(_drive_left_frwd_pin, OUTPUT);
115  pinMode(_drive_left_back_pin, OUTPUT);
116  set_drive_left_state(DRIVESTOP);
117  ledcSetup(DRIVE_PWM_LEFT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width
118  ledcAttachPin(_drive_left_enable_pin, DRIVE_PWM_LEFT_CHANNEL); // connect left drive enable with PWM channel
119 
120  // Right drive
121  pinMode(_drive_right_frwd_pin, OUTPUT);
122  pinMode(_drive_right_back_pin, OUTPUT);
123  set_drive_right_state(DRIVESTOP);
124  ledcSetup(DRIVE_PWM_RIGHT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width
125  ledcAttachPin(_drive_right_enable_pin, DRIVE_PWM_RIGHT_CHANNEL); // connect right drive enable pin with PWM channel
126 
127  // LEDs
128  pinMode(_led_frwd_pin, OUTPUT);
129  pinMode(_led_stop_pin, OUTPUT);
130  pinMode(_led_left_pin, OUTPUT);
131  pinMode(_led_right_pin, OUTPUT);
132  // all LEDS off
133  set_leds_all_off();
134 
135  // Button & -interrupt
136  button_last_pressed_at_ms = 0;
137  pinMode(_button_pin, INPUT_PULLUP);
138  attachInterrupt(digitalPinToInterrupt(_button_pin), _set_button_state, FALLING);
139 
140  // Random
141  randomSeed(analogRead(0));
142 
143  //fun stuff
144  coderacer_fun_enabled = false;
145 
146 }
147 
148 //**************************************
149 //*** Coderacer hihger level methods ***
150 //**************************************
161 void CodeRacer::stop_driving() {
162  _servo_sweep = false;
163  _drive = false;
164  set_drives_stop_left_right();
165  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
166 }
167 
173 void CodeRacer::drive_forward()
174 {
175  drive_forward(_drive_left_speed, _drive_right_speed);
176 }
177 
185 void CodeRacer::drive_forward(uint8_t left_speed, uint8_t right_speed)
186 {
187  set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD);
188  set_drives_speed_left_right(left_speed, right_speed);
189  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
190  _drive = true;
191  _drive_set_at_ms = millis();
192 }
193 
199 void CodeRacer::drive_backward()
200 {
201  drive_backward(_drive_left_speed, _drive_right_speed);
202 }
203 
211 void CodeRacer::drive_backward(uint8_t left_speed, uint8_t right_speed)
212 {
213  set_drives_states_left_right(DRIVEBACK, DRIVEBACK);
214  set_drives_speed_left_right(left_speed, right_speed);
215  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDON, LEDOFF);
216  _drive = true;
217  _drive_set_at_ms = millis();
218 }
219 
226 void CodeRacer::turn_left()
227 {
228  turn_left(_turn_left_for_ms, _drive_left_speed, _drive_right_speed);
229 }
230 
237 void CodeRacer::turn_left(unsigned long turn_for_ms)
238 {
239  turn_left(turn_for_ms, _drive_left_speed, _drive_right_speed);
240 }
241 
250 void CodeRacer::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
251 {
252  _drive = false;
253  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
254  set_drives_states_left_right(DRIVEBACK, DRIVEFRWD);
255  set_drives_speed_left_right(left_speed, right_speed);
256  // wait set delay for the timed turn
257  _turn_left_for_ms = turn_for_ms;
258  delay(_turn_left_for_ms);
259  // stop drives again
260  set_drives_stop_left_right();
261 }
262 
269 void CodeRacer::turn_right()
270 {
271  turn_right(_turn_right_for_ms, _drive_left_speed, _drive_right_speed);
272 }
273 
280 void CodeRacer::turn_right(unsigned long turn_for_ms)
281 {
282  turn_right(turn_for_ms, _drive_left_speed, _drive_right_speed);
283 }
284 
293 void CodeRacer::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
294 {
295  _drive = false;
296  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); // LEDs setzen
297  set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
298  set_drives_speed_left_right(left_speed, right_speed);
299  // wait set delay for the timed turn
300  _turn_right_for_ms = turn_for_ms;
301  delay(_turn_right_for_ms);
302  // stop drives again
303  set_drives_stop_left_right();
304 }
305 
314 void CodeRacer::start_stop_at_min_distance() {
315  start_stop_at_min_distance(_usonic_stop_distance_cm);
316 }
317 
324 void CodeRacer::start_stop_at_min_distance(unsigned long min_distance_cm) {
325  if (false == _coderacer_stop_at_distance_enabled) {
326  _coderacer_stopped_at_min_distance = false;
327  usonic_set_stop_distance_cm(min_distance_cm);
328  _coderacer_stop_at_distance_enabled = true;
329  }
330 }
331 
335 void CodeRacer::stop_stop_at_min_distance() {
336  _coderacer_stop_at_distance_enabled = false;
337 }
338 
348 bool CodeRacer::start_stop() {
349  if (_coderracer_activ != coderracer_activ) {
350  _coderracer_activ = coderracer_activ;
351  if (true == _coderracer_activ) {
352  set_leds_all_off();
353  delay(500);
354  }
355  else {
356  stop_driving();
357  set_leds_all_on();
358  delay(200);
359  servo_set_to_center();
360  _servo_look_around_at_ms = millis() + random(20000, 120000);
361  }
362  }
363 
364  if ((false == _coderracer_activ) && (true == coderacer_fun_enabled)) {
365  kitt();
366  look_around();
367  }
368 
369  return(_coderracer_activ);
370 }
371  // end of group higherlevelmeths
380 bool CodeRacer::stopped_at_min_distance() {
381  return(_coderacer_stopped_at_min_distance);
382 }
383 
387 bool CodeRacer::is_driving() {
388  return(_drive);
389 }
390 
394 unsigned long CodeRacer::turn_left_for_ms() {
395  return(_turn_left_for_ms);
396 }
397 
401 unsigned long CodeRacer::turn_right_for_ms() {
402  return(_turn_right_for_ms);
403 }
404 
408 void CodeRacer::set_inactive() {
409  coderracer_activ = false;
410 }
411 
415 void CodeRacer::set_active() {
416  coderracer_activ = true;
417 }
418 
424 bool CodeRacer::is_active() {
425  return(coderracer_activ);
426 }
427  // end of group higherlevelgetters // end of group higherlevel
430 
431 //**************************************
432 //*** Just for fun ***
433 //**************************************
440 void CodeRacer::look_around()
441 {
442  if (_servo_look_around_at_ms < millis()) {
443  _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
444  servo_set_to_left();
445  delay(500);
446  servo_set_to_right();
447  delay(800);
448  servo_set_to_center();
449  delay(300);
450  servo_set_to_left();
451  delay(100);
452  servo_set_to_center();
453  }
454 }
455 
459 void CodeRacer::kitt()
460 {
461  if (millis() - _last_led_switched_at_ms > LED_SWITCH_MS) {
462  _last_led_switched_at_ms = millis();
463  if (_last_led_on >= 5) {
464  _led_count = -1;
465  }
466  else if (_last_led_on <= 0) {
467  _led_count = 1;
468  }
469  _last_led_on = _last_led_on + _led_count;
470  switch (_last_led_on) {
471  case 0:
472  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
473  break;
474  case 1:
475  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
476  break;
477  case 2:
478  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
479  break;
480  case 3:
481  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
482  break;
483  case 4:
484  case 5:
485  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON);
486  break;
487  }
488  }
489 }
490  // end of group lowerlevelfun
492 
493 //**************************************
494 //*** Servo drive lower level control ***
495 //**************************************
510 void CodeRacer::servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos)
511 {
512  servo_center_pos = pos_center;
513  servo_left_pos = pos_left;
514  servo_right_pos = pos_right;
515  servo_sweep_left_pos = sweep_left_pos;
516  servo_sweep_right_pos = sweep_right_pos;
517 }
518 
526 void CodeRacer::servo_sweep()
527 {
528  uint8_t position;
529  _servo_sweep = true;
530  if (millis() - _servo_position_set_at_ms > SERVO_SWEEP_MS) {
531  position = _servo_position + _servo_sweep_step;
532  //sprintf(_debugmsg,"[%s] current position=%ld newpostion=%ld", __func__, _servo_position, position);
533  if ((position >= servo_sweep_left_pos) || (position >= SERVO_MAX_POSITION)) {
534  position = servo_sweep_left_pos;
535  _servo_sweep_step = SERVO_SWEEP_TO_RIGHT_STEP;
536  }
537  if ((position <= servo_sweep_right_pos) || (position <= SERVO_MIN_POSITION)) {
538  position = servo_sweep_right_pos;
539  _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP;
540  }
541  _servo_set_position(position);
542  }
543 }
544 
548 void CodeRacer::servo_set_to_right()
549 {
550  servo_set_position_wait(servo_right_pos);
551 }
552 
556 void CodeRacer::servo_set_to_left()
557 {
558  servo_set_position_wait(servo_left_pos);
559 }
560 
564 void CodeRacer::servo_set_to_center()
565 {
566  servo_set_position_wait(servo_center_pos);
567 }
568 
575 uint8_t CodeRacer::servo_set_position_wait(uint8_t position)
576 {
577  _servo_sweep = false;
578  unsigned long wait_time_ms = _servo_set_position(position);
579  delay(wait_time_ms);
580  return(_servo_position);
581 }
582 
589 unsigned long CodeRacer::servo_set_position(uint8_t position)
590 {
591  _servo_sweep = false;
592  unsigned long wait_time_ms = _servo_set_position(position);
593  return(wait_time_ms);
594 }
595 
596 unsigned long CodeRacer::_servo_set_position(uint8_t position)
597 {
598  uint8_t _position = position;
599  uint8_t absdiff;
600 
601  if (position < SERVO_MIN_POSITION) {
602  _position = SERVO_MIN_POSITION;
603  }
604  else if (position > SERVO_MAX_POSITION) {
605  _position = SERVO_MAX_POSITION;
606  }
607  _servo->write(_position);
608  // wait minimal delay to avoid code collaps
609  delay(SERVO_SET_1TICK_POSITION_DELAY_MS);
610  absdiff = abs(_servo_position - _position);
611  if (absdiff > 1) {
612  _servo_position_eta_in_ms = absdiff * SERVO_SET_1TICK_POSITION_DELAY_MS;
613  }
614  else {
615  _servo_position_eta_in_ms = 0;
616  }
617 
618  _servo_position_set_at_ms = millis();
619  _servo_position = _position;
620 
621  return(_servo_position_eta_in_ms);
622 }
623  // end of group lowerlevelservomeths
632 uint8_t CodeRacer::servo_position() {
633  return(_servo_position);
634 }
635 
639 unsigned long CodeRacer::servo_position_set_at_ms() {
640  return(_servo_position_set_at_ms);
641 }
642 
649 unsigned long CodeRacer::servo_position_eta_in_ms() {
650  return(_servo_position_eta_in_ms);
651 }
652  // end of group lowerlevelservogetters // end of group lowerlevelservo
655 
656 
657 //**************************************
658 //*** Ultrasonic lower level control ***
659 //**************************************
672 unsigned long CodeRacer::usonic_measure_cm()
673 {
674  return(usonic_measure_cm(US_MAX_ECHO_TIME_US));
675 }
676 
682 unsigned long CodeRacer::usonic_measure_us()
683  {
684  return(usonic_measure_us(US_MAX_ECHO_TIME_US));
685  }
686 
694 unsigned long CodeRacer::usonic_measure_cm(unsigned long max_echo_run_time_us)
695 {
696  unsigned long echo_runtime_us = usonic_measure_us(max_echo_run_time_us);
697  unsigned long distance_cm = echo_runtime_us * 0.0172;
698  //Serial.print("MEASURE_DISTANCE. Distance in cm is: ");
699  //Serial.println(distance_cm);
700  _usonic_distance_cm = distance_cm;
701  return(distance_cm);
702 }
703 
711 unsigned long CodeRacer::usonic_measure_us(unsigned long max_echo_run_time_us)
712 {
713  unsigned long echo_runtime_us[3] = { 0,0,0 };
714  uint8_t measnr = 0;
715 
716  do {
717  echo_runtime_us[measnr] = usonic_measure_single_shot_us(max_echo_run_time_us);
718  if (echo_runtime_us[measnr] > 200) {
719  measnr++;
720  }
721  } while (measnr < 3);
722 
723  // we will take the medium out of 3 values ...
724  if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); }
725  if (echo_runtime_us[1] > echo_runtime_us[2]) { std::swap(echo_runtime_us[1], echo_runtime_us[2]); }
726  if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); }
727 
728  //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: ");
729  //Serial.println(echo_runtime_us[1]);
730 
731  // if the stop at minimal distance is enabeled - check for minimal distance is reached
732  if (true == _coderacer_stop_at_distance_enabled) {
733  if (echo_runtime_us[1] <= _usonic_stop_distance_us) {
734  _coderacer_stopped_at_min_distance = true;
735  stop_driving();
736  _coderacer_stop_at_distance_enabled = false;
737  }
738  }
739  _usonic_distance_us = echo_runtime_us[1];
740  return(echo_runtime_us[1]);
741 }
742 
748 unsigned long CodeRacer::usonic_measure_single_shot_cm()
749 {
750  return(usonic_measure_single_shot_cm(US_MAX_ECHO_TIME_US));
751 }
752 
758 unsigned long CodeRacer::usonic_measure_single_shot_us()
759 {
760  return(usonic_measure_single_shot_us(US_MAX_ECHO_TIME_US));
761 }
762 
770 unsigned long CodeRacer::usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us)
771 {
772  // convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec
773  // the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one
774  // distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172
775  // distance_cm = (echo_duration/2) / 29.1;
776  unsigned long echo_runtime_us = usonic_measure_single_shot_us(max_echo_run_time_us);
777  unsigned long distance_cm = echo_runtime_us * 0.0172;
778  //Serial.print("MEASURE_DISTANCE. Distance in cm is: ");
779  //Serial.println(distance_cm);
780  _usonic_distance_cm = distance_cm;
781  return(distance_cm);
782 }
783 
791 unsigned long CodeRacer::usonic_measure_single_shot_us(unsigned long max_echo_run_time_us)
792  {
793  unsigned long echo_runtime_us;
794  // start measurement - send a short pulse "HIGH" to the TRIG pin of the ultrasonic sensor
795  pinMode(_us_echo_pin, OUTPUT);
796  pinMode(_us_echo_pin, INPUT);
797  digitalWrite(_us_trigger_pin, LOW);
798  delayMicroseconds(2);
799  digitalWrite(_us_trigger_pin, HIGH);
800  delayMicroseconds(10);
801  digitalWrite(_us_trigger_pin, LOW);
802  // measure runtime in microseconds until the ECHO pin aof the sensor goes HIGH
803  echo_runtime_us = pulseInLong(_us_echo_pin, HIGH, max_echo_run_time_us);
804  if (echo_runtime_us == 0) {
805  echo_runtime_us = max_echo_run_time_us; // US_MAX_ECHO_TIME_US;
806  }
807  //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: ");
808  //Serial.println(echo_runtime_us);
809  _usonic_distance_us = echo_runtime_us;
810  return(echo_runtime_us);
811  }
812  // end of group lowerlevelusmethods
825 void CodeRacer::usonic_set_stop_distance_cm(unsigned long stop_distance_cm)
826 {
827  _usonic_stop_distance_us = stop_distance_cm * 58.14;
828 }
829 
837 void CodeRacer::usonic_set_stop_distance_us(unsigned long stop_distance_us)
838 {
839  _usonic_stop_distance_us = stop_distance_us;
840 }
841 
845 unsigned long CodeRacer::usonic_distance_us() {
846  return(_usonic_distance_us);
847 }
848 
852 unsigned long CodeRacer::usonic_distance_cm() {
853  return(_usonic_distance_cm);
854 }
855  // end of group lowerlevelusgetters // end of group lowerlevelus
858 
859 
860 //**************************************
861 //*** Drives lower level control ***
862 //**************************************
863 
878 void CodeRacer::drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_for_ms, unsigned long turn_right_for_ms)
879 {
880  _drive_left_speed = drive_left_speed;
881  _drive_right_speed = drive_right_speed;
882  _turn_left_for_ms = turn_left_for_ms;
883  _turn_right_for_ms = turn_right_for_ms;
884 }
885 
889 void CodeRacer::set_drives_stop_left_right() {
890  set_drive_left_state(DRIVESTOP);
891  set_drive_right_state(DRIVESTOP);
892 }
893 
899 void CodeRacer::set_drives_states_left_right(drivestate stateleft, drivestate stateright) {
900  set_drive_left_state(stateleft);
901  set_drive_right_state(stateright);
902 }
903 
908 void CodeRacer::set_drive_left_state(drivestate state) {
909  set_drive_state(state, _drive_left_frwd_pin, _drive_left_back_pin);
910 }
911 
916 void CodeRacer::set_drive_right_state(drivestate state) {
917  set_drive_state(state, _drive_right_frwd_pin, _drive_right_back_pin);
918 }
919 
926 void CodeRacer::set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin) {
927  switch (state) {
928  case DRIVESTOP:
929  digitalWrite(frwdpin, LOW);
930  digitalWrite(backpin, LOW);
931  break;
932  case DRIVEFRWD:
933  digitalWrite(frwdpin, HIGH);
934  digitalWrite(backpin, LOW);
935  break;
936  case DRIVEBACK:
937  digitalWrite(frwdpin, LOW);
938  digitalWrite(backpin, HIGH);
939  break;
940  }
941 }
942 
950 void CodeRacer::set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright) {
951  set_drive_left_speed(speedleft);
952  set_drive_right_speed(speedright);
953 }
954 
961 void CodeRacer::set_drive_left_speed(uint8_t speed) {
962  set_drive_speed(speed, _drive_left_enable_pin);
963 }
964 
971 void CodeRacer::set_drive_right_speed(uint8_t speed) {
972  set_drive_speed(speed, _drive_right_enable_pin);
973 }
974 
982 void CodeRacer::set_drive_speed(uint8_t speed, uint8_t enablepin) {
983  _analog_write(enablepin, (int)speed);
984 }
985  // end of group lowerleveldrivesmethods
994 uint8_t CodeRacer::drive_right_speed() {
995  return _drive_right_speed;
996 }
997 
1001 uint8_t CodeRacer::drive_left_speed() {
1002  return(_drive_left_speed);
1003 }
1004 
1005 void CodeRacer::_analog_write(uint8_t pin, uint8_t speed) {
1006  if (pin == _drive_left_enable_pin) {
1007  _drive_left_speed = speed;
1008  ledcWrite(DRIVE_PWM_LEFT_CHANNEL, speed);
1009  }
1010  if (pin == _drive_right_enable_pin) {
1011  _drive_right_speed = speed;
1012  ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed);
1013  }
1014 }
1015  // end of group lowerleveldrivesgetters // end of group lowerleveldrives
1018 
1019 
1020 //**************************************
1021 //*** LED lower level control ***
1022 //**************************************
1037 void CodeRacer::set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled) {
1038  digitalWrite(_led_left_pin, leftled);
1039  digitalWrite(_led_frwd_pin, frwdled);
1040  digitalWrite(_led_right_pin, rightled);
1041  digitalWrite(_led_stop_pin, stopled);
1042 }
1043 
1048 void CodeRacer::set_leds_all(ledstate alleds) {
1049  digitalWrite(_led_left_pin, alleds);
1050  digitalWrite(_led_frwd_pin, alleds);
1051  digitalWrite(_led_right_pin, alleds);
1052  digitalWrite(_led_stop_pin, alleds);
1053 }
1054 
1058 void CodeRacer::set_leds_all_off() {
1059  set_leds_all(LEDOFF);
1060 }
1061 
1065 void CodeRacer::set_leds_all_on() {
1066  set_leds_all(LEDON);
1067 }
1068  // end of group lowerlevelledmets // end of group lowerlevelled
1071 
1072 
1073 //**************************************
1074 //*** ISRs ***
1075 //**************************************
1076 //IRAM_ATTR is used to load the code into DRAM and not to Flash to make it faster - required for ISRs
1077 void IRAM_ATTR CodeRacer::_set_button_state() {
1078  if ((millis() - button_last_pressed_at_ms) > BUTTON_BOUNCING_TIME_MS) {
1079  button_last_pressed_at_ms = millis(); // simplest debouncing - just wait ;-)
1080  coderracer_activ = !coderracer_activ;
1081  }
1082 }
1083 
1084 
1085 //**********************************************************************************************************************
1086 //** Methods below this are obsolete and only in here for compatiblity to other projects - do not use them anymore !!!
1087 //**********************************************************************************************************************
1088 void CodeRacer::motor_einstellungen(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_for_ms, unsigned long turn_right_for_ms)
1089 {
1090  drives_settings(drive_left_speed, drive_right_speed, turn_left_for_ms, turn_right_for_ms);
1091 }
1092 
1093 void CodeRacer::servo_einstellungen(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos)
1094 {
1095  servo_settings(pos_center, pos_left, pos_right, sweep_left_pos, sweep_right_pos);
1096 }
1097 
1098 void CodeRacer::servo_rechts()
1099 {
1100  Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben
1101  servo_set_to_right(); // Servo auf den Winkel rechts drehen
1102 }
1103 
1104 void CodeRacer::servo_links()
1105 {
1106  Serial.println("SERVO_LINKS"); // Meldung am Monitor ausgeben
1107  servo_set_to_left(); // Servo auf den Winkel links drehen
1108 }
1109 
1110 void CodeRacer::servo_mitte()
1111 {
1112  Serial.println("SERVO_MITTE");
1113  servo_set_to_center();
1114 }
1115 
1116 void CodeRacer::servo_schwenk()
1117 {
1118  servo_sweep();
1119 }
1120 
1121 void CodeRacer::links()
1122 {
1123  Serial.println("CODERACER_LINKS");
1124  turn_left();
1125 }
1126 
1127 void CodeRacer::rechts()
1128 {
1129  Serial.println("CODERACER_RECHTS");
1130  turn_right();
1131 }
1132 
1133 void CodeRacer::anhalten()
1134 {
1135  Serial.println("CODERACER_ANHALTEN");
1136  stop_driving();
1137 }
1138 
1139 void CodeRacer::vorwaerts()
1140 {
1141  Serial.println("CODERACER_VORWAERTS");
1142  drive_forward();
1143 }
1144 
1145 void CodeRacer::rueckwaerts()
1146 {
1147  Serial.println("CODERACER_RUECKWAERTS");
1148  drive_backward();
1149 }
1150 
1151 unsigned long CodeRacer::abstand_messen()
1152 {
1153  return(0);
1154 
1155  unsigned long distance_cm = 0;
1156  unsigned long min_distance_cm = 1000;
1157  int8_t servo_turn_direction = 0;
1158 
1159 
1160  // while driving or sweeping there will be only one value be measured - else there will be mutiple measurements and the servor will be turning
1161  if (((true == _drive) || (servo_center_pos == _servo_position) || _servo_sweep == true)) {
1162  // while driving ...
1163  //Serial.println("ABSTAND_MESSEN im fahren, direkt nach vorn oder Schwenk() ist aktiv ...");
1164  min_distance_cm = usonic_measure_cm();
1165  } else {
1166  // no sweep, not driving ...
1167  //Serial.println("ABSTAND_MESSEN im Stand nach links oder rechts...");
1168  // are we already ath left or right with the servo ?
1169  if (servo_left_pos == _servo_position) {
1170  //Serial.println("ABSTAND_MESSEN. Linke Seite.");
1171  //left ...
1172  servo_turn_direction = SERVO_SWEEP_TO_RIGHT_STEP;
1173  }
1174  if (servo_right_pos == _servo_position) {
1175  //right ...
1176  //Serial.println("ABSTAND_MESSEN rechte Seite.");
1177  servo_turn_direction = SERVO_SWEEP_TO_LEFT_STEP;
1178  }
1179  // trun the servo and do measuring ... remember the smallest value
1180  do {
1181  _servo_set_position(_servo_position + servo_turn_direction);
1182  //Serial.print("ABSTAND_MESSEN. Servo position:");
1183  //Serial.println(_servo_position);
1184  distance_cm = usonic_measure_cm();
1185  if (distance_cm < min_distance_cm) {
1186  min_distance_cm = distance_cm;
1187  }
1188  } while ((_servo_position > H_SERVO_CENTER_LEFT) || (_servo_position < H_SERVO_CENTER_RIGHT));
1189  }
1190 
1191  Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):");
1192  Serial.println(min_distance_cm);
1193  //_min_distance_cm = min_distance_cm;
1194 
1195  return(min_distance_cm);
1196 
1197 }
1198 
1199 //**********************************************************************************************************************
1200 //** Helper methods
1201 //**********************************************************************************************************************
1202 
void drive_forward()
Sets the speed and the directions of both drives so that it will move forward.
Definition: CodeRacer.cpp:173
-
-
- - - - diff --git a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.html b/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.html deleted file mode 100644 index 5637769..0000000 --- a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.html +++ /dev/null @@ -1,182 +0,0 @@ - - - - - - - -Arduino {code}racer API: Getters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - -

-Functions

uint8_t CodeRacer::servo_position ()
 Get the actual position of the servo. More...
 
unsigned long CodeRacer::servo_position_set_at_ms ()
 Get the system time in ms the servo was set to the actual position. More...
 
unsigned long CodeRacer::servo_position_eta_in_ms ()
 Get the system time in ms the servo will reach its position This is an estimated time. If this is a time in the future, the servo may still moving. If this is a time in the past , the servo should have reached its postion already. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ servo_position()

- -
-
- - - - - - - -
uint8_t CodeRacer::servo_position ()
-
- -

Get the actual position of the servo.

-
Returns
Actual position of the servo
- -

Definition at line 632 of file CodeRacer.cpp.

-
632  {
633  return(_servo_position);
634 }
-
-
- -

◆ servo_position_set_at_ms()

- -
-
- - - - - - - -
unsigned long CodeRacer::servo_position_set_at_ms ()
-
- -

Get the system time in ms the servo was set to the actual position.

-
Returns
System time in ms the servo was set
- -

Definition at line 639 of file CodeRacer.cpp.

-
639  {
640  return(_servo_position_set_at_ms);
641 }
-
-
- -

◆ servo_position_eta_in_ms()

- -
-
- - - - - - - -
unsigned long CodeRacer::servo_position_eta_in_ms ()
-
- -

Get the system time in ms the servo will reach its position This is an estimated time. If this is a time in the future, the servo may still moving. If this is a time in the past , the servo should have reached its postion already.

-
Returns
System time in ms the servo will reach its position
- -

Definition at line 649 of file CodeRacer.cpp.

-
649  {
650  return(_servo_position_eta_in_ms);
651 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.js b/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.js deleted file mode 100644 index dbcaa68..0000000 --- a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.js +++ /dev/null @@ -1,6 +0,0 @@ -var group__lowerlevelservogetters = -[ - [ "servo_position", "d4/df4/group__lowerlevelservogetters.html#ga451b3ecd272e9a11de4b221f8d771432", null ], - [ "servo_position_set_at_ms", "d4/df4/group__lowerlevelservogetters.html#gaeed05a3d4e06adccebdfce207b734b2f", null ], - [ "servo_position_eta_in_ms", "d4/df4/group__lowerlevelservogetters.html#ga84ba256b9ccdf0e9f4280279da68a509", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.map b/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.map deleted file mode 100644 index 354ca7c..0000000 --- a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.md5 b/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.md5 deleted file mode 100644 index 34e1188..0000000 --- a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.md5 +++ /dev/null @@ -1 +0,0 @@ -68f8f6d7188bd071914c1b796efb68b6 \ No newline at end of file diff --git a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.png b/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.png deleted file mode 100644 index c79e2c7..0000000 Binary files a/Doku/Doxygen/html/d4/df4/group__lowerlevelservogetters.png and /dev/null differ diff --git a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.html b/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.html deleted file mode 100644 index e154332..0000000 --- a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -Arduino {code}racer API: Lower level drives methods and getters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
- -
-
Lower level drives methods and getters
-
-
- - - - - - -

-Modules

 Methods
 
 Getters
 
-

Detailed Description

-
-
- - - - diff --git a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.js b/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.js deleted file mode 100644 index 4b19b35..0000000 --- a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.js +++ /dev/null @@ -1,5 +0,0 @@ -var group__lowerleveldrives = -[ - [ "Methods", "d1/d8a/group__lowerleveldrivesmeths.html", "d1/d8a/group__lowerleveldrivesmeths" ], - [ "Getters", "d0/d0a/group__lowerleveldrivesgetters.html", "d0/d0a/group__lowerleveldrivesgetters" ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.map b/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.map deleted file mode 100644 index 50ccb6e..0000000 --- a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.map +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.md5 b/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.md5 deleted file mode 100644 index 5dd3d62..0000000 --- a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.md5 +++ /dev/null @@ -1 +0,0 @@ -929320c5d691931416a1f3fbdc41f4b0 \ No newline at end of file diff --git a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.png b/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.png deleted file mode 100644 index 31b7357..0000000 Binary files a/Doku/Doxygen/html/d6/d98/group__lowerleveldrives.png and /dev/null differ diff --git a/Doku/Doxygen/html/d6/d9a/_code_racer_8h_source.html b/Doku/Doxygen/html/d6/d9a/_code_racer_8h_source.html deleted file mode 100644 index 8f4b320..0000000 --- a/Doku/Doxygen/html/d6/d9a/_code_racer_8h_source.html +++ /dev/null @@ -1,100 +0,0 @@ - - - - - - - -Arduino {code}racer API: C:/Users/jnoack/Documents/Arduino/libraries/CodeRacer/CodeRacer.h Source File - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
-
-
CodeRacer.h
-
-
-
1 #include "Arduino.h"
2 #include <algorithm> // std::swap
3 #include <ESP32Servo.h> // Servo drive support for ESP32
4 #include "esp32-hal-ledc.h" // Part of ESP32 board files - Analog output
5 
6 #ifndef __CodeRacer_H__
7 #define __CodeRacer_H__
8 
9 //----- Fun stuff ---------
10 #define FUN_MIN_PAUSE_MS 120000 // minimum and maximum pause between to rounds fun
11 #define FUN_MAX_PAUSE_MS 300000
12 #define LED_SWITCH_MS 50 // speed of knight rider lights
13 //----- Button ------------
14 #define H_BUTTON_PIN 17
15 #define BUTTON_BOUNCING_TIME_MS 200 // bouncing delay
16 //----- Servo -----
17 #define H_SERVO_PIN 16
18 #define H_SERVO_LEFT_POS 145 // left position of the servo
19 #define H_SERVO_CENTER_LEFT 100 // left-center position of the servo
20 #define H_SERVO_RIGHT_POS 35 // right position of the servo
21 #define H_SERVO_CENTER_RIGHT 80 // right-center position of the servo
22 #define H_SERVO_CENTER_POS 90 // center position of the servo
23 #define H_SERVO_SWEEP_LEFT_POS 140 // most left sweep position of the servo
24 #define H_SERVO_SWEEP_RIGHT_POS 40 // most right sweep position of the servo
25 #define SERVO_SWEEP_TO_LEFT_STEP 5 // sweep step to the left
26 #define SERVO_SWEEP_TO_RIGHT_STEP -5 // sweep step to the right
27 #define SERVO_SWEEP_MS 10 // duration of time betwee to sweep steps
28 #define SERVO_MAX_POSITION 170 // maximum servo position
29 #define SERVO_MIN_POSITION 10 // minimum servo position
30 #define SERVO_SET_1TICK_POSITION_DELAY_MS 3 // minimum duration of time between two servo steps
31 
32 //----- Ultrasonic sensor -----
33 #define H_US_TRIG_PIN 12
34 #define H_US_ECHO_PIN 14
35 #define H_US_STOP_DISTANCE_CM 25 // if the measured distance is smaller the racer maybe stopped
36 #define US_MAX_ECHO_TIME_US 6000 // timeout for ultrasonic sensor measurements - this is about 100cm
37 
38 //----- Drives -----
39 #define H_DRIVE_RIGHT_SPEED 255 // default speed of right side drive. 0 ...255
40 #define H_DRIVE_LEFT_SPEED 255 // default speed of left side drive. 0 ...255
41 #define H_DRIVE_RIGHT_ENABLE_PIN 2
42 #define H_DRIVE_RIGHT_FWRD_PIN 4
43 #define H_DRIVE_RIGHT_BACK_PIN 15
44 #define H_DRIVE_LEFT_ENABLE_PIN 21
45 #define H_DRIVE_LEFT_FWRD_PIN 22
46 #define H_DRIVE_LEFT_BACK_PIN 23
47 #define H_RACER_TURN_LEFT_FOR_MS 400 // duration of time the racer will turn to left
48 #define H_RACER_TURN_RIGHT_FOR_MS 400 // duration of time the racer will turn to right
49 
50 #define DRIVE_PWM_LEFT_CHANNEL 5 // PWM-channel for left side drive
51 #define DRIVE_PWM_RIGHT_CHANNEL 6 // PWM-channel for right side drive
52 
53 //----- LEDs -----
54 #define H_LED_FRWD_PIN 26
55 #define H_LED_STOP_PIN 25
56 #define H_LED_LEFT_PIN 33
57 #define H_LED_RIGHT_PIN 27
58 
59 static volatile bool coderracer_activ = false;;
60 static volatile unsigned long button_last_pressed_at_ms = millis();
61 
62 enum ledstate {
63  LEDOFF,
64  LEDON
65 };
66 
67 enum drivestate {
68  DRIVESTOP,
69  DRIVEFRWD,
70  DRIVEBACK
71 };
72 
73 //--- this is as preparation of the class creation
74 class CodeRacer {
75 
76  private:
77 
78  //pins
79  uint8_t _button_pin;
80  uint8_t _servo_pin;
81  uint8_t _us_trigger_pin;
82  uint8_t _us_echo_pin;
83  uint8_t _drive_left_frwd_pin;
84  uint8_t _drive_left_back_pin;
85  uint8_t _drive_left_enable_pin;
86  uint8_t _drive_right_frwd_pin;
87  uint8_t _drive_right_back_pin;
88  uint8_t _drive_right_enable_pin;
89  uint8_t _led_frwd_pin;
90  uint8_t _led_stop_pin;
91  uint8_t _led_left_pin;
92  uint8_t _led_right_pin;
93 
94  //servo variables
95  int8_t _servo_sweep_step;
96  uint8_t _servo_position;
97  unsigned long _servo_position_set_at_ms;
98  unsigned long _servo_position_eta_in_ms;
99 
100  //drives variables
101  uint8_t _drive_left_speed;
102  uint8_t _drive_right_speed;
103  unsigned long _turn_left_for_ms;
104  unsigned long _turn_right_for_ms;
105 
106  // ultrasonic variables
107  bool _coderacer_stopped_at_min_distance;
108  bool _coderacer_stop_at_distance_enabled;
109  unsigned long _usonic_stop_distance_cm;
110  unsigned long _usonic_stop_distance_us;
111  unsigned long _usonic_distance_us;
112  unsigned long _usonic_distance_cm;
113 
114  //fun stuff variables
115  unsigned long _last_led_switched_at_ms;
116  uint8_t _led_count;
117  uint8_t _last_led_on;
118  unsigned long _servo_look_around_at_ms;
119 
120 
121  unsigned long _min_distance_cm;
122  bool _drive;
123  unsigned long _drive_set_at_ms;
124  bool _servo_sweep;
125  bool _coderracer_activ;
126 
127  //objects
128  Servo* _servo;
129  Servo* _servo_dummy;
130 
131  static void _set_button_state();
132  void _analog_write(uint8_t pin, uint8_t speed);
133  unsigned long _servo_set_position(uint8_t position);
134 
135  public:
136  //properties
137  bool coderacer_fun_enabled;
138 
139  uint8_t servo_center_pos;
140  uint8_t servo_left_pos;
141  uint8_t servo_right_pos;
142  uint8_t servo_sweep_left_pos;
143  uint8_t servo_sweep_right_pos;
145  //methods
146  CodeRacer();
147 
148  CodeRacer(uint8_t button_pin, uint8_t servo_pin,
149  uint8_t us_trigger_pin, uint8_t us_echo_pin,
150  uint8_t drive_left_frwd_pin, uint8_t drive_left_back_pin, uint8_t drive_left_enable_pin,
151  uint8_t drive_right_frwd_pin, uint8_t drive_right_back_pin, uint8_t drive_right_enable_pin,
152  uint8_t led_frwd_pin, uint8_t led_stop_pin, uint8_t led_left_pin, uint8_t led_right_pin);
153 
154  void set_inactive();
155  void set_active();
156 
157  void begin();
158 
159  // getters
160  bool is_active();
161  bool is_driving();
162  bool stopped_at_min_distance();
163  unsigned long usonic_distance_cm();
164  unsigned long usonic_distance_us();
165  uint8_t servo_position();
166  unsigned long servo_position_set_at_ms();
167  unsigned long servo_position_eta_in_ms();
168  uint8_t drive_left_speed();
169  uint8_t drive_right_speed();
170  unsigned long turn_left_for_ms();
171  unsigned long turn_right_for_ms();
172 
173  // higher level {code}racer services
174  void stop_driving();
175  void drive_forward();
176  void drive_forward(uint8_t left_speed, uint8_t right_speed);
177  void drive_backward();
178  void drive_backward(uint8_t left_speed, uint8_t right_speed);
179  void turn_left();
180  void turn_left(unsigned long turn_for_ms);
181  void turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed);
182  void turn_right();
183  void turn_right(unsigned long turn_for_ms);
184  void turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed);
185 
186  void start_stop_at_min_distance();
187  void start_stop_at_min_distance(unsigned long min_distance_cm);
188  void stop_stop_at_min_distance();
189 
190 
191  // LEDs
192  void set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled);
193  void set_leds_all(ledstate alleds);
194  void set_leds_all_off();
195  void set_leds_all_on();
196 
197  // Drives
198  void drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_ms, unsigned long turn_right_ms);
199  void set_drives_states_left_right(drivestate stateleft, drivestate stateright);
200  void set_drive_left_state(drivestate state);
201  void set_drive_right_state(drivestate state);
202  void set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin);
203  void set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright);
204  void set_drive_left_speed(uint8_t speed);
205  void set_drive_right_speed(uint8_t speed);
206  void set_drive_speed(uint8_t speed, uint8_t enablepin);
207  void set_drives_stop_left_right();
208 
209  // Ultrasonic sensor
210  unsigned long usonic_measure_cm();
211  unsigned long usonic_measure_us();
212  unsigned long usonic_measure_cm(unsigned long max_echo_run_time_us);
213  unsigned long usonic_measure_us(unsigned long max_echo_run_time_us);
214  unsigned long usonic_measure_single_shot_cm();
215  unsigned long usonic_measure_single_shot_us();
216  unsigned long usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us);
217  unsigned long usonic_measure_single_shot_us(unsigned long max_echo_run_time_us);
218  void usonic_set_stop_distance_cm(unsigned long stop_distance_cm);
219  void usonic_set_stop_distance_us(unsigned long stop_distance_us);
220 
221  // Servo drive
222  void servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos);
223  uint8_t servo_set_position_wait(uint8_t position);
224  unsigned long servo_set_position(uint8_t position);
225  void servo_set_to_right();
226  void servo_set_to_left();
227  void servo_set_to_center();
228  void servo_sweep();
229 
230  // just for fun
231  void kitt();
232  void look_around();
233 
234  // previous OBSOLETE german language definitions of the methods - still needed to support MakerLab Murnau {code}racer project
235  // - but use the english ones for new implementations
236  void servo_einstellungen(uint8_t winkel_mitte, uint8_t winkel_links, uint8_t winkel_rechts, uint8_t schwenk_links, uint8_t schwenk_rechts);
237  void motor_einstellungen(uint8_t motor_links_tempo, uint8_t motor_rechts_tempo, unsigned long drehung_links_ms, unsigned long drehung_rechts_ms);
238  void anhalten();
239  void vorwaerts();
240  void rueckwaerts();
241  void links();
242  void rechts();
243  void servo_rechts();
244  void servo_links();
245  void servo_mitte();
246  unsigned long abstand_messen();
247  void servo_schwenk();
248  bool start_stop();
249 };
250 
251 
252 
253 #endif
-
- - - - diff --git a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.html b/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.html deleted file mode 100644 index 283d8a5..0000000 --- a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.html +++ /dev/null @@ -1,335 +0,0 @@ - - - - - - - -Arduino {code}racer API: Methods - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - -

-Functions

unsigned long CodeRacer::usonic_measure_cm ()
 Measures the distance to the next object in front of the ultra sonic sensor in cm. More...
 
unsigned long CodeRacer::usonic_measure_us ()
 Measures the distance to the next object in front of the ultra sonic sensor in microseconds. More...
 
unsigned long CodeRacer::usonic_measure_cm (unsigned long max_echo_run_time_us)
 Measures the distance to the next object in front of the ultra sonic sensor in cm. More...
 
unsigned long CodeRacer::usonic_measure_us (unsigned long max_echo_run_time_us)
 Measures the distance to the next object in front of the ultra sonic sensor in microseconds. More...
 
unsigned long CodeRacer::usonic_measure_single_shot_cm ()
 Measures the distance to the next object in front of the ultra sonic sensor in cm. More...
 
unsigned long CodeRacer::usonic_measure_single_shot_us ()
 Measures the distance to the next object in front of the ultra sonic sensor in microseconds. More...
 
unsigned long CodeRacer::usonic_measure_single_shot_cm (unsigned long max_echo_run_time_us)
 Measures the distance to the next object in front of the ultra sonic sensor in cm. More...
 
unsigned long CodeRacer::usonic_measure_single_shot_us (unsigned long max_echo_run_time_us)
 Measures the distance to the next object in front of the ultra sonic sensor in microseconds. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ usonic_measure_cm() [1/2]

- -
-
- - - - - - - -
unsigned long CodeRacer::usonic_measure_cm ()
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in cm.

-

This is the medium one out of 3 measurements. The maximum measured distance is about 100cm and defined by the US_MAX_ECHO_TIME_US setting in the header file.

Returns
The measured distance in cm.
- -

Definition at line 672 of file CodeRacer.cpp.

-
673 {
674  return(usonic_measure_cm(US_MAX_ECHO_TIME_US));
675 }
-
-
- -

◆ usonic_measure_us() [1/2]

- -
-
- - - - - - - -
unsigned long CodeRacer::usonic_measure_us ()
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in microseconds.

-

This is the medium one out of 3 measurements. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file.

Returns
The measured distance in microseconds.
- -

Definition at line 682 of file CodeRacer.cpp.

-
683  {
684  return(usonic_measure_us(US_MAX_ECHO_TIME_US));
685  }
-
-
- -

◆ usonic_measure_cm() [2/2]

- -
-
- - - - - - - - -
unsigned long CodeRacer::usonic_measure_cm (unsigned long max_echo_run_time_us)
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in cm.

-

This is the medium one out of 3 measurements. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm.

Parameters
- - -
max_echo_run_time_usDefines the maximum echo run time and by that the maximum of distance that can be measured.
-
-
-
Returns
The measured distance in cm.
- -

Definition at line 694 of file CodeRacer.cpp.

-
695 {
696  unsigned long echo_runtime_us = usonic_measure_us(max_echo_run_time_us);
697  unsigned long distance_cm = echo_runtime_us * 0.0172;
698  //Serial.print("MEASURE_DISTANCE. Distance in cm is: ");
699  //Serial.println(distance_cm);
700  _usonic_distance_cm = distance_cm;
701  return(distance_cm);
702 }
-
-
- -

◆ usonic_measure_us() [2/2]

- -
-
- - - - - - - - -
unsigned long CodeRacer::usonic_measure_us (unsigned long max_echo_run_time_us)
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in microseconds.

-

This is the medium one out of 3 measurements. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm.

Parameters
- - -
max_echo_run_time_usDefines the maximum echo run time in microseconds and by that the maximum of distance that can be measured.
-
-
-
Returns
The measured distance in microseconds.
- -

Definition at line 711 of file CodeRacer.cpp.

-
712 {
713  unsigned long echo_runtime_us[3] = { 0,0,0 };
714  uint8_t measnr = 0;
715 
716  do {
717  echo_runtime_us[measnr] = usonic_measure_single_shot_us(max_echo_run_time_us);
718  if (echo_runtime_us[measnr] > 200) {
719  measnr++;
720  }
721  } while (measnr < 3);
722 
723  // we will take the medium out of 3 values ...
724  if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); }
725  if (echo_runtime_us[1] > echo_runtime_us[2]) { std::swap(echo_runtime_us[1], echo_runtime_us[2]); }
726  if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); }
727 
728  //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: ");
729  //Serial.println(echo_runtime_us[1]);
730 
731  // if the stop at minimal distance is enabeled - check for minimal distance is reached
732  if (true == _coderacer_stop_at_distance_enabled) {
733  if (echo_runtime_us[1] <= _usonic_stop_distance_us) {
734  _coderacer_stopped_at_min_distance = true;
735  stop_driving();
736  _coderacer_stop_at_distance_enabled = false;
737  }
738  }
739  _usonic_distance_us = echo_runtime_us[1];
740  return(echo_runtime_us[1]);
741 }
-
-
- -

◆ usonic_measure_single_shot_cm() [1/2]

- -
-
- - - - - - - -
unsigned long CodeRacer::usonic_measure_single_shot_cm ()
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in cm.

-

This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file.

Returns
The measured distance in cm.
- -

Definition at line 748 of file CodeRacer.cpp.

-
749 {
750  return(usonic_measure_single_shot_cm(US_MAX_ECHO_TIME_US));
751 }
-
-
- -

◆ usonic_measure_single_shot_us() [1/2]

- -
-
- - - - - - - -
unsigned long CodeRacer::usonic_measure_single_shot_us ()
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in microseconds.

-

This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file.

Returns
The measured distance in microseconds.
- -

Definition at line 758 of file CodeRacer.cpp.

-
759 {
760  return(usonic_measure_single_shot_us(US_MAX_ECHO_TIME_US));
761 }
-
-
- -

◆ usonic_measure_single_shot_cm() [2/2]

- -
-
- - - - - - - - -
unsigned long CodeRacer::usonic_measure_single_shot_cm (unsigned long max_echo_run_time_us)
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in cm.

-

This is a one shot measurement. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm.

Parameters
- - -
max_echo_run_time_usDefines the maximum echo run time in microseconds and by that the maximum of distance that can be measured.
-
-
-
Returns
The measured distance in cm.
- -

Definition at line 770 of file CodeRacer.cpp.

-
771 {
772  // convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec
773  // the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one
774  // distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172
775  // distance_cm = (echo_duration/2) / 29.1;
776  unsigned long echo_runtime_us = usonic_measure_single_shot_us(max_echo_run_time_us);
777  unsigned long distance_cm = echo_runtime_us * 0.0172;
778  //Serial.print("MEASURE_DISTANCE. Distance in cm is: ");
779  //Serial.println(distance_cm);
780  _usonic_distance_cm = distance_cm;
781  return(distance_cm);
782 }
-
-
- -

◆ usonic_measure_single_shot_us() [2/2]

- -
-
- - - - - - - - -
unsigned long CodeRacer::usonic_measure_single_shot_us (unsigned long max_echo_run_time_us)
-
- -

Measures the distance to the next object in front of the ultra sonic sensor in microseconds.

-

This is a one shot measurement. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm.

Parameters
- - -
max_echo_run_time_usDefines the maximum echo run time in microseconds and by that the maximum of distance that can be measured.
-
-
-
Returns
The measured distance in microseconds.
- -

Definition at line 791 of file CodeRacer.cpp.

-
792  {
793  unsigned long echo_runtime_us;
794  // start measurement - send a short pulse "HIGH" to the TRIG pin of the ultrasonic sensor
795  pinMode(_us_echo_pin, OUTPUT);
796  pinMode(_us_echo_pin, INPUT);
797  digitalWrite(_us_trigger_pin, LOW);
798  delayMicroseconds(2);
799  digitalWrite(_us_trigger_pin, HIGH);
800  delayMicroseconds(10);
801  digitalWrite(_us_trigger_pin, LOW);
802  // measure runtime in microseconds until the ECHO pin aof the sensor goes HIGH
803  echo_runtime_us = pulseInLong(_us_echo_pin, HIGH, max_echo_run_time_us);
804  if (echo_runtime_us == 0) {
805  echo_runtime_us = max_echo_run_time_us; // US_MAX_ECHO_TIME_US;
806  }
807  //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: ");
808  //Serial.println(echo_runtime_us);
809  _usonic_distance_us = echo_runtime_us;
810  return(echo_runtime_us);
811  }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.js b/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.js deleted file mode 100644 index ca0eb94..0000000 --- a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.js +++ /dev/null @@ -1,11 +0,0 @@ -var group__lowerlevelusmeths = -[ - [ "usonic_measure_cm", "d6/dfc/group__lowerlevelusmeths.html#ga5f034198a28b069478c454c63dbfa225", null ], - [ "usonic_measure_us", "d6/dfc/group__lowerlevelusmeths.html#gaa01602a576fd57609bc7e08f8ef32e58", null ], - [ "usonic_measure_cm", "d6/dfc/group__lowerlevelusmeths.html#gafdd5c75d7a8e7b7c993e512ee93dde9a", null ], - [ "usonic_measure_us", "d6/dfc/group__lowerlevelusmeths.html#ga1f3401ef472cb11997e7dc98ef3e2424", null ], - [ "usonic_measure_single_shot_cm", "d6/dfc/group__lowerlevelusmeths.html#ga0c00edbbf4a3169613c9ea84d6e7dc13", null ], - [ "usonic_measure_single_shot_us", "d6/dfc/group__lowerlevelusmeths.html#gad4309b6da17085575fb0c55559e240b8", null ], - [ "usonic_measure_single_shot_cm", "d6/dfc/group__lowerlevelusmeths.html#gab413551ea8a67e1b60eda1671029b645", null ], - [ "usonic_measure_single_shot_us", "d6/dfc/group__lowerlevelusmeths.html#ga1b5b43372082f5daeee47410a09a590c", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.map b/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.map deleted file mode 100644 index e6f1a45..0000000 --- a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.md5 b/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.md5 deleted file mode 100644 index 9d6c8c9..0000000 --- a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.md5 +++ /dev/null @@ -1 +0,0 @@ -8c86a47e7c3ee5eacbea426bb722fea2 \ No newline at end of file diff --git a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.png b/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.png deleted file mode 100644 index 42cf950..0000000 Binary files a/Doku/Doxygen/html/d6/dfc/group__lowerlevelusmeths.png and /dev/null differ diff --git a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.html b/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.html deleted file mode 100644 index f043281..0000000 --- a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.html +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - -Arduino {code}racer API: Lower level LED methods - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
- -
-
Lower level LED methods
-
-
- - - - -

-Modules

 Methods
 
-

Detailed Description

-
-
- - - - diff --git a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.js b/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.js deleted file mode 100644 index 35c31bf..0000000 --- a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.js +++ /dev/null @@ -1,4 +0,0 @@ -var group__lowerlevelled = -[ - [ "Methods", "dd/dff/group__lowerlevelledmeths.html", "dd/dff/group__lowerlevelledmeths" ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.map b/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.map deleted file mode 100644 index 3f89425..0000000 --- a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.md5 b/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.md5 deleted file mode 100644 index 7380e68..0000000 --- a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.md5 +++ /dev/null @@ -1 +0,0 @@ -ae42a26c171e691377cc1cea12a6b159 \ No newline at end of file diff --git a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.png b/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.png deleted file mode 100644 index 8cf2dc7..0000000 Binary files a/Doku/Doxygen/html/d7/d0f/group__lowerlevelled.png and /dev/null differ diff --git a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.html b/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.html deleted file mode 100644 index 6f2f8a6..0000000 --- a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.html +++ /dev/null @@ -1,282 +0,0 @@ - - - - - - - -Arduino {code}racer API: Getters and setters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - - - - - - - - - - - - - -

-Functions

bool CodeRacer::stopped_at_min_distance ()
 Returns true if the racer was stopped at minimum distance. This set to false each time start_stop_at_min_distance() is called. More...
 
bool CodeRacer::is_driving ()
 Return true if the racer is driving - forward or backward. More...
 
unsigned long CodeRacer::turn_left_for_ms ()
 Returns the duration of time that is internally stored and used for turning the racer left. More...
 
unsigned long CodeRacer::turn_right_for_ms ()
 Returns the duration of time that is internally stored and used for turning the racer left. More...
 
void CodeRacer::set_inactive ()
 Sets the coderracer_active state to inactive. If start_stop() is used - the inactive mode will be entered. More...
 
void CodeRacer::set_active ()
 Sets the coderracer_active state to active. If start_stop() is used - the active mode will be entered. More...
 
bool CodeRacer::is_active ()
 Checks if coderracer_activ is set. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ stopped_at_min_distance()

- -
-
- - - - - - - -
bool CodeRacer::stopped_at_min_distance ()
-
- -

Returns true if the racer was stopped at minimum distance. This set to false each time start_stop_at_min_distance() is called.

-
Returns
True if stopped.
- -

Definition at line 380 of file CodeRacer.cpp.

-
380  {
381  return(_coderacer_stopped_at_min_distance);
382 }
-
-
- -

◆ is_driving()

- -
-
- - - - - - - -
bool CodeRacer::is_driving ()
-
- -

Return true if the racer is driving - forward or backward.

-
Returns
True if driving forward or backward
- -

Definition at line 387 of file CodeRacer.cpp.

-
387  {
388  return(_drive);
389 }
-
-
- -

◆ turn_left_for_ms()

- -
-
- - - - - - - -
unsigned long CodeRacer::turn_left_for_ms ()
-
- -

Returns the duration of time that is internally stored and used for turning the racer left.

-
Returns
Time to turn left in ms
- -

Definition at line 394 of file CodeRacer.cpp.

-
394  {
395  return(_turn_left_for_ms);
396 }
-
-
- -

◆ turn_right_for_ms()

- -
-
- - - - - - - -
unsigned long CodeRacer::turn_right_for_ms ()
-
- -

Returns the duration of time that is internally stored and used for turning the racer left.

-
Returns
Time to turn left in ms
- -

Definition at line 401 of file CodeRacer.cpp.

-
401  {
402  return(_turn_right_for_ms);
403 }
-
-
- -

◆ set_inactive()

- -
-
- - - - - - - -
void CodeRacer::set_inactive ()
-
- -

Sets the coderracer_active state to inactive. If start_stop() is used - the inactive mode will be entered.

-
Returns
nothing
- -

Definition at line 408 of file CodeRacer.cpp.

-
408  {
409  coderracer_activ = false;
410 }
-
-
- -

◆ set_active()

- -
-
- - - - - - - -
void CodeRacer::set_active ()
-
- -

Sets the coderracer_active state to active. If start_stop() is used - the active mode will be entered.

-
Returns
nothing
- -

Definition at line 415 of file CodeRacer.cpp.

-
415  {
416  coderracer_activ = true;
417 }
-
-
- -

◆ is_active()

- -
-
- - - - - - - -
bool CodeRacer::is_active ()
-
- -

Checks if coderracer_activ is set.

-

coderracer_activ is toggled each time the button is pressed. After power on coderracer_activ is set to False.

Returns
True id coderracer_activ is set - False if not.
- -

Definition at line 424 of file CodeRacer.cpp.

-
424  {
425  return(coderracer_activ);
426 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.js b/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.js deleted file mode 100644 index f9662fd..0000000 --- a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.js +++ /dev/null @@ -1,10 +0,0 @@ -var group__higherlevelgetters = -[ - [ "stopped_at_min_distance", "d7/d45/group__higherlevelgetters.html#gae8b8c0ab24ccb572281785aeca8541e1", null ], - [ "is_driving", "d7/d45/group__higherlevelgetters.html#ga33dcd96e9b12dec794c56be85ec1ee05", null ], - [ "turn_left_for_ms", "d7/d45/group__higherlevelgetters.html#gaf04fd16ca0e2ace656f9549c43d16459", null ], - [ "turn_right_for_ms", "d7/d45/group__higherlevelgetters.html#gac0698f02f6a21d9d1f5b9cf2820306cf", null ], - [ "set_inactive", "d7/d45/group__higherlevelgetters.html#ga62f1c0eea56e27d0853cb58f30eb140d", null ], - [ "set_active", "d7/d45/group__higherlevelgetters.html#ga415c69930f291d5e06b7211b31843310", null ], - [ "is_active", "d7/d45/group__higherlevelgetters.html#gaa0ab4d6a754a23ea13664a553bcc8ff2", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.map b/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.map deleted file mode 100644 index 09cc176..0000000 --- a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.md5 b/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.md5 deleted file mode 100644 index f9b8790..0000000 --- a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.md5 +++ /dev/null @@ -1 +0,0 @@ -0c88cc43f51cb6a9047b0307b81a6f18 \ No newline at end of file diff --git a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.png b/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.png deleted file mode 100644 index 507ee33..0000000 Binary files a/Doku/Doxygen/html/d7/d45/group__higherlevelgetters.png and /dev/null differ diff --git a/Doku/Doxygen/html/d8/d7a/group__lowerlevelfun.html b/Doku/Doxygen/html/d8/d7a/group__lowerlevelfun.html deleted file mode 100644 index 38b9621..0000000 --- a/Doku/Doxygen/html/d8/d7a/group__lowerlevelfun.html +++ /dev/null @@ -1,157 +0,0 @@ - - - - - - - -Arduino {code}racer API: Lower level fun stuff methods - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
- -
-
Lower level fun stuff methods
-
-
- - - - - - - - -

-Functions

void CodeRacer::look_around ()
 Fun stuff - will move the servo around after a random amount of time. More...
 
void CodeRacer::kitt ()
 Fun stuff - you know Knightrider... More...
 
-

Detailed Description

-

Function Documentation

- -

◆ look_around()

- -
-
- - - - - - - -
void CodeRacer::look_around ()
-
- -

Fun stuff - will move the servo around after a random amount of time.

-
Returns
nothing
- -

Definition at line 440 of file CodeRacer.cpp.

-
441 {
442  if (_servo_look_around_at_ms < millis()) {
443  _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
444  servo_set_to_left();
445  delay(500);
446  servo_set_to_right();
447  delay(800);
448  servo_set_to_center();
449  delay(300);
450  servo_set_to_left();
451  delay(100);
452  servo_set_to_center();
453  }
454 }
-
-
- -

◆ kitt()

- -
-
- - - - - - - -
void CodeRacer::kitt ()
-
- -

Fun stuff - you know Knightrider...

-
Returns
nothing
- -

Definition at line 459 of file CodeRacer.cpp.

-
460 {
461  if (millis() - _last_led_switched_at_ms > LED_SWITCH_MS) {
462  _last_led_switched_at_ms = millis();
463  if (_last_led_on >= 5) {
464  _led_count = -1;
465  }
466  else if (_last_led_on <= 0) {
467  _led_count = 1;
468  }
469  _last_led_on = _last_led_on + _led_count;
470  switch (_last_led_on) {
471  case 0:
472  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
473  break;
474  case 1:
475  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
476  break;
477  case 2:
478  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
479  break;
480  case 3:
481  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
482  break;
483  case 4:
484  case 5:
485  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON);
486  break;
487  }
488  }
489 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/d8/d7a/group__lowerlevelfun.js b/Doku/Doxygen/html/d8/d7a/group__lowerlevelfun.js deleted file mode 100644 index fafb192..0000000 --- a/Doku/Doxygen/html/d8/d7a/group__lowerlevelfun.js +++ /dev/null @@ -1,5 +0,0 @@ -var group__lowerlevelfun = -[ - [ "look_around", "d8/d7a/group__lowerlevelfun.html#ga04309a38252639a8eaa43809c04c11c8", null ], - [ "kitt", "d8/d7a/group__lowerlevelfun.html#ga3b6f819fb82d910888fbc87abff1470c", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d9/d80/group__higherlevel.html b/Doku/Doxygen/html/d9/d80/group__higherlevel.html deleted file mode 100644 index c88a1e3..0000000 --- a/Doku/Doxygen/html/d9/d80/group__higherlevel.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -Arduino {code}racer API: Higher level methods, setters and getters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
- -
-
Higher level methods, setters and getters
-
-
- - - - - - -

-Modules

 Methods
 
 Getters and setters
 
-

Detailed Description

-
-
- - - - diff --git a/Doku/Doxygen/html/d9/d80/group__higherlevel.js b/Doku/Doxygen/html/d9/d80/group__higherlevel.js deleted file mode 100644 index 29780e9..0000000 --- a/Doku/Doxygen/html/d9/d80/group__higherlevel.js +++ /dev/null @@ -1,5 +0,0 @@ -var group__higherlevel = -[ - [ "Methods", "d2/d40/group__higherlevelmeths.html", "d2/d40/group__higherlevelmeths" ], - [ "Getters and setters", "d7/d45/group__higherlevelgetters.html", "d7/d45/group__higherlevelgetters" ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/d9/d80/group__higherlevel.map b/Doku/Doxygen/html/d9/d80/group__higherlevel.map deleted file mode 100644 index 1ea350c..0000000 --- a/Doku/Doxygen/html/d9/d80/group__higherlevel.map +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/Doku/Doxygen/html/d9/d80/group__higherlevel.md5 b/Doku/Doxygen/html/d9/d80/group__higherlevel.md5 deleted file mode 100644 index 7aaedc8..0000000 --- a/Doku/Doxygen/html/d9/d80/group__higherlevel.md5 +++ /dev/null @@ -1 +0,0 @@ -12cfd362df9c03991f2685cfc91fc9f2 \ No newline at end of file diff --git a/Doku/Doxygen/html/d9/d80/group__higherlevel.png b/Doku/Doxygen/html/d9/d80/group__higherlevel.png deleted file mode 100644 index ffed6ba..0000000 Binary files a/Doku/Doxygen/html/d9/d80/group__higherlevel.png and /dev/null differ diff --git a/Doku/Doxygen/html/da/daf/group__lowerlevelus.html b/Doku/Doxygen/html/da/daf/group__lowerlevelus.html deleted file mode 100644 index 13b4b36..0000000 --- a/Doku/Doxygen/html/da/daf/group__lowerlevelus.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -Arduino {code}racer API: Lower level ultra sonic methods and getters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
- -
-
Lower level ultra sonic methods and getters
-
-
- - - - - - -

-Modules

 Methods
 
 Setters and getters
 
-

Detailed Description

-
-
- - - - diff --git a/Doku/Doxygen/html/da/daf/group__lowerlevelus.js b/Doku/Doxygen/html/da/daf/group__lowerlevelus.js deleted file mode 100644 index 715835f..0000000 --- a/Doku/Doxygen/html/da/daf/group__lowerlevelus.js +++ /dev/null @@ -1,5 +0,0 @@ -var group__lowerlevelus = -[ - [ "Methods", "d6/dfc/group__lowerlevelusmeths.html", "d6/dfc/group__lowerlevelusmeths" ], - [ "Setters and getters", "db/ddd/group__lowerlevelusgetters.html", "db/ddd/group__lowerlevelusgetters" ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/da/daf/group__lowerlevelus.map b/Doku/Doxygen/html/da/daf/group__lowerlevelus.map deleted file mode 100644 index b07fb2c..0000000 --- a/Doku/Doxygen/html/da/daf/group__lowerlevelus.map +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/Doku/Doxygen/html/da/daf/group__lowerlevelus.md5 b/Doku/Doxygen/html/da/daf/group__lowerlevelus.md5 deleted file mode 100644 index 7b87cab..0000000 --- a/Doku/Doxygen/html/da/daf/group__lowerlevelus.md5 +++ /dev/null @@ -1 +0,0 @@ -35f9114c2fb61134b1d44a4ab7152af0 \ No newline at end of file diff --git a/Doku/Doxygen/html/da/daf/group__lowerlevelus.png b/Doku/Doxygen/html/da/daf/group__lowerlevelus.png deleted file mode 100644 index b1bace1..0000000 Binary files a/Doku/Doxygen/html/da/daf/group__lowerlevelus.png and /dev/null differ diff --git a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.html b/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.html deleted file mode 100644 index 9ed6536..0000000 --- a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.html +++ /dev/null @@ -1,335 +0,0 @@ - - - - - - - -Arduino {code}racer API: Methods - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - - - - - - - - - - - - - -

-Functions

void CodeRacer::servo_settings (uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos)
 Overwrites the default settings taken from header file by the parameters given to this method. More...
 
void CodeRacer::servo_sweep ()
 Turns sweeping of the servo from left to right and back on. More...
 
void CodeRacer::servo_set_to_right ()
 Drives the servo to the postion that is defined by #servo_right_pos. More...
 
void CodeRacer::servo_set_to_left ()
 Drives the servo to the postion that is defined by #servo_left_pos. More...
 
void CodeRacer::servo_set_to_center ()
 Drives the servo to the postion that is defined by #servo_center_pos. More...
 
uint8_t CodeRacer::servo_set_position_wait (uint8_t position)
 Drive the servo to the postion given to this method. More...
 
unsigned long CodeRacer::servo_set_position (uint8_t position)
 Drive the servo to the postion given to this method. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ servo_settings()

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
void CodeRacer::servo_settings (uint8_t pos_center,
uint8_t pos_left,
uint8_t pos_right,
uint8_t sweep_left_pos,
uint8_t sweep_right_pos 
)
-
- -

Overwrites the default settings taken from header file by the parameters given to this method.

-
Parameters
- - - - - - -
pos_centerThe postion at which the servo moves to straight forward. Default is 90. Allowed 10 <= pos_center <= 170.
pos_leftThe postion at which the servo moves to the left. Default is 170. Allowed 10 <= pos_center <= 170.
pos_rightThe postion at which the servo moves to the right. Default is 10. Allowed 10 <= pos_center <= 170.
sweep_left_posIf the servo is sweeping from left to the right - this defines the most left postion. Default is 140. Allowed 10 <= pos_center <= 170.
sweep_right_posIf the servo is sweeping from left to the right - this defines the most right postion. Default is 40. Allowed 10 <= pos_center <= 170.
-
-
-
Returns
nothing
- -

Definition at line 510 of file CodeRacer.cpp.

-
511 {
512  servo_center_pos = pos_center;
513  servo_left_pos = pos_left;
514  servo_right_pos = pos_right;
515  servo_sweep_left_pos = sweep_left_pos;
516  servo_sweep_right_pos = sweep_right_pos;
517 }
-
-
- -

◆ servo_sweep()

- -
-
- - - - - - - -
void CodeRacer::servo_sweep ()
-
- -

Turns sweeping of the servo from left to right and back on.

-

The sweeping range is defind by #servo_sweep_left_pos and #servo_sweep_right_pos attributes. Both can be set by either servo_settings() or as public members. Every time servo_sweep() is called the servo is driven by 5 steps until either #servo_sweep_left_pos or #servo_sweep_right_pos is reached. Then it will turn the direction and step to the other side every time this method is called.

Returns
nothing
- -

Definition at line 526 of file CodeRacer.cpp.

-
527 {
528  uint8_t position;
529  _servo_sweep = true;
530  if (millis() - _servo_position_set_at_ms > SERVO_SWEEP_MS) {
531  position = _servo_position + _servo_sweep_step;
532  //sprintf(_debugmsg,"[%s] current position=%ld newpostion=%ld", __func__, _servo_position, position);
533  if ((position >= servo_sweep_left_pos) || (position >= SERVO_MAX_POSITION)) {
534  position = servo_sweep_left_pos;
535  _servo_sweep_step = SERVO_SWEEP_TO_RIGHT_STEP;
536  }
537  if ((position <= servo_sweep_right_pos) || (position <= SERVO_MIN_POSITION)) {
538  position = servo_sweep_right_pos;
539  _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP;
540  }
541  _servo_set_position(position);
542  }
543 }
-
-
- -

◆ servo_set_to_right()

- -
-
- - - - - - - -
void CodeRacer::servo_set_to_right ()
-
- -

Drives the servo to the postion that is defined by #servo_right_pos.

-
Returns
nothing
- -

Definition at line 548 of file CodeRacer.cpp.

-
549 {
550  servo_set_position_wait(servo_right_pos);
551 }
-
-
- -

◆ servo_set_to_left()

- -
-
- - - - - - - -
void CodeRacer::servo_set_to_left ()
-
- -

Drives the servo to the postion that is defined by #servo_left_pos.

-
Returns
nothing
- -

Definition at line 556 of file CodeRacer.cpp.

-
557 {
558  servo_set_position_wait(servo_left_pos);
559 }
-
-
- -

◆ servo_set_to_center()

- -
-
- - - - - - - -
void CodeRacer::servo_set_to_center ()
-
- -

Drives the servo to the postion that is defined by #servo_center_pos.

-
Returns
nothing
- -

Definition at line 564 of file CodeRacer.cpp.

-
565 {
566  servo_set_position_wait(servo_center_pos);
567 }
-
-
- -

◆ servo_set_position_wait()

- -
-
- - - - - - - - -
uint8_t CodeRacer::servo_set_position_wait (uint8_t position)
-
- -

Drive the servo to the postion given to this method.

-

The method will wait until the servo has reached its new position.

Parameters
- - -
positionPosition the servo will be drived to. Allowed are values 10<=postion<=170. 10 is at the right hand side, 170 at the left hand side.
-
-
-
Returns
The new servo position
- -

Definition at line 575 of file CodeRacer.cpp.

-
576 {
577  _servo_sweep = false;
578  unsigned long wait_time_ms = _servo_set_position(position);
579  delay(wait_time_ms);
580  return(_servo_position);
581 }
-
-
- -

◆ servo_set_position()

- -
-
- - - - - - - - -
unsigned long CodeRacer::servo_set_position (uint8_t position)
-
- -

Drive the servo to the postion given to this method.

-

The method will not wait until the servo has reached its new position.

Parameters
- - -
positionPosition the servo will be drived to. Allowed are values 10<=postion<=170. 10 is at the right hand side, 170 at the left hand side.
-
-
-
Returns
The time in ms the servo will need to reach the new position
- -

Definition at line 589 of file CodeRacer.cpp.

-
590 {
591  _servo_sweep = false;
592  unsigned long wait_time_ms = _servo_set_position(position);
593  return(wait_time_ms);
594 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.js b/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.js deleted file mode 100644 index 31816e6..0000000 --- a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.js +++ /dev/null @@ -1,10 +0,0 @@ -var group__lowerlevelservomeths = -[ - [ "servo_settings", "db/dd5/group__lowerlevelservomeths.html#ga687beb327e20f4d0541d1ac9e29c01c3", null ], - [ "servo_sweep", "db/dd5/group__lowerlevelservomeths.html#ga1e9afe1f27dfc9796b4c9b3dba245365", null ], - [ "servo_set_to_right", "db/dd5/group__lowerlevelservomeths.html#gaac73bf99cf2d19f7b1987156aa842b74", null ], - [ "servo_set_to_left", "db/dd5/group__lowerlevelservomeths.html#gaef7d1903b65a0a8ab4fafdc53080b07d", null ], - [ "servo_set_to_center", "db/dd5/group__lowerlevelservomeths.html#gad1f28aa91079e88fc3093e3074edfb32", null ], - [ "servo_set_position_wait", "db/dd5/group__lowerlevelservomeths.html#ga0149226288bff2290d52ed1cbd674edd", null ], - [ "servo_set_position", "db/dd5/group__lowerlevelservomeths.html#gab8831340049de6dbddeda997745725e6", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.map b/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.map deleted file mode 100644 index 7a7777f..0000000 --- a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.md5 b/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.md5 deleted file mode 100644 index 85f67fb..0000000 --- a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.md5 +++ /dev/null @@ -1 +0,0 @@ -597c50e7dc706800e2ae683735d343f0 \ No newline at end of file diff --git a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.png b/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.png deleted file mode 100644 index acf96f0..0000000 Binary files a/Doku/Doxygen/html/db/dd5/group__lowerlevelservomeths.png and /dev/null differ diff --git a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.html b/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.html deleted file mode 100644 index b924235..0000000 --- a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.html +++ /dev/null @@ -1,221 +0,0 @@ - - - - - - - -Arduino {code}racer API: Setters and getters - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - - - - -

-Functions

void CodeRacer::usonic_set_stop_distance_cm (unsigned long stop_distance_cm)
 Sets the stop distance in cm. More...
 
void CodeRacer::usonic_set_stop_distance_us (unsigned long stop_distance_us)
 Sets the stop distance in cm. More...
 
unsigned long CodeRacer::usonic_distance_us ()
 Returns the last measured distance in microseconds. More...
 
unsigned long CodeRacer::usonic_distance_cm ()
 Returns the last measured distance in cm. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ usonic_set_stop_distance_cm()

- -
-
- - - - - - - - -
void CodeRacer::usonic_set_stop_distance_cm (unsigned long stop_distance_cm)
-
- -

Sets the stop distance in cm.

-

If start_stop_at_min_distance() is used and distance measured with one of the measurement methods - the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. Internally the stop distance will be set as both - in cm and in microseconds.

Parameters
- - -
stop_distance_cmDistance in cm the racer will be stopped if that features was enabled by start_stop_at_min_distance() before.
-
-
-
Returns
nothing
- -

Definition at line 825 of file CodeRacer.cpp.

-
826 {
827  _usonic_stop_distance_us = stop_distance_cm * 58.14;
828 }
-
-
- -

◆ usonic_set_stop_distance_us()

- -
-
- - - - - - - - -
void CodeRacer::usonic_set_stop_distance_us (unsigned long stop_distance_us)
-
- -

Sets the stop distance in cm.

-

If start_stop_at_min_distance() is used and distance measured with one of the measurement methods - the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. Internally the stop distance will be set as both - in cm and in microseconds.

Parameters
- - -
stop_distance_usDistance in cm the racer will be stopped if that features was enabled by start_stop_at_min_distance() before.
-
-
-
Returns
nothing
- -

Definition at line 837 of file CodeRacer.cpp.

-
838 {
839  _usonic_stop_distance_us = stop_distance_us;
840 }
-
-
- -

◆ usonic_distance_us()

- -
-
- - - - - - - -
unsigned long CodeRacer::usonic_distance_us ()
-
- -

Returns the last measured distance in microseconds.

-
Returns
Distance in microseconds
- -

Definition at line 845 of file CodeRacer.cpp.

-
845  {
846  return(_usonic_distance_us);
847 }
-
-
- -

◆ usonic_distance_cm()

- -
-
- - - - - - - -
unsigned long CodeRacer::usonic_distance_cm ()
-
- -

Returns the last measured distance in cm.

-
Returns
Distance in cm
- -

Definition at line 852 of file CodeRacer.cpp.

-
852  {
853  return(_usonic_distance_cm);
854 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.js b/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.js deleted file mode 100644 index 33d391f..0000000 --- a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.js +++ /dev/null @@ -1,7 +0,0 @@ -var group__lowerlevelusgetters = -[ - [ "usonic_set_stop_distance_cm", "db/ddd/group__lowerlevelusgetters.html#gaa7c5a6563a5736ed38d12f616de480df", null ], - [ "usonic_set_stop_distance_us", "db/ddd/group__lowerlevelusgetters.html#ga2f06c193ae86c5b1cba450caf5adf146", null ], - [ "usonic_distance_us", "db/ddd/group__lowerlevelusgetters.html#ga917b90f21e731ef5f690d5198e7f4d3e", null ], - [ "usonic_distance_cm", "db/ddd/group__lowerlevelusgetters.html#gad59842c14196598e55644b2a22621454", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.map b/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.map deleted file mode 100644 index 067e2ec..0000000 --- a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.md5 b/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.md5 deleted file mode 100644 index 2541f41..0000000 --- a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.md5 +++ /dev/null @@ -1 +0,0 @@ -2ea30e8364ac6dafffce41eb4e6f6037 \ No newline at end of file diff --git a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.png b/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.png deleted file mode 100644 index 9248f22..0000000 Binary files a/Doku/Doxygen/html/db/ddd/group__lowerlevelusgetters.png and /dev/null differ diff --git a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.html b/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.html deleted file mode 100644 index fb33954..0000000 --- a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.html +++ /dev/null @@ -1,246 +0,0 @@ - - - - - - - -Arduino {code}racer API: Methods - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- - -
- - - - - - - - - - - - - - -

-Functions

void CodeRacer::set_leds_left_stop_frwd_right (ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled)
 Sets all of the 4 LEDs to a ledstate (LEDON, LEDOFF) More...
 
void CodeRacer::set_leds_all (ledstate alleds)
 Sets all of the 4 LEDs to the same ledstate (LEDON, LEDOFF) More...
 
void CodeRacer::set_leds_all_off ()
 Sets all of the 4 LEDs to the ledstate LEDOFF. More...
 
void CodeRacer::set_leds_all_on ()
 Sets all of the 4 LEDs to the ledstate LEDON. More...
 
-

Detailed Description

-

Function Documentation

- -

◆ set_leds_left_stop_frwd_right()

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
void CodeRacer::set_leds_left_stop_frwd_right (ledstate leftled,
ledstate stopled,
ledstate frwdled,
ledstate rightled 
)
-
- -

Sets all of the 4 LEDs to a ledstate (LEDON, LEDOFF)

-
Parameters
- - - - - -
leftledset state of status left LED (most left yellow led)
stopledset state of status stop LED (red led)
frwdledset state of status forward LED (green or blue led)
rightledset state of status right LED (most right yellow led)
-
-
-
Returns
nothing
- -

Definition at line 1037 of file CodeRacer.cpp.

-
1037  {
1038  digitalWrite(_led_left_pin, leftled);
1039  digitalWrite(_led_frwd_pin, frwdled);
1040  digitalWrite(_led_right_pin, rightled);
1041  digitalWrite(_led_stop_pin, stopled);
1042 }
-
-
- -

◆ set_leds_all()

- -
-
- - - - - - - - -
void CodeRacer::set_leds_all (ledstate alleds)
-
- -

Sets all of the 4 LEDs to the same ledstate (LEDON, LEDOFF)

-
Parameters
- - -
alledsset state to all status LEDs
-
-
-
Returns
nothing
- -

Definition at line 1048 of file CodeRacer.cpp.

-
1048  {
1049  digitalWrite(_led_left_pin, alleds);
1050  digitalWrite(_led_frwd_pin, alleds);
1051  digitalWrite(_led_right_pin, alleds);
1052  digitalWrite(_led_stop_pin, alleds);
1053 }
-
-
- -

◆ set_leds_all_off()

- -
-
- - - - - - - -
void CodeRacer::set_leds_all_off ()
-
- -

Sets all of the 4 LEDs to the ledstate LEDOFF.

-
Returns
nothing
- -

Definition at line 1058 of file CodeRacer.cpp.

-
1058  {
1059  set_leds_all(LEDOFF);
1060 }
-
-
- -

◆ set_leds_all_on()

- -
-
- - - - - - - -
void CodeRacer::set_leds_all_on ()
-
- -

Sets all of the 4 LEDs to the ledstate LEDON.

-
Returns
nothing
- -

Definition at line 1065 of file CodeRacer.cpp.

-
1065  {
1066  set_leds_all(LEDON);
1067 }
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.js b/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.js deleted file mode 100644 index b215041..0000000 --- a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.js +++ /dev/null @@ -1,7 +0,0 @@ -var group__lowerlevelledmeths = -[ - [ "set_leds_left_stop_frwd_right", "dd/dff/group__lowerlevelledmeths.html#gab2514ca3994de3d64337dd6536fa6ef3", null ], - [ "set_leds_all", "dd/dff/group__lowerlevelledmeths.html#gab4319e66963b1b71a34370d73962fa78", null ], - [ "set_leds_all_off", "dd/dff/group__lowerlevelledmeths.html#gaa3f2ad08103127f2cb49344c33b666ea", null ], - [ "set_leds_all_on", "dd/dff/group__lowerlevelledmeths.html#ga0c8b3d6ce992e1dcfd13fd86c9f89846", null ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.map b/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.map deleted file mode 100644 index e62e212..0000000 --- a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.map +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.md5 b/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.md5 deleted file mode 100644 index 68186e4..0000000 --- a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.md5 +++ /dev/null @@ -1 +0,0 @@ -92c6efd7535f583cf9e0049790e5e563 \ No newline at end of file diff --git a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.png b/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.png deleted file mode 100644 index 656cf74..0000000 Binary files a/Doku/Doxygen/html/dd/dff/group__lowerlevelledmeths.png and /dev/null differ diff --git a/Doku/Doxygen/html/dir_11f10faf8e1af149a19b120728e5c8cd.html b/Doku/Doxygen/html/dir_11f10faf8e1af149a19b120728e5c8cd.html deleted file mode 100644 index 0f78499..0000000 --- a/Doku/Doxygen/html/dir_11f10faf8e1af149a19b120728e5c8cd.html +++ /dev/null @@ -1,100 +0,0 @@ - - - - - - - -Arduino {code}racer API: C:/Users/jnoack/Documents/Arduino/libraries/CodeRacer Directory Reference - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
-
-
CodeRacer Directory Reference
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/dir_481cc946b8a81b8d9363a4aad6201160.html b/Doku/Doxygen/html/dir_481cc946b8a81b8d9363a4aad6201160.html deleted file mode 100644 index 61a2784..0000000 --- a/Doku/Doxygen/html/dir_481cc946b8a81b8d9363a4aad6201160.html +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - -Arduino {code}racer API: C:/Users/jnoack/Documents/Arduino/libraries Directory Reference - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
-
-
libraries Directory Reference
-
-
- - -

-Directories

-
-
- - - - diff --git a/Doku/Doxygen/html/dir_a991eec27578c865874ede3d8ec657c2.html b/Doku/Doxygen/html/dir_a991eec27578c865874ede3d8ec657c2.html deleted file mode 100644 index b1fe5c0..0000000 --- a/Doku/Doxygen/html/dir_a991eec27578c865874ede3d8ec657c2.html +++ /dev/null @@ -1,100 +0,0 @@ - - - - - - - -Arduino {code}racer API: C:/Users/jnoack/Documents/Arduino Directory Reference - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
-
-
Arduino Directory Reference
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/doc.png b/Doku/Doxygen/html/doc.png deleted file mode 100644 index 17edabf..0000000 Binary files a/Doku/Doxygen/html/doc.png and /dev/null differ diff --git a/Doku/Doxygen/html/doxygen.css b/Doku/Doxygen/html/doxygen.css deleted file mode 100644 index 4f1ab91..0000000 --- a/Doku/Doxygen/html/doxygen.css +++ /dev/null @@ -1,1596 +0,0 @@ -/* The standard CSS for doxygen 1.8.13 */ - -body, table, div, p, dl { - font: 400 14px/22px Roboto,sans-serif; -} - -p.reference, p.definition { - font: 400 14px/22px Roboto,sans-serif; -} - -/* @group Heading Levels */ - -h1.groupheader { - font-size: 150%; -} - -.title { - font: 400 14px/28px Roboto,sans-serif; - font-size: 150%; - font-weight: bold; - margin: 10px 2px; -} - -h2.groupheader { - border-bottom: 1px solid #879ECB; - color: #354C7B; - font-size: 150%; - font-weight: normal; - margin-top: 1.75em; - padding-top: 8px; - padding-bottom: 4px; - width: 100%; -} - -h3.groupheader { - font-size: 100%; -} - -h1, h2, h3, h4, h5, h6 { - -webkit-transition: text-shadow 0.5s linear; - -moz-transition: text-shadow 0.5s linear; - -ms-transition: text-shadow 0.5s linear; - -o-transition: text-shadow 0.5s linear; - transition: text-shadow 0.5s linear; - margin-right: 15px; -} - -h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { - text-shadow: 0 0 15px cyan; -} - -dt { - font-weight: bold; -} - -div.multicol { - -moz-column-gap: 1em; - -webkit-column-gap: 1em; - -moz-column-count: 3; - -webkit-column-count: 3; -} - -p.startli, p.startdd { - margin-top: 2px; -} - -p.starttd { - margin-top: 0px; -} - -p.endli { - margin-bottom: 0px; -} - -p.enddd { - margin-bottom: 4px; -} - -p.endtd { - margin-bottom: 2px; -} - -/* @end */ - -caption { - font-weight: bold; -} - -span.legend { - font-size: 70%; - text-align: center; -} - -h3.version { - font-size: 90%; - text-align: center; -} - -div.qindex, div.navtab{ - background-color: #EBEFF6; - border: 1px solid #A3B4D7; - text-align: center; -} - -div.qindex, div.navpath { - width: 100%; - line-height: 140%; -} - -div.navtab { - margin-right: 15px; -} - -/* @group Link Styling */ - -a { - color: #3D578C; - font-weight: normal; - text-decoration: none; -} - -.contents a:visited { - color: #4665A2; -} - -a:hover { - text-decoration: underline; -} - -a.qindex { - font-weight: bold; -} - -a.qindexHL { - font-weight: bold; - background-color: #9CAFD4; - color: #ffffff; - border: 1px double #869DCA; -} - -.contents a.qindexHL:visited { - color: #ffffff; -} - -a.el { - font-weight: bold; -} - -a.elRef { -} - -a.code, a.code:visited, a.line, a.line:visited { - color: #4665A2; -} - -a.codeRef, a.codeRef:visited, a.lineRef, a.lineRef:visited { - color: #4665A2; -} - -/* @end */ - -dl.el { - margin-left: -1cm; -} - -pre.fragment { - border: 1px solid #C4CFE5; - background-color: #FBFCFD; - padding: 4px 6px; - margin: 4px 8px 4px 2px; - overflow: auto; - word-wrap: break-word; - font-size: 9pt; - line-height: 125%; - font-family: monospace, fixed; - font-size: 105%; -} - -div.fragment { - padding: 0px; - margin: 4px 8px 4px 2px; - background-color: #FBFCFD; - border: 1px solid #C4CFE5; -} - -div.line { - font-family: monospace, fixed; - font-size: 13px; - min-height: 13px; - line-height: 1.0; - text-wrap: unrestricted; - white-space: -moz-pre-wrap; /* Moz */ - white-space: -pre-wrap; /* Opera 4-6 */ - white-space: -o-pre-wrap; /* Opera 7 */ - white-space: pre-wrap; /* CSS3 */ - word-wrap: break-word; /* IE 5.5+ */ - text-indent: -53px; - padding-left: 53px; - padding-bottom: 0px; - margin: 0px; - -webkit-transition-property: background-color, box-shadow; - -webkit-transition-duration: 0.5s; - -moz-transition-property: background-color, box-shadow; - -moz-transition-duration: 0.5s; - -ms-transition-property: background-color, box-shadow; - -ms-transition-duration: 0.5s; - -o-transition-property: background-color, box-shadow; - -o-transition-duration: 0.5s; - transition-property: background-color, box-shadow; - transition-duration: 0.5s; -} - -div.line:after { - content:"\000A"; - white-space: pre; -} - -div.line.glow { - background-color: cyan; - box-shadow: 0 0 10px cyan; -} - - -span.lineno { - padding-right: 4px; - text-align: right; - border-right: 2px solid #0F0; - background-color: #E8E8E8; - white-space: pre; -} -span.lineno a { - background-color: #D8D8D8; -} - -span.lineno a:hover { - background-color: #C8C8C8; -} - -.lineno { - -webkit-touch-callout: none; - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; -} - -div.ah, span.ah { - background-color: black; - font-weight: bold; - color: #ffffff; - margin-bottom: 3px; - margin-top: 3px; - padding: 0.2em; - border: solid thin #333; - border-radius: 0.5em; - -webkit-border-radius: .5em; - -moz-border-radius: .5em; - box-shadow: 2px 2px 3px #999; - -webkit-box-shadow: 2px 2px 3px #999; - -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; - background-image: -webkit-gradient(linear, left top, left bottom, from(#eee), to(#000),color-stop(0.3, #444)); - background-image: -moz-linear-gradient(center top, #eee 0%, #444 40%, #000 110%); -} - -div.classindex ul { - list-style: none; - padding-left: 0; -} - -div.classindex span.ai { - display: inline-block; -} - -div.groupHeader { - margin-left: 16px; - margin-top: 12px; - font-weight: bold; -} - -div.groupText { - margin-left: 16px; - font-style: italic; -} - -body { - background-color: white; - color: black; - margin: 0; -} - -div.contents { - margin-top: 10px; - margin-left: 12px; - margin-right: 8px; -} - -td.indexkey { - background-color: #EBEFF6; - font-weight: bold; - border: 1px solid #C4CFE5; - margin: 2px 0px 2px 0; - padding: 2px 10px; - white-space: nowrap; - vertical-align: top; -} - -td.indexvalue { - background-color: #EBEFF6; - border: 1px solid #C4CFE5; - padding: 2px 10px; - margin: 2px 0px; -} - -tr.memlist { - background-color: #EEF1F7; -} - -p.formulaDsp { - text-align: center; -} - -img.formulaDsp { - -} - -img.formulaInl { - vertical-align: middle; -} - -div.center { - text-align: center; - margin-top: 0px; - margin-bottom: 0px; - padding: 0px; -} - -div.center img { - border: 0px; -} - -address.footer { - text-align: right; - padding-right: 12px; -} - -img.footer { - border: 0px; - vertical-align: middle; -} - -/* @group Code Colorization */ - -span.keyword { - color: #008000 -} - -span.keywordtype { - color: #604020 -} - -span.keywordflow { - color: #e08000 -} - -span.comment { - color: #800000 -} - -span.preprocessor { - color: #806020 -} - -span.stringliteral { - color: #002080 -} - -span.charliteral { - color: #008080 -} - -span.vhdldigit { - color: #ff00ff -} - -span.vhdlchar { - color: #000000 -} - -span.vhdlkeyword { - color: #700070 -} - -span.vhdllogic { - color: #ff0000 -} - -blockquote { - background-color: #F7F8FB; - border-left: 2px solid #9CAFD4; - margin: 0 24px 0 4px; - padding: 0 12px 0 16px; -} - -/* @end */ - -/* -.search { - color: #003399; - font-weight: bold; -} - -form.search { - margin-bottom: 0px; - margin-top: 0px; -} - -input.search { - font-size: 75%; - color: #000080; - font-weight: normal; - background-color: #e8eef2; -} -*/ - -td.tiny { - font-size: 75%; -} - -.dirtab { - padding: 4px; - border-collapse: collapse; - border: 1px solid #A3B4D7; -} - -th.dirtab { - background: #EBEFF6; - font-weight: bold; -} - -hr { - height: 0px; - border: none; - border-top: 1px solid #4A6AAA; -} - -hr.footer { - height: 1px; -} - -/* @group Member Descriptions */ - -table.memberdecls { - border-spacing: 0px; - padding: 0px; -} - -.memberdecls td, .fieldtable tr { - -webkit-transition-property: background-color, box-shadow; - -webkit-transition-duration: 0.5s; - -moz-transition-property: background-color, box-shadow; - -moz-transition-duration: 0.5s; - -ms-transition-property: background-color, box-shadow; - -ms-transition-duration: 0.5s; - -o-transition-property: background-color, box-shadow; - -o-transition-duration: 0.5s; - transition-property: background-color, box-shadow; - transition-duration: 0.5s; -} - -.memberdecls td.glow, .fieldtable tr.glow { - background-color: cyan; - box-shadow: 0 0 15px cyan; -} - -.mdescLeft, .mdescRight, -.memItemLeft, .memItemRight, -.memTemplItemLeft, .memTemplItemRight, .memTemplParams { - background-color: #F9FAFC; - border: none; - margin: 4px; - padding: 1px 0 0 8px; -} - -.mdescLeft, .mdescRight { - padding: 0px 8px 4px 8px; - color: #555; -} - -.memSeparator { - border-bottom: 1px solid #DEE4F0; - line-height: 1px; - margin: 0px; - padding: 0px; -} - -.memItemLeft, .memTemplItemLeft { - white-space: nowrap; -} - -.memItemRight { - width: 100%; -} - -.memTemplParams { - color: #4665A2; - white-space: nowrap; - font-size: 80%; -} - -/* @end */ - -/* @group Member Details */ - -/* Styles for detailed member documentation */ - -.memtitle { - padding: 8px; - border-top: 1px solid #A8B8D9; - border-left: 1px solid #A8B8D9; - border-right: 1px solid #A8B8D9; - border-top-right-radius: 4px; - border-top-left-radius: 4px; - margin-bottom: -1px; - background-image: url('nav_f.png'); - background-repeat: repeat-x; - background-color: #E2E8F2; - line-height: 1.25; - font-weight: 300; - float:left; -} - -.permalink -{ - font-size: 65%; - display: inline-block; - vertical-align: middle; -} - -.memtemplate { - font-size: 80%; - color: #4665A2; - font-weight: normal; - margin-left: 9px; -} - -.memnav { - background-color: #EBEFF6; - border: 1px solid #A3B4D7; - text-align: center; - margin: 2px; - margin-right: 15px; - padding: 2px; -} - -.mempage { - width: 100%; -} - -.memitem { - padding: 0; - margin-bottom: 10px; - margin-right: 5px; - -webkit-transition: box-shadow 0.5s linear; - -moz-transition: box-shadow 0.5s linear; - -ms-transition: box-shadow 0.5s linear; - -o-transition: box-shadow 0.5s linear; - transition: box-shadow 0.5s linear; - display: table !important; - width: 100%; -} - -.memitem.glow { - box-shadow: 0 0 15px cyan; -} - -.memname { - font-weight: 400; - margin-left: 6px; -} - -.memname td { - vertical-align: bottom; -} - -.memproto, dl.reflist dt { - border-top: 1px solid #A8B8D9; - border-left: 1px solid #A8B8D9; - border-right: 1px solid #A8B8D9; - padding: 6px 0px 6px 0px; - color: #253555; - font-weight: bold; - text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); - background-color: #DFE5F1; - /* opera specific markup */ - box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); - border-top-right-radius: 4px; - /* firefox specific markup */ - -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; - -moz-border-radius-topright: 4px; - /* webkit specific markup */ - -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); - -webkit-border-top-right-radius: 4px; - -} - -.overload { - font-family: "courier new",courier,monospace; - font-size: 65%; -} - -.memdoc, dl.reflist dd { - border-bottom: 1px solid #A8B8D9; - border-left: 1px solid #A8B8D9; - border-right: 1px solid #A8B8D9; - padding: 6px 10px 2px 10px; - background-color: #FBFCFD; - border-top-width: 0; - background-image:url('nav_g.png'); - background-repeat:repeat-x; - background-color: #FFFFFF; - /* opera specific markup */ - border-bottom-left-radius: 4px; - border-bottom-right-radius: 4px; - box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); - /* firefox specific markup */ - -moz-border-radius-bottomleft: 4px; - -moz-border-radius-bottomright: 4px; - -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; - /* webkit specific markup */ - -webkit-border-bottom-left-radius: 4px; - -webkit-border-bottom-right-radius: 4px; - -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -} - -dl.reflist dt { - padding: 5px; -} - -dl.reflist dd { - margin: 0px 0px 10px 0px; - padding: 5px; -} - -.paramkey { - text-align: right; -} - -.paramtype { - white-space: nowrap; -} - -.paramname { - color: #602020; - white-space: nowrap; -} -.paramname em { - font-style: normal; -} -.paramname code { - line-height: 14px; -} - -.params, .retval, .exception, .tparams { - margin-left: 0px; - padding-left: 0px; -} - -.params .paramname, .retval .paramname { - font-weight: bold; - vertical-align: top; -} - -.params .paramtype { - font-style: italic; - vertical-align: top; -} - -.params .paramdir { - font-family: "courier new",courier,monospace; - vertical-align: top; -} - -table.mlabels { - border-spacing: 0px; -} - -td.mlabels-left { - width: 100%; - padding: 0px; -} - -td.mlabels-right { - vertical-align: bottom; - padding: 0px; - white-space: nowrap; -} - -span.mlabels { - margin-left: 8px; -} - -span.mlabel { - background-color: #728DC1; - border-top:1px solid #5373B4; - border-left:1px solid #5373B4; - border-right:1px solid #C4CFE5; - border-bottom:1px solid #C4CFE5; - text-shadow: none; - color: white; - margin-right: 4px; - padding: 2px 3px; - border-radius: 3px; - font-size: 7pt; - white-space: nowrap; - vertical-align: middle; -} - - - -/* @end */ - -/* these are for tree view inside a (index) page */ - -div.directory { - margin: 10px 0px; - border-top: 1px solid #9CAFD4; - border-bottom: 1px solid #9CAFD4; - width: 100%; -} - -.directory table { - border-collapse:collapse; -} - -.directory td { - margin: 0px; - padding: 0px; - vertical-align: top; -} - -.directory td.entry { - white-space: nowrap; - padding-right: 6px; - padding-top: 3px; -} - -.directory td.entry a { - outline:none; -} - -.directory td.entry a img { - border: none; -} - -.directory td.desc { - width: 100%; - padding-left: 6px; - padding-right: 6px; - padding-top: 3px; - border-left: 1px solid rgba(0,0,0,0.05); -} - -.directory tr.even { - padding-left: 6px; - background-color: #F7F8FB; -} - -.directory img { - vertical-align: -30%; -} - -.directory .levels { - white-space: nowrap; - width: 100%; - text-align: right; - font-size: 9pt; -} - -.directory .levels span { - cursor: pointer; - padding-left: 2px; - padding-right: 2px; - color: #3D578C; -} - -.arrow { - color: #9CAFD4; - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; - cursor: pointer; - font-size: 80%; - display: inline-block; - width: 16px; - height: 22px; -} - -.icon { - font-family: Arial, Helvetica; - font-weight: bold; - font-size: 12px; - height: 14px; - width: 16px; - display: inline-block; - background-color: #728DC1; - color: white; - text-align: center; - border-radius: 4px; - margin-left: 2px; - margin-right: 2px; -} - -.icona { - width: 24px; - height: 22px; - display: inline-block; -} - -.iconfopen { - width: 24px; - height: 18px; - margin-bottom: 4px; - background-image:url('folderopen.png'); - background-position: 0px -4px; - background-repeat: repeat-y; - vertical-align:top; - display: inline-block; -} - -.iconfclosed { - width: 24px; - height: 18px; - margin-bottom: 4px; - background-image:url('folderclosed.png'); - background-position: 0px -4px; - background-repeat: repeat-y; - vertical-align:top; - display: inline-block; -} - -.icondoc { - width: 24px; - height: 18px; - margin-bottom: 4px; - background-image:url('doc.png'); - background-position: 0px -4px; - background-repeat: repeat-y; - vertical-align:top; - display: inline-block; -} - -table.directory { - font: 400 14px Roboto,sans-serif; -} - -/* @end */ - -div.dynheader { - margin-top: 8px; - -webkit-touch-callout: none; - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; -} - -address { - font-style: normal; - color: #2A3D61; -} - -table.doxtable caption { - caption-side: top; -} - -table.doxtable { - border-collapse:collapse; - margin-top: 4px; - margin-bottom: 4px; -} - -table.doxtable td, table.doxtable th { - border: 1px solid #2D4068; - padding: 3px 7px 2px; -} - -table.doxtable th { - background-color: #374F7F; - color: #FFFFFF; - font-size: 110%; - padding-bottom: 4px; - padding-top: 5px; -} - -table.fieldtable { - /*width: 100%;*/ - margin-bottom: 10px; - border: 1px solid #A8B8D9; - border-spacing: 0px; - -moz-border-radius: 4px; - -webkit-border-radius: 4px; - border-radius: 4px; - -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; - -webkit-box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); - box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); -} - -.fieldtable td, .fieldtable th { - padding: 3px 7px 2px; -} - -.fieldtable td.fieldtype, .fieldtable td.fieldname { - white-space: nowrap; - border-right: 1px solid #A8B8D9; - border-bottom: 1px solid #A8B8D9; - vertical-align: top; -} - -.fieldtable td.fieldname { - padding-top: 3px; -} - -.fieldtable td.fielddoc { - border-bottom: 1px solid #A8B8D9; - /*width: 100%;*/ -} - -.fieldtable td.fielddoc p:first-child { - margin-top: 0px; -} - -.fieldtable td.fielddoc p:last-child { - margin-bottom: 2px; -} - -.fieldtable tr:last-child td { - border-bottom: none; -} - -.fieldtable th { - background-image:url('nav_f.png'); - background-repeat:repeat-x; - background-color: #E2E8F2; - font-size: 90%; - color: #253555; - padding-bottom: 4px; - padding-top: 5px; - text-align:left; - font-weight: 400; - -moz-border-radius-topleft: 4px; - -moz-border-radius-topright: 4px; - -webkit-border-top-left-radius: 4px; - -webkit-border-top-right-radius: 4px; - border-top-left-radius: 4px; - border-top-right-radius: 4px; - border-bottom: 1px solid #A8B8D9; -} - - -.tabsearch { - top: 0px; - left: 10px; - height: 36px; - background-image: url('tab_b.png'); - z-index: 101; - overflow: hidden; - font-size: 13px; -} - -.navpath ul -{ - font-size: 11px; - background-image:url('tab_b.png'); - background-repeat:repeat-x; - background-position: 0 -5px; - height:30px; - line-height:30px; - color:#8AA0CC; - border:solid 1px #C2CDE4; - overflow:hidden; - margin:0px; - padding:0px; -} - -.navpath li -{ - list-style-type:none; - float:left; - padding-left:10px; - padding-right:15px; - background-image:url('bc_s.png'); - background-repeat:no-repeat; - background-position:right; - color:#364D7C; -} - -.navpath li.navelem a -{ - height:32px; - display:block; - text-decoration: none; - outline: none; - color: #283A5D; - font-family: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; - text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); - text-decoration: none; -} - -.navpath li.navelem a:hover -{ - color:#6884BD; -} - -.navpath li.footer -{ - list-style-type:none; - float:right; - padding-left:10px; - padding-right:15px; - background-image:none; - background-repeat:no-repeat; - background-position:right; - color:#364D7C; - font-size: 8pt; -} - - -div.summary -{ - float: right; - font-size: 8pt; - padding-right: 5px; - width: 50%; - text-align: right; -} - -div.summary a -{ - white-space: nowrap; -} - -table.classindex -{ - margin: 10px; - white-space: nowrap; - margin-left: 3%; - margin-right: 3%; - width: 94%; - border: 0; - border-spacing: 0; - padding: 0; -} - -div.ingroups -{ - font-size: 8pt; - width: 50%; - text-align: left; -} - -div.ingroups a -{ - white-space: nowrap; -} - -div.header -{ - background-image:url('nav_h.png'); - background-repeat:repeat-x; - background-color: #F9FAFC; - margin: 0px; - border-bottom: 1px solid #C4CFE5; -} - -div.headertitle -{ - padding: 5px 5px 5px 10px; -} - -dl -{ - padding: 0 0 0 10px; -} - -/* dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug */ -dl.section -{ - margin-left: 0px; - padding-left: 0px; -} - -dl.note -{ - margin-left:-7px; - padding-left: 3px; - border-left:4px solid; - border-color: #D0C000; -} - -dl.warning, dl.attention -{ - margin-left:-7px; - padding-left: 3px; - border-left:4px solid; - border-color: #FF0000; -} - -dl.pre, dl.post, dl.invariant -{ - margin-left:-7px; - padding-left: 3px; - border-left:4px solid; - border-color: #00D000; -} - -dl.deprecated -{ - margin-left:-7px; - padding-left: 3px; - border-left:4px solid; - border-color: #505050; -} - -dl.todo -{ - margin-left:-7px; - padding-left: 3px; - border-left:4px solid; - border-color: #00C0E0; -} - -dl.test -{ - margin-left:-7px; - padding-left: 3px; - border-left:4px solid; - border-color: #3030E0; -} - -dl.bug -{ - margin-left:-7px; - padding-left: 3px; - border-left:4px solid; - border-color: #C08050; -} - -dl.section dd { - margin-bottom: 6px; -} - - -#projectlogo -{ - text-align: center; - vertical-align: bottom; - border-collapse: separate; -} - -#projectlogo img -{ - border: 0px none; -} - -#projectalign -{ - vertical-align: middle; -} - -#projectname -{ - font: 300% Tahoma, Arial,sans-serif; - margin: 0px; - padding: 2px 0px; -} - -#projectbrief -{ - font: 120% Tahoma, Arial,sans-serif; - margin: 0px; - padding: 0px; -} - -#projectnumber -{ - font: 50% Tahoma, Arial,sans-serif; - margin: 0px; - padding: 0px; -} - -#titlearea -{ - padding: 0px; - margin: 0px; - width: 100%; - border-bottom: 1px solid #5373B4; -} - -.image -{ - text-align: center; -} - -.dotgraph -{ - text-align: center; -} - -.mscgraph -{ - text-align: center; -} - -.plantumlgraph -{ - text-align: center; -} - -.diagraph -{ - text-align: center; -} - -.caption -{ - font-weight: bold; -} - -div.zoom -{ - border: 1px solid #90A5CE; -} - -dl.citelist { - margin-bottom:50px; -} - -dl.citelist dt { - color:#334975; - float:left; - font-weight:bold; - margin-right:10px; - padding:5px; -} - -dl.citelist dd { - margin:2px 0; - padding:5px 0; -} - -div.toc { - padding: 14px 25px; - background-color: #F4F6FA; - border: 1px solid #D8DFEE; - border-radius: 7px 7px 7px 7px; - float: right; - height: auto; - margin: 0 8px 10px 10px; - width: 200px; -} - -div.toc li { - background: url("bdwn.png") no-repeat scroll 0 5px transparent; - font: 10px/1.2 Verdana,DejaVu Sans,Geneva,sans-serif; - margin-top: 5px; - padding-left: 10px; - padding-top: 2px; -} - -div.toc h3 { - font: bold 12px/1.2 Arial,FreeSans,sans-serif; - color: #4665A2; - border-bottom: 0 none; - margin: 0; -} - -div.toc ul { - list-style: none outside none; - border: medium none; - padding: 0px; -} - -div.toc li.level1 { - margin-left: 0px; -} - -div.toc li.level2 { - margin-left: 15px; -} - -div.toc li.level3 { - margin-left: 30px; -} - -div.toc li.level4 { - margin-left: 45px; -} - -.inherit_header { - font-weight: bold; - color: gray; - cursor: pointer; - -webkit-touch-callout: none; - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; -} - -.inherit_header td { - padding: 6px 0px 2px 5px; -} - -.inherit { - display: none; -} - -tr.heading h2 { - margin-top: 12px; - margin-bottom: 4px; -} - -/* tooltip related style info */ - -.ttc { - position: absolute; - display: none; -} - -#powerTip { - cursor: default; - white-space: nowrap; - background-color: white; - border: 1px solid gray; - border-radius: 4px 4px 4px 4px; - box-shadow: 1px 1px 7px gray; - display: none; - font-size: smaller; - max-width: 80%; - opacity: 0.9; - padding: 1ex 1em 1em; - position: absolute; - z-index: 2147483647; -} - -#powerTip div.ttdoc { - color: grey; - font-style: italic; -} - -#powerTip div.ttname a { - font-weight: bold; -} - -#powerTip div.ttname { - font-weight: bold; -} - -#powerTip div.ttdeci { - color: #006318; -} - -#powerTip div { - margin: 0px; - padding: 0px; - font: 12px/16px Roboto,sans-serif; -} - -#powerTip:before, #powerTip:after { - content: ""; - position: absolute; - margin: 0px; -} - -#powerTip.n:after, #powerTip.n:before, -#powerTip.s:after, #powerTip.s:before, -#powerTip.w:after, #powerTip.w:before, -#powerTip.e:after, #powerTip.e:before, -#powerTip.ne:after, #powerTip.ne:before, -#powerTip.se:after, #powerTip.se:before, -#powerTip.nw:after, #powerTip.nw:before, -#powerTip.sw:after, #powerTip.sw:before { - border: solid transparent; - content: " "; - height: 0; - width: 0; - position: absolute; -} - -#powerTip.n:after, #powerTip.s:after, -#powerTip.w:after, #powerTip.e:after, -#powerTip.nw:after, #powerTip.ne:after, -#powerTip.sw:after, #powerTip.se:after { - border-color: rgba(255, 255, 255, 0); -} - -#powerTip.n:before, #powerTip.s:before, -#powerTip.w:before, #powerTip.e:before, -#powerTip.nw:before, #powerTip.ne:before, -#powerTip.sw:before, #powerTip.se:before { - border-color: rgba(128, 128, 128, 0); -} - -#powerTip.n:after, #powerTip.n:before, -#powerTip.ne:after, #powerTip.ne:before, -#powerTip.nw:after, #powerTip.nw:before { - top: 100%; -} - -#powerTip.n:after, #powerTip.ne:after, #powerTip.nw:after { - border-top-color: #ffffff; - border-width: 10px; - margin: 0px -10px; -} -#powerTip.n:before { - border-top-color: #808080; - border-width: 11px; - margin: 0px -11px; -} -#powerTip.n:after, #powerTip.n:before { - left: 50%; -} - -#powerTip.nw:after, #powerTip.nw:before { - right: 14px; -} - -#powerTip.ne:after, #powerTip.ne:before { - left: 14px; -} - -#powerTip.s:after, #powerTip.s:before, -#powerTip.se:after, #powerTip.se:before, -#powerTip.sw:after, #powerTip.sw:before { - bottom: 100%; -} - -#powerTip.s:after, #powerTip.se:after, #powerTip.sw:after { - border-bottom-color: #ffffff; - border-width: 10px; - margin: 0px -10px; -} - -#powerTip.s:before, #powerTip.se:before, #powerTip.sw:before { - border-bottom-color: #808080; - border-width: 11px; - margin: 0px -11px; -} - -#powerTip.s:after, #powerTip.s:before { - left: 50%; -} - -#powerTip.sw:after, #powerTip.sw:before { - right: 14px; -} - -#powerTip.se:after, #powerTip.se:before { - left: 14px; -} - -#powerTip.e:after, #powerTip.e:before { - left: 100%; -} -#powerTip.e:after { - border-left-color: #ffffff; - border-width: 10px; - top: 50%; - margin-top: -10px; -} -#powerTip.e:before { - border-left-color: #808080; - border-width: 11px; - top: 50%; - margin-top: -11px; -} - -#powerTip.w:after, #powerTip.w:before { - right: 100%; -} -#powerTip.w:after { - border-right-color: #ffffff; - border-width: 10px; - top: 50%; - margin-top: -10px; -} -#powerTip.w:before { - border-right-color: #808080; - border-width: 11px; - top: 50%; - margin-top: -11px; -} - -@media print -{ - #top { display: none; } - #side-nav { display: none; } - #nav-path { display: none; } - body { overflow:visible; } - h1, h2, h3, h4, h5, h6 { page-break-after: avoid; } - .summary { display: none; } - .memitem { page-break-inside: avoid; } - #doc-content - { - margin-left:0 !important; - height:auto !important; - width:auto !important; - overflow:inherit; - display:inline; - } -} - -/* @group Markdown */ - -/* -table.markdownTable { - border-collapse:collapse; - margin-top: 4px; - margin-bottom: 4px; -} - -table.markdownTable td, table.markdownTable th { - border: 1px solid #2D4068; - padding: 3px 7px 2px; -} - -table.markdownTableHead tr { -} - -table.markdownTableBodyLeft td, table.markdownTable th { - border: 1px solid #2D4068; - padding: 3px 7px 2px; -} - -th.markdownTableHeadLeft th.markdownTableHeadRight th.markdownTableHeadCenter th.markdownTableHeadNone { - background-color: #374F7F; - color: #FFFFFF; - font-size: 110%; - padding-bottom: 4px; - padding-top: 5px; -} - -th.markdownTableHeadLeft { - text-align: left -} - -th.markdownTableHeadRight { - text-align: right -} - -th.markdownTableHeadCenter { - text-align: center -} -*/ - -table.markdownTable { - border-collapse:collapse; - margin-top: 4px; - margin-bottom: 4px; -} - -table.markdownTable td, table.markdownTable th { - border: 1px solid #2D4068; - padding: 3px 7px 2px; -} - -table.markdownTable tr { -} - -th.markdownTableHeadLeft, th.markdownTableHeadRight, th.markdownTableHeadCenter, th.markdownTableHeadNone { - background-color: #374F7F; - color: #FFFFFF; - font-size: 110%; - padding-bottom: 4px; - padding-top: 5px; -} - -th.markdownTableHeadLeft, td.markdownTableBodyLeft { - text-align: left -} - -th.markdownTableHeadRight, td.markdownTableBodyRight { - text-align: right -} - -th.markdownTableHeadCenter, td.markdownTableBodyCenter { - text-align: center -} - - -/* @end */ diff --git a/Doku/Doxygen/html/doxygen.png b/Doku/Doxygen/html/doxygen.png deleted file mode 100644 index 3ff17d8..0000000 Binary files a/Doku/Doxygen/html/doxygen.png and /dev/null differ diff --git a/Doku/Doxygen/html/dynsections.js b/Doku/Doxygen/html/dynsections.js deleted file mode 100644 index 1e6bf07..0000000 --- a/Doku/Doxygen/html/dynsections.js +++ /dev/null @@ -1,104 +0,0 @@ -function toggleVisibility(linkObj) -{ - var base = $(linkObj).attr('id'); - var summary = $('#'+base+'-summary'); - var content = $('#'+base+'-content'); - var trigger = $('#'+base+'-trigger'); - var src=$(trigger).attr('src'); - if (content.is(':visible')===true) { - content.hide(); - summary.show(); - $(linkObj).addClass('closed').removeClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); - } else { - content.show(); - summary.hide(); - $(linkObj).removeClass('closed').addClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); - } - return false; -} - -function updateStripes() -{ - $('table.directory tr'). - removeClass('even').filter(':visible:even').addClass('even'); -} - -function toggleLevel(level) -{ - $('table.directory tr').each(function() { - var l = this.id.split('_').length-1; - var i = $('#img'+this.id.substring(3)); - var a = $('#arr'+this.id.substring(3)); - if (l - - - - - - -Arduino {code}racer API: Graph Legend - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
-
-
Graph Legend
-
-
-

This page explains how to interpret the graphs that are generated by doxygen.

-

Consider the following example:

/*! Invisible class because of truncation */
class Invisible { };
/*! Truncated class, inheritance relation is hidden */
class Truncated : public Invisible { };
/* Class not documented with doxygen comments */
class Undocumented { };
/*! Class that is inherited using public inheritance */
class PublicBase : public Truncated { };
/*! A template class */
template<class T> class Templ { };
/*! Class that is inherited using protected inheritance */
class ProtectedBase { };
/*! Class that is inherited using private inheritance */
class PrivateBase { };
/*! Class that is used by the Inherited class */
class Used { };
/*! Super class that inherits a number of other classes */
class Inherited : public PublicBase,
protected ProtectedBase,
private PrivateBase,
public Undocumented,
public Templ<int>
{
private:
Used *m_usedClass;
};

This will result in the following graph:

-
- -
-

The boxes in the above graph have the following meaning:

-
    -
  • -A filled gray box represents the struct or class for which the graph is generated.
  • -
  • -A box with a black border denotes a documented struct or class.
  • -
  • -A box with a gray border denotes an undocumented struct or class.
  • -
  • -A box with a red border denotes a documented struct or class forwhich not all inheritance/containment relations are shown. A graph is truncated if it does not fit within the specified boundaries.
  • -
-

The arrows have the following meaning:

-
    -
  • -A dark blue arrow is used to visualize a public inheritance relation between two classes.
  • -
  • -A dark green arrow is used for protected inheritance.
  • -
  • -A dark red arrow is used for private inheritance.
  • -
  • -A purple dashed arrow is used if a class is contained or used by another class. The arrow is labelled with the variable(s) through which the pointed class or struct is accessible.
  • -
  • -A yellow dashed arrow denotes a relation between a template instance and the template class it was instantiated from. The arrow is labelled with the template parameters of the instance.
  • -
-
-
- - - - diff --git a/Doku/Doxygen/html/graph_legend.md5 b/Doku/Doxygen/html/graph_legend.md5 deleted file mode 100644 index a06ed05..0000000 --- a/Doku/Doxygen/html/graph_legend.md5 +++ /dev/null @@ -1 +0,0 @@ -387ff8eb65306fa251338d3c9bd7bfff \ No newline at end of file diff --git a/Doku/Doxygen/html/graph_legend.png b/Doku/Doxygen/html/graph_legend.png deleted file mode 100644 index e303709..0000000 Binary files a/Doku/Doxygen/html/graph_legend.png and /dev/null differ diff --git a/Doku/Doxygen/html/index.html b/Doku/Doxygen/html/index.html deleted file mode 100644 index 1cf52a4..0000000 --- a/Doku/Doxygen/html/index.html +++ /dev/null @@ -1,99 +0,0 @@ - - - - - - - -Arduino {code}racer API: Main Page - - - - - - - - - - - - - - -
-
- - - - - - - -
-
Arduino {code}racer API -
-
... better know the details.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
- -
- -
-
-
Arduino {code}racer API Documentation
-
-
-
-
- - - - diff --git a/Doku/Doxygen/html/jquery.js b/Doku/Doxygen/html/jquery.js deleted file mode 100644 index f5343ed..0000000 --- a/Doku/Doxygen/html/jquery.js +++ /dev/null @@ -1,87 +0,0 @@ -/*! - * jQuery JavaScript Library v1.7.1 - * http://jquery.com/ - * - * Copyright 2011, John Resig - * Dual licensed under the MIT or GPL Version 2 licenses. - * http://jquery.org/license - * - * Includes Sizzle.js - * http://sizzlejs.com/ - * Copyright 2011, The Dojo Foundation - * Released under the MIT, BSD, and GPL Licenses. - * - * Date: Mon Nov 21 21:11:03 2011 -0500 - */ -(function(bb,L){var av=bb.document,bu=bb.navigator,bl=bb.location;var b=(function(){var bF=function(b0,b1){return new bF.fn.init(b0,b1,bD)},bU=bb.jQuery,bH=bb.$,bD,bY=/^(?:[^#<]*(<[\w\W]+>)[^>]*$|#([\w\-]*)$)/,bM=/\S/,bI=/^\s+/,bE=/\s+$/,bA=/^<(\w+)\s*\/?>(?:<\/\1>)?$/,bN=/^[\],:{}\s]*$/,bW=/\\(?:["\\\/bfnrt]|u[0-9a-fA-F]{4})/g,bP=/"[^"\\\n\r]*"|true|false|null|-?\d+(?:\.\d*)?(?:[eE][+\-]?\d+)?/g,bJ=/(?:^|:|,)(?:\s*\[)+/g,by=/(webkit)[ \/]([\w.]+)/,bR=/(opera)(?:.*version)?[ \/]([\w.]+)/,bQ=/(msie) ([\w.]+)/,bS=/(mozilla)(?:.*? rv:([\w.]+))?/,bB=/-([a-z]|[0-9])/ig,bZ=/^-ms-/,bT=function(b0,b1){return(b1+"").toUpperCase()},bX=bu.userAgent,bV,bC,e,bL=Object.prototype.toString,bG=Object.prototype.hasOwnProperty,bz=Array.prototype.push,bK=Array.prototype.slice,bO=String.prototype.trim,bv=Array.prototype.indexOf,bx={};bF.fn=bF.prototype={constructor:bF,init:function(b0,b4,b3){var b2,b5,b1,b6;if(!b0){return this}if(b0.nodeType){this.context=this[0]=b0;this.length=1;return this}if(b0==="body"&&!b4&&av.body){this.context=av;this[0]=av.body;this.selector=b0;this.length=1;return this}if(typeof b0==="string"){if(b0.charAt(0)==="<"&&b0.charAt(b0.length-1)===">"&&b0.length>=3){b2=[null,b0,null]}else{b2=bY.exec(b0)}if(b2&&(b2[1]||!b4)){if(b2[1]){b4=b4 instanceof bF?b4[0]:b4;b6=(b4?b4.ownerDocument||b4:av);b1=bA.exec(b0);if(b1){if(bF.isPlainObject(b4)){b0=[av.createElement(b1[1])];bF.fn.attr.call(b0,b4,true)}else{b0=[b6.createElement(b1[1])]}}else{b1=bF.buildFragment([b2[1]],[b6]);b0=(b1.cacheable?bF.clone(b1.fragment):b1.fragment).childNodes}return bF.merge(this,b0)}else{b5=av.getElementById(b2[2]);if(b5&&b5.parentNode){if(b5.id!==b2[2]){return b3.find(b0)}this.length=1;this[0]=b5}this.context=av;this.selector=b0;return this}}else{if(!b4||b4.jquery){return(b4||b3).find(b0)}else{return this.constructor(b4).find(b0)}}}else{if(bF.isFunction(b0)){return b3.ready(b0)}}if(b0.selector!==L){this.selector=b0.selector;this.context=b0.context}return bF.makeArray(b0,this)},selector:"",jquery:"1.7.1",length:0,size:function(){return this.length},toArray:function(){return bK.call(this,0)},get:function(b0){return b0==null?this.toArray():(b0<0?this[this.length+b0]:this[b0])},pushStack:function(b1,b3,b0){var b2=this.constructor();if(bF.isArray(b1)){bz.apply(b2,b1)}else{bF.merge(b2,b1)}b2.prevObject=this;b2.context=this.context;if(b3==="find"){b2.selector=this.selector+(this.selector?" ":"")+b0}else{if(b3){b2.selector=this.selector+"."+b3+"("+b0+")"}}return b2},each:function(b1,b0){return bF.each(this,b1,b0)},ready:function(b0){bF.bindReady();bC.add(b0);return this},eq:function(b0){b0=+b0;return b0===-1?this.slice(b0):this.slice(b0,b0+1)},first:function(){return this.eq(0)},last:function(){return this.eq(-1)},slice:function(){return this.pushStack(bK.apply(this,arguments),"slice",bK.call(arguments).join(","))},map:function(b0){return this.pushStack(bF.map(this,function(b2,b1){return b0.call(b2,b1,b2)}))},end:function(){return this.prevObject||this.constructor(null)},push:bz,sort:[].sort,splice:[].splice};bF.fn.init.prototype=bF.fn;bF.extend=bF.fn.extend=function(){var b9,b2,b0,b1,b6,b7,b5=arguments[0]||{},b4=1,b3=arguments.length,b8=false;if(typeof b5==="boolean"){b8=b5;b5=arguments[1]||{};b4=2}if(typeof b5!=="object"&&!bF.isFunction(b5)){b5={}}if(b3===b4){b5=this;--b4}for(;b40){return}bC.fireWith(av,[bF]);if(bF.fn.trigger){bF(av).trigger("ready").off("ready")}}},bindReady:function(){if(bC){return}bC=bF.Callbacks("once memory");if(av.readyState==="complete"){return setTimeout(bF.ready,1)}if(av.addEventListener){av.addEventListener("DOMContentLoaded",e,false);bb.addEventListener("load",bF.ready,false)}else{if(av.attachEvent){av.attachEvent("onreadystatechange",e);bb.attachEvent("onload",bF.ready);var b0=false;try{b0=bb.frameElement==null}catch(b1){}if(av.documentElement.doScroll&&b0){bw()}}}},isFunction:function(b0){return bF.type(b0)==="function"},isArray:Array.isArray||function(b0){return bF.type(b0)==="array"},isWindow:function(b0){return b0&&typeof b0==="object"&&"setInterval" in b0},isNumeric:function(b0){return !isNaN(parseFloat(b0))&&isFinite(b0)},type:function(b0){return b0==null?String(b0):bx[bL.call(b0)]||"object"},isPlainObject:function(b2){if(!b2||bF.type(b2)!=="object"||b2.nodeType||bF.isWindow(b2)){return false}try{if(b2.constructor&&!bG.call(b2,"constructor")&&!bG.call(b2.constructor.prototype,"isPrototypeOf")){return false}}catch(b1){return false}var b0;for(b0 in b2){}return b0===L||bG.call(b2,b0)},isEmptyObject:function(b1){for(var b0 in b1){return false}return true},error:function(b0){throw new Error(b0)},parseJSON:function(b0){if(typeof b0!=="string"||!b0){return null}b0=bF.trim(b0);if(bb.JSON&&bb.JSON.parse){return bb.JSON.parse(b0)}if(bN.test(b0.replace(bW,"@").replace(bP,"]").replace(bJ,""))){return(new Function("return "+b0))()}bF.error("Invalid JSON: "+b0)},parseXML:function(b2){var b0,b1;try{if(bb.DOMParser){b1=new DOMParser();b0=b1.parseFromString(b2,"text/xml")}else{b0=new ActiveXObject("Microsoft.XMLDOM");b0.async="false";b0.loadXML(b2)}}catch(b3){b0=L}if(!b0||!b0.documentElement||b0.getElementsByTagName("parsererror").length){bF.error("Invalid XML: "+b2)}return b0},noop:function(){},globalEval:function(b0){if(b0&&bM.test(b0)){(bb.execScript||function(b1){bb["eval"].call(bb,b1)})(b0)}},camelCase:function(b0){return b0.replace(bZ,"ms-").replace(bB,bT)},nodeName:function(b1,b0){return b1.nodeName&&b1.nodeName.toUpperCase()===b0.toUpperCase()},each:function(b3,b6,b2){var b1,b4=0,b5=b3.length,b0=b5===L||bF.isFunction(b3);if(b2){if(b0){for(b1 in b3){if(b6.apply(b3[b1],b2)===false){break}}}else{for(;b40&&b0[0]&&b0[b1-1])||b1===0||bF.isArray(b0));if(b3){for(;b21?aJ.call(arguments,0):bG;if(!(--bw)){bC.resolveWith(bC,bx)}}}function bz(bF){return function(bG){bB[bF]=arguments.length>1?aJ.call(arguments,0):bG;bC.notifyWith(bE,bB)}}if(e>1){for(;bv
a";bI=bv.getElementsByTagName("*");bF=bv.getElementsByTagName("a")[0];if(!bI||!bI.length||!bF){return{}}bG=av.createElement("select");bx=bG.appendChild(av.createElement("option"));bE=bv.getElementsByTagName("input")[0];bJ={leadingWhitespace:(bv.firstChild.nodeType===3),tbody:!bv.getElementsByTagName("tbody").length,htmlSerialize:!!bv.getElementsByTagName("link").length,style:/top/.test(bF.getAttribute("style")),hrefNormalized:(bF.getAttribute("href")==="/a"),opacity:/^0.55/.test(bF.style.opacity),cssFloat:!!bF.style.cssFloat,checkOn:(bE.value==="on"),optSelected:bx.selected,getSetAttribute:bv.className!=="t",enctype:!!av.createElement("form").enctype,html5Clone:av.createElement("nav").cloneNode(true).outerHTML!=="<:nav>",submitBubbles:true,changeBubbles:true,focusinBubbles:false,deleteExpando:true,noCloneEvent:true,inlineBlockNeedsLayout:false,shrinkWrapBlocks:false,reliableMarginRight:true};bE.checked=true;bJ.noCloneChecked=bE.cloneNode(true).checked;bG.disabled=true;bJ.optDisabled=!bx.disabled;try{delete bv.test}catch(bC){bJ.deleteExpando=false}if(!bv.addEventListener&&bv.attachEvent&&bv.fireEvent){bv.attachEvent("onclick",function(){bJ.noCloneEvent=false});bv.cloneNode(true).fireEvent("onclick")}bE=av.createElement("input");bE.value="t";bE.setAttribute("type","radio");bJ.radioValue=bE.value==="t";bE.setAttribute("checked","checked");bv.appendChild(bE);bD=av.createDocumentFragment();bD.appendChild(bv.lastChild);bJ.checkClone=bD.cloneNode(true).cloneNode(true).lastChild.checked;bJ.appendChecked=bE.checked;bD.removeChild(bE);bD.appendChild(bv);bv.innerHTML="";if(bb.getComputedStyle){bA=av.createElement("div");bA.style.width="0";bA.style.marginRight="0";bv.style.width="2px";bv.appendChild(bA);bJ.reliableMarginRight=(parseInt((bb.getComputedStyle(bA,null)||{marginRight:0}).marginRight,10)||0)===0}if(bv.attachEvent){for(by in {submit:1,change:1,focusin:1}){bB="on"+by;bw=(bB in bv);if(!bw){bv.setAttribute(bB,"return;");bw=(typeof bv[bB]==="function")}bJ[by+"Bubbles"]=bw}}bD.removeChild(bv);bD=bG=bx=bA=bv=bE=null;b(function(){var bM,bU,bV,bT,bN,bO,bL,bS,bR,e,bP,bQ=av.getElementsByTagName("body")[0];if(!bQ){return}bL=1;bS="position:absolute;top:0;left:0;width:1px;height:1px;margin:0;";bR="visibility:hidden;border:0;";e="style='"+bS+"border:5px solid #000;padding:0;'";bP="
";bM=av.createElement("div");bM.style.cssText=bR+"width:0;height:0;position:static;top:0;margin-top:"+bL+"px";bQ.insertBefore(bM,bQ.firstChild);bv=av.createElement("div");bM.appendChild(bv);bv.innerHTML="
t
";bz=bv.getElementsByTagName("td");bw=(bz[0].offsetHeight===0);bz[0].style.display="";bz[1].style.display="none";bJ.reliableHiddenOffsets=bw&&(bz[0].offsetHeight===0);bv.innerHTML="";bv.style.width=bv.style.paddingLeft="1px";b.boxModel=bJ.boxModel=bv.offsetWidth===2;if(typeof bv.style.zoom!=="undefined"){bv.style.display="inline";bv.style.zoom=1;bJ.inlineBlockNeedsLayout=(bv.offsetWidth===2);bv.style.display="";bv.innerHTML="
";bJ.shrinkWrapBlocks=(bv.offsetWidth!==2)}bv.style.cssText=bS+bR;bv.innerHTML=bP;bU=bv.firstChild;bV=bU.firstChild;bN=bU.nextSibling.firstChild.firstChild;bO={doesNotAddBorder:(bV.offsetTop!==5),doesAddBorderForTableAndCells:(bN.offsetTop===5)};bV.style.position="fixed";bV.style.top="20px";bO.fixedPosition=(bV.offsetTop===20||bV.offsetTop===15);bV.style.position=bV.style.top="";bU.style.overflow="hidden";bU.style.position="relative";bO.subtractsBorderForOverflowNotVisible=(bV.offsetTop===-5);bO.doesNotIncludeMarginInBodyOffset=(bQ.offsetTop!==bL);bQ.removeChild(bM);bv=bM=null;b.extend(bJ,bO)});return bJ})();var aS=/^(?:\{.*\}|\[.*\])$/,aA=/([A-Z])/g;b.extend({cache:{},uuid:0,expando:"jQuery"+(b.fn.jquery+Math.random()).replace(/\D/g,""),noData:{embed:true,object:"clsid:D27CDB6E-AE6D-11cf-96B8-444553540000",applet:true},hasData:function(e){e=e.nodeType?b.cache[e[b.expando]]:e[b.expando];return !!e&&!S(e)},data:function(bx,bv,bz,by){if(!b.acceptData(bx)){return}var bG,bA,bD,bE=b.expando,bC=typeof bv==="string",bF=bx.nodeType,e=bF?b.cache:bx,bw=bF?bx[bE]:bx[bE]&&bE,bB=bv==="events";if((!bw||!e[bw]||(!bB&&!by&&!e[bw].data))&&bC&&bz===L){return}if(!bw){if(bF){bx[bE]=bw=++b.uuid}else{bw=bE}}if(!e[bw]){e[bw]={};if(!bF){e[bw].toJSON=b.noop}}if(typeof bv==="object"||typeof bv==="function"){if(by){e[bw]=b.extend(e[bw],bv)}else{e[bw].data=b.extend(e[bw].data,bv)}}bG=bA=e[bw];if(!by){if(!bA.data){bA.data={}}bA=bA.data}if(bz!==L){bA[b.camelCase(bv)]=bz}if(bB&&!bA[bv]){return bG.events}if(bC){bD=bA[bv];if(bD==null){bD=bA[b.camelCase(bv)]}}else{bD=bA}return bD},removeData:function(bx,bv,by){if(!b.acceptData(bx)){return}var bB,bA,bz,bC=b.expando,bD=bx.nodeType,e=bD?b.cache:bx,bw=bD?bx[bC]:bC;if(!e[bw]){return}if(bv){bB=by?e[bw]:e[bw].data;if(bB){if(!b.isArray(bv)){if(bv in bB){bv=[bv]}else{bv=b.camelCase(bv);if(bv in bB){bv=[bv]}else{bv=bv.split(" ")}}}for(bA=0,bz=bv.length;bA-1){return true}}return false},val:function(bx){var e,bv,by,bw=this[0];if(!arguments.length){if(bw){e=b.valHooks[bw.nodeName.toLowerCase()]||b.valHooks[bw.type];if(e&&"get" in e&&(bv=e.get(bw,"value"))!==L){return bv}bv=bw.value;return typeof bv==="string"?bv.replace(aU,""):bv==null?"":bv}return}by=b.isFunction(bx);return this.each(function(bA){var bz=b(this),bB;if(this.nodeType!==1){return}if(by){bB=bx.call(this,bA,bz.val())}else{bB=bx}if(bB==null){bB=""}else{if(typeof bB==="number"){bB+=""}else{if(b.isArray(bB)){bB=b.map(bB,function(bC){return bC==null?"":bC+""})}}}e=b.valHooks[this.nodeName.toLowerCase()]||b.valHooks[this.type];if(!e||!("set" in e)||e.set(this,bB,"value")===L){this.value=bB}})}});b.extend({valHooks:{option:{get:function(e){var bv=e.attributes.value;return !bv||bv.specified?e.value:e.text}},select:{get:function(e){var bA,bv,bz,bx,by=e.selectedIndex,bB=[],bC=e.options,bw=e.type==="select-one";if(by<0){return null}bv=bw?by:0;bz=bw?by+1:bC.length;for(;bv=0});if(!e.length){bv.selectedIndex=-1}return e}}},attrFn:{val:true,css:true,html:true,text:true,data:true,width:true,height:true,offset:true},attr:function(bA,bx,bB,bz){var bw,e,by,bv=bA.nodeType;if(!bA||bv===3||bv===8||bv===2){return}if(bz&&bx in b.attrFn){return b(bA)[bx](bB)}if(typeof bA.getAttribute==="undefined"){return b.prop(bA,bx,bB)}by=bv!==1||!b.isXMLDoc(bA);if(by){bx=bx.toLowerCase();e=b.attrHooks[bx]||(ao.test(bx)?aY:be)}if(bB!==L){if(bB===null){b.removeAttr(bA,bx);return}else{if(e&&"set" in e&&by&&(bw=e.set(bA,bB,bx))!==L){return bw}else{bA.setAttribute(bx,""+bB);return bB}}}else{if(e&&"get" in e&&by&&(bw=e.get(bA,bx))!==null){return bw}else{bw=bA.getAttribute(bx);return bw===null?L:bw}}},removeAttr:function(bx,bz){var by,bA,bv,e,bw=0;if(bz&&bx.nodeType===1){bA=bz.toLowerCase().split(af);e=bA.length;for(;bw=0)}}})});var bd=/^(?:textarea|input|select)$/i,n=/^([^\.]*)?(?:\.(.+))?$/,J=/\bhover(\.\S+)?\b/,aO=/^key/,bf=/^(?:mouse|contextmenu)|click/,T=/^(?:focusinfocus|focusoutblur)$/,U=/^(\w*)(?:#([\w\-]+))?(?:\.([\w\-]+))?$/,Y=function(e){var bv=U.exec(e);if(bv){bv[1]=(bv[1]||"").toLowerCase();bv[3]=bv[3]&&new RegExp("(?:^|\\s)"+bv[3]+"(?:\\s|$)")}return bv},j=function(bw,e){var bv=bw.attributes||{};return((!e[1]||bw.nodeName.toLowerCase()===e[1])&&(!e[2]||(bv.id||{}).value===e[2])&&(!e[3]||e[3].test((bv["class"]||{}).value)))},bt=function(e){return b.event.special.hover?e:e.replace(J,"mouseenter$1 mouseleave$1")};b.event={add:function(bx,bC,bJ,bA,by){var bD,bB,bK,bI,bH,bF,e,bG,bv,bz,bw,bE;if(bx.nodeType===3||bx.nodeType===8||!bC||!bJ||!(bD=b._data(bx))){return}if(bJ.handler){bv=bJ;bJ=bv.handler}if(!bJ.guid){bJ.guid=b.guid++}bK=bD.events;if(!bK){bD.events=bK={}}bB=bD.handle;if(!bB){bD.handle=bB=function(bL){return typeof b!=="undefined"&&(!bL||b.event.triggered!==bL.type)?b.event.dispatch.apply(bB.elem,arguments):L};bB.elem=bx}bC=b.trim(bt(bC)).split(" ");for(bI=0;bI=0){bG=bG.slice(0,-1);bw=true}if(bG.indexOf(".")>=0){bx=bG.split(".");bG=bx.shift();bx.sort()}if((!bA||b.event.customEvent[bG])&&!b.event.global[bG]){return}bv=typeof bv==="object"?bv[b.expando]?bv:new b.Event(bG,bv):new b.Event(bG);bv.type=bG;bv.isTrigger=true;bv.exclusive=bw;bv.namespace=bx.join(".");bv.namespace_re=bv.namespace?new RegExp("(^|\\.)"+bx.join("\\.(?:.*\\.)?")+"(\\.|$)"):null;by=bG.indexOf(":")<0?"on"+bG:"";if(!bA){e=b.cache;for(bC in e){if(e[bC].events&&e[bC].events[bG]){b.event.trigger(bv,bD,e[bC].handle.elem,true)}}return}bv.result=L;if(!bv.target){bv.target=bA}bD=bD!=null?b.makeArray(bD):[];bD.unshift(bv);bF=b.event.special[bG]||{};if(bF.trigger&&bF.trigger.apply(bA,bD)===false){return}bB=[[bA,bF.bindType||bG]];if(!bJ&&!bF.noBubble&&!b.isWindow(bA)){bI=bF.delegateType||bG;bH=T.test(bI+bG)?bA:bA.parentNode;bz=null;for(;bH;bH=bH.parentNode){bB.push([bH,bI]);bz=bH}if(bz&&bz===bA.ownerDocument){bB.push([bz.defaultView||bz.parentWindow||bb,bI])}}for(bC=0;bCbA){bH.push({elem:this,matches:bz.slice(bA)})}for(bC=0;bC0?this.on(e,null,bx,bw):this.trigger(e)};if(b.attrFn){b.attrFn[e]=true}if(aO.test(e)){b.event.fixHooks[e]=b.event.keyHooks}if(bf.test(e)){b.event.fixHooks[e]=b.event.mouseHooks}}); -/*! - * Sizzle CSS Selector Engine - * Copyright 2011, The Dojo Foundation - * Released under the MIT, BSD, and GPL Licenses. - * More information: http://sizzlejs.com/ - */ -(function(){var bH=/((?:\((?:\([^()]+\)|[^()]+)+\)|\[(?:\[[^\[\]]*\]|['"][^'"]*['"]|[^\[\]'"]+)+\]|\\.|[^ >+~,(\[\\]+)+|[>+~])(\s*,\s*)?((?:.|\r|\n)*)/g,bC="sizcache"+(Math.random()+"").replace(".",""),bI=0,bL=Object.prototype.toString,bB=false,bA=true,bK=/\\/g,bO=/\r\n/g,bQ=/\W/;[0,0].sort(function(){bA=false;return 0});var by=function(bV,e,bY,bZ){bY=bY||[];e=e||av;var b1=e;if(e.nodeType!==1&&e.nodeType!==9){return[]}if(!bV||typeof bV!=="string"){return bY}var bS,b3,b6,bR,b2,b5,b4,bX,bU=true,bT=by.isXML(e),bW=[],b0=bV;do{bH.exec("");bS=bH.exec(b0);if(bS){b0=bS[3];bW.push(bS[1]);if(bS[2]){bR=bS[3];break}}}while(bS);if(bW.length>1&&bD.exec(bV)){if(bW.length===2&&bE.relative[bW[0]]){b3=bM(bW[0]+bW[1],e,bZ)}else{b3=bE.relative[bW[0]]?[e]:by(bW.shift(),e);while(bW.length){bV=bW.shift();if(bE.relative[bV]){bV+=bW.shift()}b3=bM(bV,b3,bZ)}}}else{if(!bZ&&bW.length>1&&e.nodeType===9&&!bT&&bE.match.ID.test(bW[0])&&!bE.match.ID.test(bW[bW.length-1])){b2=by.find(bW.shift(),e,bT);e=b2.expr?by.filter(b2.expr,b2.set)[0]:b2.set[0]}if(e){b2=bZ?{expr:bW.pop(),set:bF(bZ)}:by.find(bW.pop(),bW.length===1&&(bW[0]==="~"||bW[0]==="+")&&e.parentNode?e.parentNode:e,bT);b3=b2.expr?by.filter(b2.expr,b2.set):b2.set;if(bW.length>0){b6=bF(b3)}else{bU=false}while(bW.length){b5=bW.pop();b4=b5;if(!bE.relative[b5]){b5=""}else{b4=bW.pop()}if(b4==null){b4=e}bE.relative[b5](b6,b4,bT)}}else{b6=bW=[]}}if(!b6){b6=b3}if(!b6){by.error(b5||bV)}if(bL.call(b6)==="[object Array]"){if(!bU){bY.push.apply(bY,b6)}else{if(e&&e.nodeType===1){for(bX=0;b6[bX]!=null;bX++){if(b6[bX]&&(b6[bX]===true||b6[bX].nodeType===1&&by.contains(e,b6[bX]))){bY.push(b3[bX])}}}else{for(bX=0;b6[bX]!=null;bX++){if(b6[bX]&&b6[bX].nodeType===1){bY.push(b3[bX])}}}}}else{bF(b6,bY)}if(bR){by(bR,b1,bY,bZ);by.uniqueSort(bY)}return bY};by.uniqueSort=function(bR){if(bJ){bB=bA;bR.sort(bJ);if(bB){for(var e=1;e0};by.find=function(bX,e,bY){var bW,bS,bU,bT,bV,bR;if(!bX){return[]}for(bS=0,bU=bE.order.length;bS":function(bW,bR){var bV,bU=typeof bR==="string",bS=0,e=bW.length;if(bU&&!bQ.test(bR)){bR=bR.toLowerCase();for(;bS=0)){if(!bS){e.push(bV)}}else{if(bS){bR[bU]=false}}}}return false},ID:function(e){return e[1].replace(bK,"")},TAG:function(bR,e){return bR[1].replace(bK,"").toLowerCase()},CHILD:function(e){if(e[1]==="nth"){if(!e[2]){by.error(e[0])}e[2]=e[2].replace(/^\+|\s*/g,"");var bR=/(-?)(\d*)(?:n([+\-]?\d*))?/.exec(e[2]==="even"&&"2n"||e[2]==="odd"&&"2n+1"||!/\D/.test(e[2])&&"0n+"+e[2]||e[2]);e[2]=(bR[1]+(bR[2]||1))-0;e[3]=bR[3]-0}else{if(e[2]){by.error(e[0])}}e[0]=bI++;return e},ATTR:function(bU,bR,bS,e,bV,bW){var bT=bU[1]=bU[1].replace(bK,"");if(!bW&&bE.attrMap[bT]){bU[1]=bE.attrMap[bT]}bU[4]=(bU[4]||bU[5]||"").replace(bK,"");if(bU[2]==="~="){bU[4]=" "+bU[4]+" "}return bU},PSEUDO:function(bU,bR,bS,e,bV){if(bU[1]==="not"){if((bH.exec(bU[3])||"").length>1||/^\w/.test(bU[3])){bU[3]=by(bU[3],null,null,bR)}else{var bT=by.filter(bU[3],bR,bS,true^bV);if(!bS){e.push.apply(e,bT)}return false}}else{if(bE.match.POS.test(bU[0])||bE.match.CHILD.test(bU[0])){return true}}return bU},POS:function(e){e.unshift(true);return e}},filters:{enabled:function(e){return e.disabled===false&&e.type!=="hidden"},disabled:function(e){return e.disabled===true},checked:function(e){return e.checked===true},selected:function(e){if(e.parentNode){e.parentNode.selectedIndex}return e.selected===true},parent:function(e){return !!e.firstChild},empty:function(e){return !e.firstChild},has:function(bS,bR,e){return !!by(e[3],bS).length},header:function(e){return(/h\d/i).test(e.nodeName)},text:function(bS){var e=bS.getAttribute("type"),bR=bS.type;return bS.nodeName.toLowerCase()==="input"&&"text"===bR&&(e===bR||e===null)},radio:function(e){return e.nodeName.toLowerCase()==="input"&&"radio"===e.type},checkbox:function(e){return e.nodeName.toLowerCase()==="input"&&"checkbox"===e.type},file:function(e){return e.nodeName.toLowerCase()==="input"&&"file"===e.type},password:function(e){return e.nodeName.toLowerCase()==="input"&&"password"===e.type},submit:function(bR){var e=bR.nodeName.toLowerCase();return(e==="input"||e==="button")&&"submit"===bR.type},image:function(e){return e.nodeName.toLowerCase()==="input"&&"image"===e.type},reset:function(bR){var e=bR.nodeName.toLowerCase();return(e==="input"||e==="button")&&"reset"===bR.type},button:function(bR){var e=bR.nodeName.toLowerCase();return e==="input"&&"button"===bR.type||e==="button"},input:function(e){return(/input|select|textarea|button/i).test(e.nodeName)},focus:function(e){return e===e.ownerDocument.activeElement}},setFilters:{first:function(bR,e){return e===0},last:function(bS,bR,e,bT){return bR===bT.length-1},even:function(bR,e){return e%2===0},odd:function(bR,e){return e%2===1},lt:function(bS,bR,e){return bRe[3]-0},nth:function(bS,bR,e){return e[3]-0===bR},eq:function(bS,bR,e){return e[3]-0===bR}},filter:{PSEUDO:function(bS,bX,bW,bY){var e=bX[1],bR=bE.filters[e];if(bR){return bR(bS,bW,bX,bY)}else{if(e==="contains"){return(bS.textContent||bS.innerText||bw([bS])||"").indexOf(bX[3])>=0}else{if(e==="not"){var bT=bX[3];for(var bV=0,bU=bT.length;bV=0)}}},ID:function(bR,e){return bR.nodeType===1&&bR.getAttribute("id")===e},TAG:function(bR,e){return(e==="*"&&bR.nodeType===1)||!!bR.nodeName&&bR.nodeName.toLowerCase()===e},CLASS:function(bR,e){return(" "+(bR.className||bR.getAttribute("class"))+" ").indexOf(e)>-1},ATTR:function(bV,bT){var bS=bT[1],e=by.attr?by.attr(bV,bS):bE.attrHandle[bS]?bE.attrHandle[bS](bV):bV[bS]!=null?bV[bS]:bV.getAttribute(bS),bW=e+"",bU=bT[2],bR=bT[4];return e==null?bU==="!=":!bU&&by.attr?e!=null:bU==="="?bW===bR:bU==="*="?bW.indexOf(bR)>=0:bU==="~="?(" "+bW+" ").indexOf(bR)>=0:!bR?bW&&e!==false:bU==="!="?bW!==bR:bU==="^="?bW.indexOf(bR)===0:bU==="$="?bW.substr(bW.length-bR.length)===bR:bU==="|="?bW===bR||bW.substr(0,bR.length+1)===bR+"-":false},POS:function(bU,bR,bS,bV){var e=bR[2],bT=bE.setFilters[e];if(bT){return bT(bU,bS,bR,bV)}}}};var bD=bE.match.POS,bx=function(bR,e){return"\\"+(e-0+1)};for(var bz in bE.match){bE.match[bz]=new RegExp(bE.match[bz].source+(/(?![^\[]*\])(?![^\(]*\))/.source));bE.leftMatch[bz]=new RegExp(/(^(?:.|\r|\n)*?)/.source+bE.match[bz].source.replace(/\\(\d+)/g,bx))}var bF=function(bR,e){bR=Array.prototype.slice.call(bR,0);if(e){e.push.apply(e,bR);return e}return bR};try{Array.prototype.slice.call(av.documentElement.childNodes,0)[0].nodeType}catch(bP){bF=function(bU,bT){var bS=0,bR=bT||[];if(bL.call(bU)==="[object Array]"){Array.prototype.push.apply(bR,bU)}else{if(typeof bU.length==="number"){for(var e=bU.length;bS";e.insertBefore(bR,e.firstChild);if(av.getElementById(bS)){bE.find.ID=function(bU,bV,bW){if(typeof bV.getElementById!=="undefined"&&!bW){var bT=bV.getElementById(bU[1]);return bT?bT.id===bU[1]||typeof bT.getAttributeNode!=="undefined"&&bT.getAttributeNode("id").nodeValue===bU[1]?[bT]:L:[]}};bE.filter.ID=function(bV,bT){var bU=typeof bV.getAttributeNode!=="undefined"&&bV.getAttributeNode("id");return bV.nodeType===1&&bU&&bU.nodeValue===bT}}e.removeChild(bR);e=bR=null})();(function(){var e=av.createElement("div");e.appendChild(av.createComment(""));if(e.getElementsByTagName("*").length>0){bE.find.TAG=function(bR,bV){var bU=bV.getElementsByTagName(bR[1]);if(bR[1]==="*"){var bT=[];for(var bS=0;bU[bS];bS++){if(bU[bS].nodeType===1){bT.push(bU[bS])}}bU=bT}return bU}}e.innerHTML="";if(e.firstChild&&typeof e.firstChild.getAttribute!=="undefined"&&e.firstChild.getAttribute("href")!=="#"){bE.attrHandle.href=function(bR){return bR.getAttribute("href",2)}}e=null})();if(av.querySelectorAll){(function(){var e=by,bT=av.createElement("div"),bS="__sizzle__";bT.innerHTML="

";if(bT.querySelectorAll&&bT.querySelectorAll(".TEST").length===0){return}by=function(b4,bV,bZ,b3){bV=bV||av;if(!b3&&!by.isXML(bV)){var b2=/^(\w+$)|^\.([\w\-]+$)|^#([\w\-]+$)/.exec(b4);if(b2&&(bV.nodeType===1||bV.nodeType===9)){if(b2[1]){return bF(bV.getElementsByTagName(b4),bZ)}else{if(b2[2]&&bE.find.CLASS&&bV.getElementsByClassName){return bF(bV.getElementsByClassName(b2[2]),bZ)}}}if(bV.nodeType===9){if(b4==="body"&&bV.body){return bF([bV.body],bZ)}else{if(b2&&b2[3]){var bY=bV.getElementById(b2[3]);if(bY&&bY.parentNode){if(bY.id===b2[3]){return bF([bY],bZ)}}else{return bF([],bZ)}}}try{return bF(bV.querySelectorAll(b4),bZ)}catch(b0){}}else{if(bV.nodeType===1&&bV.nodeName.toLowerCase()!=="object"){var bW=bV,bX=bV.getAttribute("id"),bU=bX||bS,b6=bV.parentNode,b5=/^\s*[+~]/.test(b4);if(!bX){bV.setAttribute("id",bU)}else{bU=bU.replace(/'/g,"\\$&")}if(b5&&b6){bV=bV.parentNode}try{if(!b5||b6){return bF(bV.querySelectorAll("[id='"+bU+"'] "+b4),bZ)}}catch(b1){}finally{if(!bX){bW.removeAttribute("id")}}}}}return e(b4,bV,bZ,b3)};for(var bR in e){by[bR]=e[bR]}bT=null})()}(function(){var e=av.documentElement,bS=e.matchesSelector||e.mozMatchesSelector||e.webkitMatchesSelector||e.msMatchesSelector;if(bS){var bU=!bS.call(av.createElement("div"),"div"),bR=false;try{bS.call(av.documentElement,"[test!='']:sizzle")}catch(bT){bR=true}by.matchesSelector=function(bW,bY){bY=bY.replace(/\=\s*([^'"\]]*)\s*\]/g,"='$1']");if(!by.isXML(bW)){try{if(bR||!bE.match.PSEUDO.test(bY)&&!/!=/.test(bY)){var bV=bS.call(bW,bY);if(bV||!bU||bW.document&&bW.document.nodeType!==11){return bV}}}catch(bX){}}return by(bY,null,null,[bW]).length>0}}})();(function(){var e=av.createElement("div");e.innerHTML="
";if(!e.getElementsByClassName||e.getElementsByClassName("e").length===0){return}e.lastChild.className="e";if(e.getElementsByClassName("e").length===1){return}bE.order.splice(1,0,"CLASS");bE.find.CLASS=function(bR,bS,bT){if(typeof bS.getElementsByClassName!=="undefined"&&!bT){return bS.getElementsByClassName(bR[1])}};e=null})();function bv(bR,bW,bV,bZ,bX,bY){for(var bT=0,bS=bZ.length;bT0){bU=e;break}}}e=e[bR]}bZ[bT]=bU}}}if(av.documentElement.contains){by.contains=function(bR,e){return bR!==e&&(bR.contains?bR.contains(e):true)}}else{if(av.documentElement.compareDocumentPosition){by.contains=function(bR,e){return !!(bR.compareDocumentPosition(e)&16)}}else{by.contains=function(){return false}}}by.isXML=function(e){var bR=(e?e.ownerDocument||e:0).documentElement;return bR?bR.nodeName!=="HTML":false};var bM=function(bS,e,bW){var bV,bX=[],bU="",bY=e.nodeType?[e]:e;while((bV=bE.match.PSEUDO.exec(bS))){bU+=bV[0];bS=bS.replace(bE.match.PSEUDO,"")}bS=bE.relative[bS]?bS+"*":bS;for(var bT=0,bR=bY.length;bT0){for(bB=bA;bB=0:b.filter(e,this).length>0:this.filter(e).length>0)},closest:function(by,bx){var bv=[],bw,e,bz=this[0];if(b.isArray(by)){var bB=1;while(bz&&bz.ownerDocument&&bz!==bx){for(bw=0;bw-1:b.find.matchesSelector(bz,by)){bv.push(bz);break}else{bz=bz.parentNode;if(!bz||!bz.ownerDocument||bz===bx||bz.nodeType===11){break}}}}bv=bv.length>1?b.unique(bv):bv;return this.pushStack(bv,"closest",by)},index:function(e){if(!e){return(this[0]&&this[0].parentNode)?this.prevAll().length:-1}if(typeof e==="string"){return b.inArray(this[0],b(e))}return b.inArray(e.jquery?e[0]:e,this)},add:function(e,bv){var bx=typeof e==="string"?b(e,bv):b.makeArray(e&&e.nodeType?[e]:e),bw=b.merge(this.get(),bx);return this.pushStack(C(bx[0])||C(bw[0])?bw:b.unique(bw))},andSelf:function(){return this.add(this.prevObject)}});function C(e){return !e||!e.parentNode||e.parentNode.nodeType===11}b.each({parent:function(bv){var e=bv.parentNode;return e&&e.nodeType!==11?e:null},parents:function(e){return b.dir(e,"parentNode")},parentsUntil:function(bv,e,bw){return b.dir(bv,"parentNode",bw)},next:function(e){return b.nth(e,2,"nextSibling")},prev:function(e){return b.nth(e,2,"previousSibling")},nextAll:function(e){return b.dir(e,"nextSibling")},prevAll:function(e){return b.dir(e,"previousSibling")},nextUntil:function(bv,e,bw){return b.dir(bv,"nextSibling",bw)},prevUntil:function(bv,e,bw){return b.dir(bv,"previousSibling",bw)},siblings:function(e){return b.sibling(e.parentNode.firstChild,e)},children:function(e){return b.sibling(e.firstChild)},contents:function(e){return b.nodeName(e,"iframe")?e.contentDocument||e.contentWindow.document:b.makeArray(e.childNodes)}},function(e,bv){b.fn[e]=function(by,bw){var bx=b.map(this,bv,by);if(!ab.test(e)){bw=by}if(bw&&typeof bw==="string"){bx=b.filter(bw,bx)}bx=this.length>1&&!ay[e]?b.unique(bx):bx;if((this.length>1||a9.test(bw))&&aq.test(e)){bx=bx.reverse()}return this.pushStack(bx,e,P.call(arguments).join(","))}});b.extend({filter:function(bw,e,bv){if(bv){bw=":not("+bw+")"}return e.length===1?b.find.matchesSelector(e[0],bw)?[e[0]]:[]:b.find.matches(bw,e)},dir:function(bw,bv,by){var e=[],bx=bw[bv];while(bx&&bx.nodeType!==9&&(by===L||bx.nodeType!==1||!b(bx).is(by))){if(bx.nodeType===1){e.push(bx)}bx=bx[bv]}return e},nth:function(by,e,bw,bx){e=e||1;var bv=0;for(;by;by=by[bw]){if(by.nodeType===1&&++bv===e){break}}return by},sibling:function(bw,bv){var e=[];for(;bw;bw=bw.nextSibling){if(bw.nodeType===1&&bw!==bv){e.push(bw)}}return e}});function aG(bx,bw,e){bw=bw||0;if(b.isFunction(bw)){return b.grep(bx,function(bz,by){var bA=!!bw.call(bz,by,bz);return bA===e})}else{if(bw.nodeType){return b.grep(bx,function(bz,by){return(bz===bw)===e})}else{if(typeof bw==="string"){var bv=b.grep(bx,function(by){return by.nodeType===1});if(bp.test(bw)){return b.filter(bw,bv,!e)}else{bw=b.filter(bw,bv)}}}}return b.grep(bx,function(bz,by){return(b.inArray(bz,bw)>=0)===e})}function a(e){var bw=aR.split("|"),bv=e.createDocumentFragment();if(bv.createElement){while(bw.length){bv.createElement(bw.pop())}}return bv}var aR="abbr|article|aside|audio|canvas|datalist|details|figcaption|figure|footer|header|hgroup|mark|meter|nav|output|progress|section|summary|time|video",ag=/ jQuery\d+="(?:\d+|null)"/g,ar=/^\s+/,R=/<(?!area|br|col|embed|hr|img|input|link|meta|param)(([\w:]+)[^>]*)\/>/ig,d=/<([\w:]+)/,w=/",""],legend:[1,"
","
"],thead:[1,"","
"],tr:[2,"","
"],td:[3,"","
"],col:[2,"","
"],area:[1,"",""],_default:[0,"",""]},ac=a(av);ax.optgroup=ax.option;ax.tbody=ax.tfoot=ax.colgroup=ax.caption=ax.thead;ax.th=ax.td;if(!b.support.htmlSerialize){ax._default=[1,"div
","
"]}b.fn.extend({text:function(e){if(b.isFunction(e)){return this.each(function(bw){var bv=b(this);bv.text(e.call(this,bw,bv.text()))})}if(typeof e!=="object"&&e!==L){return this.empty().append((this[0]&&this[0].ownerDocument||av).createTextNode(e))}return b.text(this)},wrapAll:function(e){if(b.isFunction(e)){return this.each(function(bw){b(this).wrapAll(e.call(this,bw))})}if(this[0]){var bv=b(e,this[0].ownerDocument).eq(0).clone(true);if(this[0].parentNode){bv.insertBefore(this[0])}bv.map(function(){var bw=this;while(bw.firstChild&&bw.firstChild.nodeType===1){bw=bw.firstChild}return bw}).append(this)}return this},wrapInner:function(e){if(b.isFunction(e)){return this.each(function(bv){b(this).wrapInner(e.call(this,bv))})}return this.each(function(){var bv=b(this),bw=bv.contents();if(bw.length){bw.wrapAll(e)}else{bv.append(e)}})},wrap:function(e){var bv=b.isFunction(e);return this.each(function(bw){b(this).wrapAll(bv?e.call(this,bw):e)})},unwrap:function(){return this.parent().each(function(){if(!b.nodeName(this,"body")){b(this).replaceWith(this.childNodes)}}).end()},append:function(){return this.domManip(arguments,true,function(e){if(this.nodeType===1){this.appendChild(e)}})},prepend:function(){return this.domManip(arguments,true,function(e){if(this.nodeType===1){this.insertBefore(e,this.firstChild)}})},before:function(){if(this[0]&&this[0].parentNode){return this.domManip(arguments,false,function(bv){this.parentNode.insertBefore(bv,this)})}else{if(arguments.length){var e=b.clean(arguments);e.push.apply(e,this.toArray());return this.pushStack(e,"before",arguments)}}},after:function(){if(this[0]&&this[0].parentNode){return this.domManip(arguments,false,function(bv){this.parentNode.insertBefore(bv,this.nextSibling)})}else{if(arguments.length){var e=this.pushStack(this,"after",arguments);e.push.apply(e,b.clean(arguments));return e}}},remove:function(e,bx){for(var bv=0,bw;(bw=this[bv])!=null;bv++){if(!e||b.filter(e,[bw]).length){if(!bx&&bw.nodeType===1){b.cleanData(bw.getElementsByTagName("*"));b.cleanData([bw])}if(bw.parentNode){bw.parentNode.removeChild(bw)}}}return this},empty:function(){for(var e=0,bv;(bv=this[e])!=null;e++){if(bv.nodeType===1){b.cleanData(bv.getElementsByTagName("*"))}while(bv.firstChild){bv.removeChild(bv.firstChild)}}return this},clone:function(bv,e){bv=bv==null?false:bv;e=e==null?bv:e;return this.map(function(){return b.clone(this,bv,e)})},html:function(bx){if(bx===L){return this[0]&&this[0].nodeType===1?this[0].innerHTML.replace(ag,""):null}else{if(typeof bx==="string"&&!ae.test(bx)&&(b.support.leadingWhitespace||!ar.test(bx))&&!ax[(d.exec(bx)||["",""])[1].toLowerCase()]){bx=bx.replace(R,"<$1>");try{for(var bw=0,bv=this.length;bw1&&bw0?this.clone(true):this).get();b(bC[bA])[bv](by);bz=bz.concat(by)}return this.pushStack(bz,e,bC.selector)}}});function bg(e){if(typeof e.getElementsByTagName!=="undefined"){return e.getElementsByTagName("*")}else{if(typeof e.querySelectorAll!=="undefined"){return e.querySelectorAll("*")}else{return[]}}}function az(e){if(e.type==="checkbox"||e.type==="radio"){e.defaultChecked=e.checked}}function E(e){var bv=(e.nodeName||"").toLowerCase();if(bv==="input"){az(e)}else{if(bv!=="script"&&typeof e.getElementsByTagName!=="undefined"){b.grep(e.getElementsByTagName("input"),az)}}}function al(e){var bv=av.createElement("div");ac.appendChild(bv);bv.innerHTML=e.outerHTML;return bv.firstChild}b.extend({clone:function(by,bA,bw){var e,bv,bx,bz=b.support.html5Clone||!ah.test("<"+by.nodeName)?by.cloneNode(true):al(by);if((!b.support.noCloneEvent||!b.support.noCloneChecked)&&(by.nodeType===1||by.nodeType===11)&&!b.isXMLDoc(by)){ai(by,bz);e=bg(by);bv=bg(bz);for(bx=0;e[bx];++bx){if(bv[bx]){ai(e[bx],bv[bx])}}}if(bA){t(by,bz);if(bw){e=bg(by);bv=bg(bz);for(bx=0;e[bx];++bx){t(e[bx],bv[bx])}}}e=bv=null;return bz},clean:function(bw,by,bH,bA){var bF;by=by||av;if(typeof by.createElement==="undefined"){by=by.ownerDocument||by[0]&&by[0].ownerDocument||av}var bI=[],bB;for(var bE=0,bz;(bz=bw[bE])!=null;bE++){if(typeof bz==="number"){bz+=""}if(!bz){continue}if(typeof bz==="string"){if(!W.test(bz)){bz=by.createTextNode(bz)}else{bz=bz.replace(R,"<$1>");var bK=(d.exec(bz)||["",""])[1].toLowerCase(),bx=ax[bK]||ax._default,bD=bx[0],bv=by.createElement("div");if(by===av){ac.appendChild(bv)}else{a(by).appendChild(bv)}bv.innerHTML=bx[1]+bz+bx[2];while(bD--){bv=bv.lastChild}if(!b.support.tbody){var e=w.test(bz),bC=bK==="table"&&!e?bv.firstChild&&bv.firstChild.childNodes:bx[1]===""&&!e?bv.childNodes:[];for(bB=bC.length-1;bB>=0;--bB){if(b.nodeName(bC[bB],"tbody")&&!bC[bB].childNodes.length){bC[bB].parentNode.removeChild(bC[bB])}}}if(!b.support.leadingWhitespace&&ar.test(bz)){bv.insertBefore(by.createTextNode(ar.exec(bz)[0]),bv.firstChild)}bz=bv.childNodes}}var bG;if(!b.support.appendChecked){if(bz[0]&&typeof(bG=bz.length)==="number"){for(bB=0;bB=0){return bx+"px"}}else{return bx}}}});if(!b.support.opacity){b.cssHooks.opacity={get:function(bv,e){return au.test((e&&bv.currentStyle?bv.currentStyle.filter:bv.style.filter)||"")?(parseFloat(RegExp.$1)/100)+"":e?"1":""},set:function(by,bz){var bx=by.style,bv=by.currentStyle,e=b.isNumeric(bz)?"alpha(opacity="+bz*100+")":"",bw=bv&&bv.filter||bx.filter||"";bx.zoom=1;if(bz>=1&&b.trim(bw.replace(ak,""))===""){bx.removeAttribute("filter");if(bv&&!bv.filter){return}}bx.filter=ak.test(bw)?bw.replace(ak,e):bw+" "+e}}}b(function(){if(!b.support.reliableMarginRight){b.cssHooks.marginRight={get:function(bw,bv){var e;b.swap(bw,{display:"inline-block"},function(){if(bv){e=Z(bw,"margin-right","marginRight")}else{e=bw.style.marginRight}});return e}}}});if(av.defaultView&&av.defaultView.getComputedStyle){aI=function(by,bw){var bv,bx,e;bw=bw.replace(z,"-$1").toLowerCase();if((bx=by.ownerDocument.defaultView)&&(e=bx.getComputedStyle(by,null))){bv=e.getPropertyValue(bw);if(bv===""&&!b.contains(by.ownerDocument.documentElement,by)){bv=b.style(by,bw)}}return bv}}if(av.documentElement.currentStyle){aX=function(bz,bw){var bA,e,by,bv=bz.currentStyle&&bz.currentStyle[bw],bx=bz.style;if(bv===null&&bx&&(by=bx[bw])){bv=by}if(!bc.test(bv)&&bn.test(bv)){bA=bx.left;e=bz.runtimeStyle&&bz.runtimeStyle.left;if(e){bz.runtimeStyle.left=bz.currentStyle.left}bx.left=bw==="fontSize"?"1em":(bv||0);bv=bx.pixelLeft+"px";bx.left=bA;if(e){bz.runtimeStyle.left=e}}return bv===""?"auto":bv}}Z=aI||aX;function p(by,bw,bv){var bA=bw==="width"?by.offsetWidth:by.offsetHeight,bz=bw==="width"?an:a1,bx=0,e=bz.length;if(bA>0){if(bv!=="border"){for(;bx)<[^<]*)*<\/script>/gi,q=/^(?:select|textarea)/i,h=/\s+/,br=/([?&])_=[^&]*/,K=/^([\w\+\.\-]+:)(?:\/\/([^\/?#:]*)(?::(\d+))?)?/,A=b.fn.load,aa={},r={},aE,s,aV=["*/"]+["*"];try{aE=bl.href}catch(aw){aE=av.createElement("a");aE.href="";aE=aE.href}s=K.exec(aE.toLowerCase())||[];function f(e){return function(by,bA){if(typeof by!=="string"){bA=by;by="*"}if(b.isFunction(bA)){var bx=by.toLowerCase().split(h),bw=0,bz=bx.length,bv,bB,bC;for(;bw=0){var e=bw.slice(by,bw.length);bw=bw.slice(0,by)}var bx="GET";if(bz){if(b.isFunction(bz)){bA=bz;bz=L}else{if(typeof bz==="object"){bz=b.param(bz,b.ajaxSettings.traditional);bx="POST"}}}var bv=this;b.ajax({url:bw,type:bx,dataType:"html",data:bz,complete:function(bC,bB,bD){bD=bC.responseText;if(bC.isResolved()){bC.done(function(bE){bD=bE});bv.html(e?b("
").append(bD.replace(a6,"")).find(e):bD)}if(bA){bv.each(bA,[bD,bB,bC])}}});return this},serialize:function(){return b.param(this.serializeArray())},serializeArray:function(){return this.map(function(){return this.elements?b.makeArray(this.elements):this}).filter(function(){return this.name&&!this.disabled&&(this.checked||q.test(this.nodeName)||aZ.test(this.type))}).map(function(e,bv){var bw=b(this).val();return bw==null?null:b.isArray(bw)?b.map(bw,function(by,bx){return{name:bv.name,value:by.replace(bs,"\r\n")}}):{name:bv.name,value:bw.replace(bs,"\r\n")}}).get()}});b.each("ajaxStart ajaxStop ajaxComplete ajaxError ajaxSuccess ajaxSend".split(" "),function(e,bv){b.fn[bv]=function(bw){return this.on(bv,bw)}});b.each(["get","post"],function(e,bv){b[bv]=function(bw,by,bz,bx){if(b.isFunction(by)){bx=bx||bz;bz=by;by=L}return b.ajax({type:bv,url:bw,data:by,success:bz,dataType:bx})}});b.extend({getScript:function(e,bv){return b.get(e,L,bv,"script")},getJSON:function(e,bv,bw){return b.get(e,bv,bw,"json")},ajaxSetup:function(bv,e){if(e){am(bv,b.ajaxSettings)}else{e=bv;bv=b.ajaxSettings}am(bv,e);return bv},ajaxSettings:{url:aE,isLocal:aM.test(s[1]),global:true,type:"GET",contentType:"application/x-www-form-urlencoded",processData:true,async:true,accepts:{xml:"application/xml, text/xml",html:"text/html",text:"text/plain",json:"application/json, text/javascript","*":aV},contents:{xml:/xml/,html:/html/,json:/json/},responseFields:{xml:"responseXML",text:"responseText"},converters:{"* text":bb.String,"text html":true,"text json":b.parseJSON,"text xml":b.parseXML},flatOptions:{context:true,url:true}},ajaxPrefilter:f(aa),ajaxTransport:f(r),ajax:function(bz,bx){if(typeof bz==="object"){bx=bz;bz=L}bx=bx||{};var bD=b.ajaxSetup({},bx),bS=bD.context||bD,bG=bS!==bD&&(bS.nodeType||bS instanceof b)?b(bS):b.event,bR=b.Deferred(),bN=b.Callbacks("once memory"),bB=bD.statusCode||{},bC,bH={},bO={},bQ,by,bL,bE,bI,bA=0,bw,bK,bJ={readyState:0,setRequestHeader:function(bT,bU){if(!bA){var e=bT.toLowerCase();bT=bO[e]=bO[e]||bT;bH[bT]=bU}return this},getAllResponseHeaders:function(){return bA===2?bQ:null},getResponseHeader:function(bT){var e;if(bA===2){if(!by){by={};while((e=aD.exec(bQ))){by[e[1].toLowerCase()]=e[2]}}e=by[bT.toLowerCase()]}return e===L?null:e},overrideMimeType:function(e){if(!bA){bD.mimeType=e}return this},abort:function(e){e=e||"abort";if(bL){bL.abort(e)}bF(0,e);return this}};function bF(bZ,bU,b0,bW){if(bA===2){return}bA=2;if(bE){clearTimeout(bE)}bL=L;bQ=bW||"";bJ.readyState=bZ>0?4:0;var bT,b4,b3,bX=bU,bY=b0?bj(bD,bJ,b0):L,bV,b2;if(bZ>=200&&bZ<300||bZ===304){if(bD.ifModified){if((bV=bJ.getResponseHeader("Last-Modified"))){b.lastModified[bC]=bV}if((b2=bJ.getResponseHeader("Etag"))){b.etag[bC]=b2}}if(bZ===304){bX="notmodified";bT=true}else{try{b4=G(bD,bY);bX="success";bT=true}catch(b1){bX="parsererror";b3=b1}}}else{b3=bX;if(!bX||bZ){bX="error";if(bZ<0){bZ=0}}}bJ.status=bZ;bJ.statusText=""+(bU||bX);if(bT){bR.resolveWith(bS,[b4,bX,bJ])}else{bR.rejectWith(bS,[bJ,bX,b3])}bJ.statusCode(bB);bB=L;if(bw){bG.trigger("ajax"+(bT?"Success":"Error"),[bJ,bD,bT?b4:b3])}bN.fireWith(bS,[bJ,bX]);if(bw){bG.trigger("ajaxComplete",[bJ,bD]);if(!(--b.active)){b.event.trigger("ajaxStop")}}}bR.promise(bJ);bJ.success=bJ.done;bJ.error=bJ.fail;bJ.complete=bN.add;bJ.statusCode=function(bT){if(bT){var e;if(bA<2){for(e in bT){bB[e]=[bB[e],bT[e]]}}else{e=bT[bJ.status];bJ.then(e,e)}}return this};bD.url=((bz||bD.url)+"").replace(bq,"").replace(c,s[1]+"//");bD.dataTypes=b.trim(bD.dataType||"*").toLowerCase().split(h);if(bD.crossDomain==null){bI=K.exec(bD.url.toLowerCase());bD.crossDomain=!!(bI&&(bI[1]!=s[1]||bI[2]!=s[2]||(bI[3]||(bI[1]==="http:"?80:443))!=(s[3]||(s[1]==="http:"?80:443))))}if(bD.data&&bD.processData&&typeof bD.data!=="string"){bD.data=b.param(bD.data,bD.traditional)}aW(aa,bD,bx,bJ);if(bA===2){return false}bw=bD.global;bD.type=bD.type.toUpperCase();bD.hasContent=!aQ.test(bD.type);if(bw&&b.active++===0){b.event.trigger("ajaxStart")}if(!bD.hasContent){if(bD.data){bD.url+=(M.test(bD.url)?"&":"?")+bD.data;delete bD.data}bC=bD.url;if(bD.cache===false){var bv=b.now(),bP=bD.url.replace(br,"$1_="+bv);bD.url=bP+((bP===bD.url)?(M.test(bD.url)?"&":"?")+"_="+bv:"")}}if(bD.data&&bD.hasContent&&bD.contentType!==false||bx.contentType){bJ.setRequestHeader("Content-Type",bD.contentType)}if(bD.ifModified){bC=bC||bD.url;if(b.lastModified[bC]){bJ.setRequestHeader("If-Modified-Since",b.lastModified[bC])}if(b.etag[bC]){bJ.setRequestHeader("If-None-Match",b.etag[bC])}}bJ.setRequestHeader("Accept",bD.dataTypes[0]&&bD.accepts[bD.dataTypes[0]]?bD.accepts[bD.dataTypes[0]]+(bD.dataTypes[0]!=="*"?", "+aV+"; q=0.01":""):bD.accepts["*"]);for(bK in bD.headers){bJ.setRequestHeader(bK,bD.headers[bK])}if(bD.beforeSend&&(bD.beforeSend.call(bS,bJ,bD)===false||bA===2)){bJ.abort();return false}for(bK in {success:1,error:1,complete:1}){bJ[bK](bD[bK])}bL=aW(r,bD,bx,bJ);if(!bL){bF(-1,"No Transport")}else{bJ.readyState=1;if(bw){bG.trigger("ajaxSend",[bJ,bD])}if(bD.async&&bD.timeout>0){bE=setTimeout(function(){bJ.abort("timeout")},bD.timeout)}try{bA=1;bL.send(bH,bF)}catch(bM){if(bA<2){bF(-1,bM)}else{throw bM}}}return bJ},param:function(e,bw){var bv=[],by=function(bz,bA){bA=b.isFunction(bA)?bA():bA;bv[bv.length]=encodeURIComponent(bz)+"="+encodeURIComponent(bA)};if(bw===L){bw=b.ajaxSettings.traditional}if(b.isArray(e)||(e.jquery&&!b.isPlainObject(e))){b.each(e,function(){by(this.name,this.value)})}else{for(var bx in e){v(bx,e[bx],bw,by)}}return bv.join("&").replace(k,"+")}});function v(bw,by,bv,bx){if(b.isArray(by)){b.each(by,function(bA,bz){if(bv||ap.test(bw)){bx(bw,bz)}else{v(bw+"["+(typeof bz==="object"||b.isArray(bz)?bA:"")+"]",bz,bv,bx)}})}else{if(!bv&&by!=null&&typeof by==="object"){for(var e in by){v(bw+"["+e+"]",by[e],bv,bx)}}else{bx(bw,by)}}}b.extend({active:0,lastModified:{},etag:{}});function bj(bD,bC,bz){var bv=bD.contents,bB=bD.dataTypes,bw=bD.responseFields,by,bA,bx,e;for(bA in bw){if(bA in bz){bC[bw[bA]]=bz[bA]}}while(bB[0]==="*"){bB.shift();if(by===L){by=bD.mimeType||bC.getResponseHeader("content-type")}}if(by){for(bA in bv){if(bv[bA]&&bv[bA].test(by)){bB.unshift(bA);break}}}if(bB[0] in bz){bx=bB[0]}else{for(bA in bz){if(!bB[0]||bD.converters[bA+" "+bB[0]]){bx=bA;break}if(!e){e=bA}}bx=bx||e}if(bx){if(bx!==bB[0]){bB.unshift(bx)}return bz[bx]}}function G(bH,bz){if(bH.dataFilter){bz=bH.dataFilter(bz,bH.dataType)}var bD=bH.dataTypes,bG={},bA,bE,bw=bD.length,bB,bC=bD[0],bx,by,bF,bv,e;for(bA=1;bA=bw.duration+this.startTime){this.now=this.end;this.pos=this.state=1;this.update();bw.animatedProperties[this.prop]=true;for(bA in bw.animatedProperties){if(bw.animatedProperties[bA]!==true){e=false}}if(e){if(bw.overflow!=null&&!b.support.shrinkWrapBlocks){b.each(["","X","Y"],function(bC,bD){bz.style["overflow"+bD]=bw.overflow[bC]})}if(bw.hide){b(bz).hide()}if(bw.hide||bw.show){for(bA in bw.animatedProperties){b.style(bz,bA,bw.orig[bA]);b.removeData(bz,"fxshow"+bA,true);b.removeData(bz,"toggle"+bA,true)}}bv=bw.complete;if(bv){bw.complete=false;bv.call(bz)}}return false}else{if(bw.duration==Infinity){this.now=bx}else{bB=bx-this.startTime;this.state=bB/bw.duration;this.pos=b.easing[bw.animatedProperties[this.prop]](this.state,bB,0,1,bw.duration);this.now=this.start+((this.end-this.start)*this.pos)}this.update()}return true}};b.extend(b.fx,{tick:function(){var bw,bv=b.timers,e=0;for(;e").appendTo(e),bw=bv.css("display");bv.remove();if(bw==="none"||bw===""){if(!a8){a8=av.createElement("iframe");a8.frameBorder=a8.width=a8.height=0}e.appendChild(a8);if(!m||!a8.createElement){m=(a8.contentWindow||a8.contentDocument).document;m.write((av.compatMode==="CSS1Compat"?"":"")+"");m.close()}bv=m.createElement(bx);m.body.appendChild(bv);bw=b.css(bv,"display");e.removeChild(a8)}Q[bx]=bw}return Q[bx]}var V=/^t(?:able|d|h)$/i,ad=/^(?:body|html)$/i;if("getBoundingClientRect" in av.documentElement){b.fn.offset=function(bI){var by=this[0],bB;if(bI){return this.each(function(e){b.offset.setOffset(this,bI,e)})}if(!by||!by.ownerDocument){return null}if(by===by.ownerDocument.body){return b.offset.bodyOffset(by)}try{bB=by.getBoundingClientRect()}catch(bF){}var bH=by.ownerDocument,bw=bH.documentElement;if(!bB||!b.contains(bw,by)){return bB?{top:bB.top,left:bB.left}:{top:0,left:0}}var bC=bH.body,bD=aK(bH),bA=bw.clientTop||bC.clientTop||0,bE=bw.clientLeft||bC.clientLeft||0,bv=bD.pageYOffset||b.support.boxModel&&bw.scrollTop||bC.scrollTop,bz=bD.pageXOffset||b.support.boxModel&&bw.scrollLeft||bC.scrollLeft,bG=bB.top+bv-bA,bx=bB.left+bz-bE;return{top:bG,left:bx}}}else{b.fn.offset=function(bF){var bz=this[0];if(bF){return this.each(function(bG){b.offset.setOffset(this,bF,bG)})}if(!bz||!bz.ownerDocument){return null}if(bz===bz.ownerDocument.body){return b.offset.bodyOffset(bz)}var bC,bw=bz.offsetParent,bv=bz,bE=bz.ownerDocument,bx=bE.documentElement,bA=bE.body,bB=bE.defaultView,e=bB?bB.getComputedStyle(bz,null):bz.currentStyle,bD=bz.offsetTop,by=bz.offsetLeft;while((bz=bz.parentNode)&&bz!==bA&&bz!==bx){if(b.support.fixedPosition&&e.position==="fixed"){break}bC=bB?bB.getComputedStyle(bz,null):bz.currentStyle;bD-=bz.scrollTop;by-=bz.scrollLeft;if(bz===bw){bD+=bz.offsetTop;by+=bz.offsetLeft;if(b.support.doesNotAddBorder&&!(b.support.doesAddBorderForTableAndCells&&V.test(bz.nodeName))){bD+=parseFloat(bC.borderTopWidth)||0;by+=parseFloat(bC.borderLeftWidth)||0}bv=bw;bw=bz.offsetParent}if(b.support.subtractsBorderForOverflowNotVisible&&bC.overflow!=="visible"){bD+=parseFloat(bC.borderTopWidth)||0;by+=parseFloat(bC.borderLeftWidth)||0}e=bC}if(e.position==="relative"||e.position==="static"){bD+=bA.offsetTop;by+=bA.offsetLeft}if(b.support.fixedPosition&&e.position==="fixed"){bD+=Math.max(bx.scrollTop,bA.scrollTop);by+=Math.max(bx.scrollLeft,bA.scrollLeft)}return{top:bD,left:by}}}b.offset={bodyOffset:function(e){var bw=e.offsetTop,bv=e.offsetLeft;if(b.support.doesNotIncludeMarginInBodyOffset){bw+=parseFloat(b.css(e,"marginTop"))||0;bv+=parseFloat(b.css(e,"marginLeft"))||0}return{top:bw,left:bv}},setOffset:function(bx,bG,bA){var bB=b.css(bx,"position");if(bB==="static"){bx.style.position="relative"}var bz=b(bx),bv=bz.offset(),e=b.css(bx,"top"),bE=b.css(bx,"left"),bF=(bB==="absolute"||bB==="fixed")&&b.inArray("auto",[e,bE])>-1,bD={},bC={},bw,by;if(bF){bC=bz.position();bw=bC.top;by=bC.left}else{bw=parseFloat(e)||0;by=parseFloat(bE)||0}if(b.isFunction(bG)){bG=bG.call(bx,bA,bv)}if(bG.top!=null){bD.top=(bG.top-bv.top)+bw}if(bG.left!=null){bD.left=(bG.left-bv.left)+by}if("using" in bG){bG.using.call(bx,bD)}else{bz.css(bD)}}};b.fn.extend({position:function(){if(!this[0]){return null}var bw=this[0],bv=this.offsetParent(),bx=this.offset(),e=ad.test(bv[0].nodeName)?{top:0,left:0}:bv.offset();bx.top-=parseFloat(b.css(bw,"marginTop"))||0;bx.left-=parseFloat(b.css(bw,"marginLeft"))||0;e.top+=parseFloat(b.css(bv[0],"borderTopWidth"))||0;e.left+=parseFloat(b.css(bv[0],"borderLeftWidth"))||0;return{top:bx.top-e.top,left:bx.left-e.left}},offsetParent:function(){return this.map(function(){var e=this.offsetParent||av.body;while(e&&(!ad.test(e.nodeName)&&b.css(e,"position")==="static")){e=e.offsetParent}return e})}});b.each(["Left","Top"],function(bv,e){var bw="scroll"+e;b.fn[bw]=function(bz){var bx,by;if(bz===L){bx=this[0];if(!bx){return null}by=aK(bx);return by?("pageXOffset" in by)?by[bv?"pageYOffset":"pageXOffset"]:b.support.boxModel&&by.document.documentElement[bw]||by.document.body[bw]:bx[bw]}return this.each(function(){by=aK(this);if(by){by.scrollTo(!bv?bz:b(by).scrollLeft(),bv?bz:b(by).scrollTop())}else{this[bw]=bz}})}});function aK(e){return b.isWindow(e)?e:e.nodeType===9?e.defaultView||e.parentWindow:false}b.each(["Height","Width"],function(bv,e){var bw=e.toLowerCase();b.fn["inner"+e]=function(){var bx=this[0];return bx?bx.style?parseFloat(b.css(bx,bw,"padding")):this[bw]():null};b.fn["outer"+e]=function(by){var bx=this[0];return bx?bx.style?parseFloat(b.css(bx,bw,by?"margin":"border")):this[bw]():null};b.fn[bw]=function(bz){var bA=this[0];if(!bA){return bz==null?null:this}if(b.isFunction(bz)){return this.each(function(bE){var bD=b(this);bD[bw](bz.call(this,bE,bD[bw]()))})}if(b.isWindow(bA)){var bB=bA.document.documentElement["client"+e],bx=bA.document.body;return bA.document.compatMode==="CSS1Compat"&&bB||bx&&bx["client"+e]||bB}else{if(bA.nodeType===9){return Math.max(bA.documentElement["client"+e],bA.body["scroll"+e],bA.documentElement["scroll"+e],bA.body["offset"+e],bA.documentElement["offset"+e])}else{if(bz===L){var bC=b.css(bA,bw),by=parseFloat(bC);return b.isNumeric(by)?by:bC}else{return this.css(bw,typeof bz==="string"?bz:bz+"px")}}}}});bb.jQuery=bb.$=b;if(typeof define==="function"&&define.amd&&define.amd.jQuery){define("jquery",[],function(){return b})}})(window);/*! - * jQuery UI 1.8.18 - * - * Copyright 2011, AUTHORS.txt (http://jqueryui.com/about) - * Dual licensed under the MIT or GPL Version 2 licenses. - * http://jquery.org/license - * - * http://docs.jquery.com/UI - */ -(function(a,d){a.ui=a.ui||{};if(a.ui.version){return}a.extend(a.ui,{version:"1.8.18",keyCode:{ALT:18,BACKSPACE:8,CAPS_LOCK:20,COMMA:188,COMMAND:91,COMMAND_LEFT:91,COMMAND_RIGHT:93,CONTROL:17,DELETE:46,DOWN:40,END:35,ENTER:13,ESCAPE:27,HOME:36,INSERT:45,LEFT:37,MENU:93,NUMPAD_ADD:107,NUMPAD_DECIMAL:110,NUMPAD_DIVIDE:111,NUMPAD_ENTER:108,NUMPAD_MULTIPLY:106,NUMPAD_SUBTRACT:109,PAGE_DOWN:34,PAGE_UP:33,PERIOD:190,RIGHT:39,SHIFT:16,SPACE:32,TAB:9,UP:38,WINDOWS:91}});a.fn.extend({propAttr:a.fn.prop||a.fn.attr,_focus:a.fn.focus,focus:function(e,f){return typeof e==="number"?this.each(function(){var g=this;setTimeout(function(){a(g).focus();if(f){f.call(g)}},e)}):this._focus.apply(this,arguments)},scrollParent:function(){var e;if((a.browser.msie&&(/(static|relative)/).test(this.css("position")))||(/absolute/).test(this.css("position"))){e=this.parents().filter(function(){return(/(relative|absolute|fixed)/).test(a.curCSS(this,"position",1))&&(/(auto|scroll)/).test(a.curCSS(this,"overflow",1)+a.curCSS(this,"overflow-y",1)+a.curCSS(this,"overflow-x",1))}).eq(0)}else{e=this.parents().filter(function(){return(/(auto|scroll)/).test(a.curCSS(this,"overflow",1)+a.curCSS(this,"overflow-y",1)+a.curCSS(this,"overflow-x",1))}).eq(0)}return(/fixed/).test(this.css("position"))||!e.length?a(document):e},zIndex:function(h){if(h!==d){return this.css("zIndex",h)}if(this.length){var f=a(this[0]),e,g;while(f.length&&f[0]!==document){e=f.css("position");if(e==="absolute"||e==="relative"||e==="fixed"){g=parseInt(f.css("zIndex"),10);if(!isNaN(g)&&g!==0){return g}}f=f.parent()}}return 0},disableSelection:function(){return this.bind((a.support.selectstart?"selectstart":"mousedown")+".ui-disableSelection",function(e){e.preventDefault()})},enableSelection:function(){return this.unbind(".ui-disableSelection")}});a.each(["Width","Height"],function(g,e){var f=e==="Width"?["Left","Right"]:["Top","Bottom"],h=e.toLowerCase(),k={innerWidth:a.fn.innerWidth,innerHeight:a.fn.innerHeight,outerWidth:a.fn.outerWidth,outerHeight:a.fn.outerHeight};function j(m,l,i,n){a.each(f,function(){l-=parseFloat(a.curCSS(m,"padding"+this,true))||0;if(i){l-=parseFloat(a.curCSS(m,"border"+this+"Width",true))||0}if(n){l-=parseFloat(a.curCSS(m,"margin"+this,true))||0}});return l}a.fn["inner"+e]=function(i){if(i===d){return k["inner"+e].call(this)}return this.each(function(){a(this).css(h,j(this,i)+"px")})};a.fn["outer"+e]=function(i,l){if(typeof i!=="number"){return k["outer"+e].call(this,i)}return this.each(function(){a(this).css(h,j(this,i,true,l)+"px")})}});function c(g,e){var j=g.nodeName.toLowerCase();if("area"===j){var i=g.parentNode,h=i.name,f;if(!g.href||!h||i.nodeName.toLowerCase()!=="map"){return false}f=a("img[usemap=#"+h+"]")[0];return !!f&&b(f)}return(/input|select|textarea|button|object/.test(j)?!g.disabled:"a"==j?g.href||e:e)&&b(g)}function b(e){return !a(e).parents().andSelf().filter(function(){return a.curCSS(this,"visibility")==="hidden"||a.expr.filters.hidden(this)}).length}a.extend(a.expr[":"],{data:function(g,f,e){return !!a.data(g,e[3])},focusable:function(e){return c(e,!isNaN(a.attr(e,"tabindex")))},tabbable:function(g){var e=a.attr(g,"tabindex"),f=isNaN(e);return(f||e>=0)&&c(g,!f)}});a(function(){var e=document.body,f=e.appendChild(f=document.createElement("div"));f.offsetHeight;a.extend(f.style,{minHeight:"100px",height:"auto",padding:0,borderWidth:0});a.support.minHeight=f.offsetHeight===100;a.support.selectstart="onselectstart" in f;e.removeChild(f).style.display="none"});a.extend(a.ui,{plugin:{add:function(f,g,j){var h=a.ui[f].prototype;for(var e in j){h.plugins[e]=h.plugins[e]||[];h.plugins[e].push([g,j[e]])}},call:function(e,g,f){var j=e.plugins[g];if(!j||!e.element[0].parentNode){return}for(var h=0;h0){return true}h[e]=1;g=(h[e]>0);h[e]=0;return g},isOverAxis:function(f,e,g){return(f>e)&&(f<(e+g))},isOver:function(j,f,i,h,e,g){return a.ui.isOverAxis(j,i,e)&&a.ui.isOverAxis(f,h,g)}})})(jQuery);/*! - * jQuery UI Widget 1.8.18 - * - * Copyright 2011, AUTHORS.txt (http://jqueryui.com/about) - * Dual licensed under the MIT or GPL Version 2 licenses. - * http://jquery.org/license - * - * http://docs.jquery.com/UI/Widget - */ -(function(b,d){if(b.cleanData){var c=b.cleanData;b.cleanData=function(f){for(var g=0,h;(h=f[g])!=null;g++){try{b(h).triggerHandler("remove")}catch(j){}}c(f)}}else{var a=b.fn.remove;b.fn.remove=function(e,f){return this.each(function(){if(!f){if(!e||b.filter(e,[this]).length){b("*",this).add([this]).each(function(){try{b(this).triggerHandler("remove")}catch(g){}})}}return a.call(b(this),e,f)})}}b.widget=function(f,h,e){var g=f.split(".")[0],j;f=f.split(".")[1];j=g+"-"+f;if(!e){e=h;h=b.Widget}b.expr[":"][j]=function(k){return !!b.data(k,f)};b[g]=b[g]||{};b[g][f]=function(k,l){if(arguments.length){this._createWidget(k,l)}};var i=new h();i.options=b.extend(true,{},i.options);b[g][f].prototype=b.extend(true,i,{namespace:g,widgetName:f,widgetEventPrefix:b[g][f].prototype.widgetEventPrefix||f,widgetBaseClass:j},e);b.widget.bridge(f,b[g][f])};b.widget.bridge=function(f,e){b.fn[f]=function(i){var g=typeof i==="string",h=Array.prototype.slice.call(arguments,1),j=this;i=!g&&h.length?b.extend.apply(null,[true,i].concat(h)):i;if(g&&i.charAt(0)==="_"){return j}if(g){this.each(function(){var k=b.data(this,f),l=k&&b.isFunction(k[i])?k[i].apply(k,h):k;if(l!==k&&l!==d){j=l;return false}})}else{this.each(function(){var k=b.data(this,f);if(k){k.option(i||{})._init()}else{b.data(this,f,new e(i,this))}})}return j}};b.Widget=function(e,f){if(arguments.length){this._createWidget(e,f)}};b.Widget.prototype={widgetName:"widget",widgetEventPrefix:"",options:{disabled:false},_createWidget:function(f,g){b.data(g,this.widgetName,this);this.element=b(g);this.options=b.extend(true,{},this.options,this._getCreateOptions(),f);var e=this;this.element.bind("remove."+this.widgetName,function(){e.destroy()});this._create();this._trigger("create");this._init()},_getCreateOptions:function(){return b.metadata&&b.metadata.get(this.element[0])[this.widgetName]},_create:function(){},_init:function(){},destroy:function(){this.element.unbind("."+this.widgetName).removeData(this.widgetName);this.widget().unbind("."+this.widgetName).removeAttr("aria-disabled").removeClass(this.widgetBaseClass+"-disabled ui-state-disabled")},widget:function(){return this.element},option:function(f,g){var e=f;if(arguments.length===0){return b.extend({},this.options)}if(typeof f==="string"){if(g===d){return this.options[f]}e={};e[f]=g}this._setOptions(e);return this},_setOptions:function(f){var e=this;b.each(f,function(g,h){e._setOption(g,h)});return this},_setOption:function(e,f){this.options[e]=f;if(e==="disabled"){this.widget()[f?"addClass":"removeClass"](this.widgetBaseClass+"-disabled ui-state-disabled").attr("aria-disabled",f)}return this},enable:function(){return this._setOption("disabled",false)},disable:function(){return this._setOption("disabled",true)},_trigger:function(e,f,g){var j,i,h=this.options[e];g=g||{};f=b.Event(f);f.type=(e===this.widgetEventPrefix?e:this.widgetEventPrefix+e).toLowerCase();f.target=this.element[0];i=f.originalEvent;if(i){for(j in i){if(!(j in f)){f[j]=i[j]}}}this.element.trigger(f,g);return !(b.isFunction(h)&&h.call(this.element[0],f,g)===false||f.isDefaultPrevented())}}})(jQuery);/*! - * jQuery UI Mouse 1.8.18 - * - * Copyright 2011, AUTHORS.txt (http://jqueryui.com/about) - * Dual licensed under the MIT or GPL Version 2 licenses. - * http://jquery.org/license - * - * http://docs.jquery.com/UI/Mouse - * - * Depends: - * jquery.ui.widget.js - */ -(function(b,c){var a=false;b(document).mouseup(function(d){a=false});b.widget("ui.mouse",{options:{cancel:":input,option",distance:1,delay:0},_mouseInit:function(){var d=this;this.element.bind("mousedown."+this.widgetName,function(e){return d._mouseDown(e)}).bind("click."+this.widgetName,function(e){if(true===b.data(e.target,d.widgetName+".preventClickEvent")){b.removeData(e.target,d.widgetName+".preventClickEvent");e.stopImmediatePropagation();return false}});this.started=false},_mouseDestroy:function(){this.element.unbind("."+this.widgetName)},_mouseDown:function(f){if(a){return}(this._mouseStarted&&this._mouseUp(f));this._mouseDownEvent=f;var e=this,g=(f.which==1),d=(typeof this.options.cancel=="string"&&f.target.nodeName?b(f.target).closest(this.options.cancel).length:false);if(!g||d||!this._mouseCapture(f)){return true}this.mouseDelayMet=!this.options.delay;if(!this.mouseDelayMet){this._mouseDelayTimer=setTimeout(function(){e.mouseDelayMet=true},this.options.delay)}if(this._mouseDistanceMet(f)&&this._mouseDelayMet(f)){this._mouseStarted=(this._mouseStart(f)!==false);if(!this._mouseStarted){f.preventDefault();return true}}if(true===b.data(f.target,this.widgetName+".preventClickEvent")){b.removeData(f.target,this.widgetName+".preventClickEvent")}this._mouseMoveDelegate=function(h){return e._mouseMove(h)};this._mouseUpDelegate=function(h){return e._mouseUp(h)};b(document).bind("mousemove."+this.widgetName,this._mouseMoveDelegate).bind("mouseup."+this.widgetName,this._mouseUpDelegate);f.preventDefault();a=true;return true},_mouseMove:function(d){if(b.browser.msie&&!(document.documentMode>=9)&&!d.button){return this._mouseUp(d)}if(this._mouseStarted){this._mouseDrag(d);return d.preventDefault()}if(this._mouseDistanceMet(d)&&this._mouseDelayMet(d)){this._mouseStarted=(this._mouseStart(this._mouseDownEvent,d)!==false);(this._mouseStarted?this._mouseDrag(d):this._mouseUp(d))}return !this._mouseStarted},_mouseUp:function(d){b(document).unbind("mousemove."+this.widgetName,this._mouseMoveDelegate).unbind("mouseup."+this.widgetName,this._mouseUpDelegate);if(this._mouseStarted){this._mouseStarted=false;if(d.target==this._mouseDownEvent.target){b.data(d.target,this.widgetName+".preventClickEvent",true)}this._mouseStop(d)}return false},_mouseDistanceMet:function(d){return(Math.max(Math.abs(this._mouseDownEvent.pageX-d.pageX),Math.abs(this._mouseDownEvent.pageY-d.pageY))>=this.options.distance)},_mouseDelayMet:function(d){return this.mouseDelayMet},_mouseStart:function(d){},_mouseDrag:function(d){},_mouseStop:function(d){},_mouseCapture:function(d){return true}})})(jQuery);(function(c,d){c.widget("ui.resizable",c.ui.mouse,{widgetEventPrefix:"resize",options:{alsoResize:false,animate:false,animateDuration:"slow",animateEasing:"swing",aspectRatio:false,autoHide:false,containment:false,ghost:false,grid:false,handles:"e,s,se",helper:false,maxHeight:null,maxWidth:null,minHeight:10,minWidth:10,zIndex:1000},_create:function(){var f=this,k=this.options;this.element.addClass("ui-resizable");c.extend(this,{_aspectRatio:!!(k.aspectRatio),aspectRatio:k.aspectRatio,originalElement:this.element,_proportionallyResizeElements:[],_helper:k.helper||k.ghost||k.animate?k.helper||"ui-resizable-helper":null});if(this.element[0].nodeName.match(/canvas|textarea|input|select|button|img/i)){this.element.wrap(c('
').css({position:this.element.css("position"),width:this.element.outerWidth(),height:this.element.outerHeight(),top:this.element.css("top"),left:this.element.css("left")}));this.element=this.element.parent().data("resizable",this.element.data("resizable"));this.elementIsWrapper=true;this.element.css({marginLeft:this.originalElement.css("marginLeft"),marginTop:this.originalElement.css("marginTop"),marginRight:this.originalElement.css("marginRight"),marginBottom:this.originalElement.css("marginBottom")});this.originalElement.css({marginLeft:0,marginTop:0,marginRight:0,marginBottom:0});this.originalResizeStyle=this.originalElement.css("resize");this.originalElement.css("resize","none");this._proportionallyResizeElements.push(this.originalElement.css({position:"static",zoom:1,display:"block"}));this.originalElement.css({margin:this.originalElement.css("margin")});this._proportionallyResize()}this.handles=k.handles||(!c(".ui-resizable-handle",this.element).length?"e,s,se":{n:".ui-resizable-n",e:".ui-resizable-e",s:".ui-resizable-s",w:".ui-resizable-w",se:".ui-resizable-se",sw:".ui-resizable-sw",ne:".ui-resizable-ne",nw:".ui-resizable-nw"});if(this.handles.constructor==String){if(this.handles=="all"){this.handles="n,e,s,w,se,sw,ne,nw"}var l=this.handles.split(",");this.handles={};for(var g=0;g
');if(/sw|se|ne|nw/.test(j)){h.css({zIndex:++k.zIndex})}if("se"==j){h.addClass("ui-icon ui-icon-gripsmall-diagonal-se")}this.handles[j]=".ui-resizable-"+j;this.element.append(h)}}this._renderAxis=function(q){q=q||this.element;for(var n in this.handles){if(this.handles[n].constructor==String){this.handles[n]=c(this.handles[n],this.element).show()}if(this.elementIsWrapper&&this.originalElement[0].nodeName.match(/textarea|input|select|button/i)){var o=c(this.handles[n],this.element),p=0;p=/sw|ne|nw|se|n|s/.test(n)?o.outerHeight():o.outerWidth();var m=["padding",/ne|nw|n/.test(n)?"Top":/se|sw|s/.test(n)?"Bottom":/^e$/.test(n)?"Right":"Left"].join("");q.css(m,p);this._proportionallyResize()}if(!c(this.handles[n]).length){continue}}};this._renderAxis(this.element);this._handles=c(".ui-resizable-handle",this.element).disableSelection();this._handles.mouseover(function(){if(!f.resizing){if(this.className){var i=this.className.match(/ui-resizable-(se|sw|ne|nw|n|e|s|w)/i)}f.axis=i&&i[1]?i[1]:"se"}});if(k.autoHide){this._handles.hide();c(this.element).addClass("ui-resizable-autohide").hover(function(){if(k.disabled){return}c(this).removeClass("ui-resizable-autohide");f._handles.show()},function(){if(k.disabled){return}if(!f.resizing){c(this).addClass("ui-resizable-autohide");f._handles.hide()}})}this._mouseInit()},destroy:function(){this._mouseDestroy();var e=function(g){c(g).removeClass("ui-resizable ui-resizable-disabled ui-resizable-resizing").removeData("resizable").unbind(".resizable").find(".ui-resizable-handle").remove()};if(this.elementIsWrapper){e(this.element);var f=this.element;f.after(this.originalElement.css({position:f.css("position"),width:f.outerWidth(),height:f.outerHeight(),top:f.css("top"),left:f.css("left")})).remove()}this.originalElement.css("resize",this.originalResizeStyle);e(this.originalElement);return this},_mouseCapture:function(f){var g=false;for(var e in this.handles){if(c(this.handles[e])[0]==f.target){g=true}}return !this.options.disabled&&g},_mouseStart:function(g){var j=this.options,f=this.element.position(),e=this.element;this.resizing=true;this.documentScroll={top:c(document).scrollTop(),left:c(document).scrollLeft()};if(e.is(".ui-draggable")||(/absolute/).test(e.css("position"))){e.css({position:"absolute",top:f.top,left:f.left})}this._renderProxy();var k=b(this.helper.css("left")),h=b(this.helper.css("top"));if(j.containment){k+=c(j.containment).scrollLeft()||0;h+=c(j.containment).scrollTop()||0}this.offset=this.helper.offset();this.position={left:k,top:h};this.size=this._helper?{width:e.outerWidth(),height:e.outerHeight()}:{width:e.width(),height:e.height()};this.originalSize=this._helper?{width:e.outerWidth(),height:e.outerHeight()}:{width:e.width(),height:e.height()};this.originalPosition={left:k,top:h};this.sizeDiff={width:e.outerWidth()-e.width(),height:e.outerHeight()-e.height()};this.originalMousePosition={left:g.pageX,top:g.pageY};this.aspectRatio=(typeof j.aspectRatio=="number")?j.aspectRatio:((this.originalSize.width/this.originalSize.height)||1);var i=c(".ui-resizable-"+this.axis).css("cursor");c("body").css("cursor",i=="auto"?this.axis+"-resize":i);e.addClass("ui-resizable-resizing");this._propagate("start",g);return true},_mouseDrag:function(e){var h=this.helper,g=this.options,m={},q=this,j=this.originalMousePosition,n=this.axis;var r=(e.pageX-j.left)||0,p=(e.pageY-j.top)||0;var i=this._change[n];if(!i){return false}var l=i.apply(this,[e,r,p]),k=c.browser.msie&&c.browser.version<7,f=this.sizeDiff;this._updateVirtualBoundaries(e.shiftKey);if(this._aspectRatio||e.shiftKey){l=this._updateRatio(l,e)}l=this._respectSize(l,e);this._propagate("resize",e);h.css({top:this.position.top+"px",left:this.position.left+"px",width:this.size.width+"px",height:this.size.height+"px"});if(!this._helper&&this._proportionallyResizeElements.length){this._proportionallyResize()}this._updateCache(l);this._trigger("resize",e,this.ui());return false},_mouseStop:function(h){this.resizing=false;var i=this.options,m=this;if(this._helper){var g=this._proportionallyResizeElements,e=g.length&&(/textarea/i).test(g[0].nodeName),f=e&&c.ui.hasScroll(g[0],"left")?0:m.sizeDiff.height,k=e?0:m.sizeDiff.width;var n={width:(m.helper.width()-k),height:(m.helper.height()-f)},j=(parseInt(m.element.css("left"),10)+(m.position.left-m.originalPosition.left))||null,l=(parseInt(m.element.css("top"),10)+(m.position.top-m.originalPosition.top))||null;if(!i.animate){this.element.css(c.extend(n,{top:l,left:j}))}m.helper.height(m.size.height);m.helper.width(m.size.width);if(this._helper&&!i.animate){this._proportionallyResize()}}c("body").css("cursor","auto");this.element.removeClass("ui-resizable-resizing");this._propagate("stop",h);if(this._helper){this.helper.remove()}return false},_updateVirtualBoundaries:function(g){var j=this.options,i,h,f,k,e;e={minWidth:a(j.minWidth)?j.minWidth:0,maxWidth:a(j.maxWidth)?j.maxWidth:Infinity,minHeight:a(j.minHeight)?j.minHeight:0,maxHeight:a(j.maxHeight)?j.maxHeight:Infinity};if(this._aspectRatio||g){i=e.minHeight*this.aspectRatio;f=e.minWidth/this.aspectRatio;h=e.maxHeight*this.aspectRatio;k=e.maxWidth/this.aspectRatio;if(i>e.minWidth){e.minWidth=i}if(f>e.minHeight){e.minHeight=f}if(hl.width),s=a(l.height)&&i.minHeight&&(i.minHeight>l.height);if(h){l.width=i.minWidth}if(s){l.height=i.minHeight}if(t){l.width=i.maxWidth}if(m){l.height=i.maxHeight}var f=this.originalPosition.left+this.originalSize.width,p=this.position.top+this.size.height;var k=/sw|nw|w/.test(q),e=/nw|ne|n/.test(q);if(h&&k){l.left=f-i.minWidth}if(t&&k){l.left=f-i.maxWidth}if(s&&e){l.top=p-i.minHeight}if(m&&e){l.top=p-i.maxHeight}var n=!l.width&&!l.height;if(n&&!l.left&&l.top){l.top=null}else{if(n&&!l.top&&l.left){l.left=null}}return l},_proportionallyResize:function(){var k=this.options;if(!this._proportionallyResizeElements.length){return}var g=this.helper||this.element;for(var f=0;f');var e=c.browser.msie&&c.browser.version<7,g=(e?1:0),h=(e?2:-1);this.helper.addClass(this._helper).css({width:this.element.outerWidth()+h,height:this.element.outerHeight()+h,position:"absolute",left:this.elementOffset.left-g+"px",top:this.elementOffset.top-g+"px",zIndex:++i.zIndex});this.helper.appendTo("body").disableSelection()}else{this.helper=this.element}},_change:{e:function(g,f,e){return{width:this.originalSize.width+f}},w:function(h,f,e){var j=this.options,g=this.originalSize,i=this.originalPosition;return{left:i.left+f,width:g.width-f}},n:function(h,f,e){var j=this.options,g=this.originalSize,i=this.originalPosition;return{top:i.top+e,height:g.height-e}},s:function(g,f,e){return{height:this.originalSize.height+e}},se:function(g,f,e){return c.extend(this._change.s.apply(this,arguments),this._change.e.apply(this,[g,f,e]))},sw:function(g,f,e){return c.extend(this._change.s.apply(this,arguments),this._change.w.apply(this,[g,f,e]))},ne:function(g,f,e){return c.extend(this._change.n.apply(this,arguments),this._change.e.apply(this,[g,f,e]))},nw:function(g,f,e){return c.extend(this._change.n.apply(this,arguments),this._change.w.apply(this,[g,f,e]))}},_propagate:function(f,e){c.ui.plugin.call(this,f,[e,this.ui()]);(f!="resize"&&this._trigger(f,e,this.ui()))},plugins:{},ui:function(){return{originalElement:this.originalElement,element:this.element,helper:this.helper,position:this.position,size:this.size,originalSize:this.originalSize,originalPosition:this.originalPosition}}});c.extend(c.ui.resizable,{version:"1.8.18"});c.ui.plugin.add("resizable","alsoResize",{start:function(f,g){var e=c(this).data("resizable"),i=e.options;var h=function(j){c(j).each(function(){var k=c(this);k.data("resizable-alsoresize",{width:parseInt(k.width(),10),height:parseInt(k.height(),10),left:parseInt(k.css("left"),10),top:parseInt(k.css("top"),10)})})};if(typeof(i.alsoResize)=="object"&&!i.alsoResize.parentNode){if(i.alsoResize.length){i.alsoResize=i.alsoResize[0];h(i.alsoResize)}else{c.each(i.alsoResize,function(j){h(j)})}}else{h(i.alsoResize)}},resize:function(g,i){var f=c(this).data("resizable"),j=f.options,h=f.originalSize,l=f.originalPosition;var k={height:(f.size.height-h.height)||0,width:(f.size.width-h.width)||0,top:(f.position.top-l.top)||0,left:(f.position.left-l.left)||0},e=function(m,n){c(m).each(function(){var q=c(this),r=c(this).data("resizable-alsoresize"),p={},o=n&&n.length?n:q.parents(i.originalElement[0]).length?["width","height"]:["width","height","top","left"];c.each(o,function(s,u){var t=(r[u]||0)+(k[u]||0);if(t&&t>=0){p[u]=t||null}});q.css(p)})};if(typeof(j.alsoResize)=="object"&&!j.alsoResize.nodeType){c.each(j.alsoResize,function(m,n){e(m,n)})}else{e(j.alsoResize)}},stop:function(e,f){c(this).removeData("resizable-alsoresize")}});c.ui.plugin.add("resizable","animate",{stop:function(i,n){var p=c(this).data("resizable"),j=p.options;var h=p._proportionallyResizeElements,e=h.length&&(/textarea/i).test(h[0].nodeName),f=e&&c.ui.hasScroll(h[0],"left")?0:p.sizeDiff.height,l=e?0:p.sizeDiff.width;var g={width:(p.size.width-l),height:(p.size.height-f)},k=(parseInt(p.element.css("left"),10)+(p.position.left-p.originalPosition.left))||null,m=(parseInt(p.element.css("top"),10)+(p.position.top-p.originalPosition.top))||null;p.element.animate(c.extend(g,m&&k?{top:m,left:k}:{}),{duration:j.animateDuration,easing:j.animateEasing,step:function(){var o={width:parseInt(p.element.css("width"),10),height:parseInt(p.element.css("height"),10),top:parseInt(p.element.css("top"),10),left:parseInt(p.element.css("left"),10)};if(h&&h.length){c(h[0]).css({width:o.width,height:o.height})}p._updateCache(o);p._propagate("resize",i)}})}});c.ui.plugin.add("resizable","containment",{start:function(f,r){var t=c(this).data("resizable"),j=t.options,l=t.element;var g=j.containment,k=(g instanceof c)?g.get(0):(/parent/.test(g))?l.parent().get(0):g;if(!k){return}t.containerElement=c(k);if(/document/.test(g)||g==document){t.containerOffset={left:0,top:0};t.containerPosition={left:0,top:0};t.parentData={element:c(document),left:0,top:0,width:c(document).width(),height:c(document).height()||document.body.parentNode.scrollHeight}}else{var n=c(k),i=[];c(["Top","Right","Left","Bottom"]).each(function(p,o){i[p]=b(n.css("padding"+o))});t.containerOffset=n.offset();t.containerPosition=n.position();t.containerSize={height:(n.innerHeight()-i[3]),width:(n.innerWidth()-i[1])};var q=t.containerOffset,e=t.containerSize.height,m=t.containerSize.width,h=(c.ui.hasScroll(k,"left")?k.scrollWidth:m),s=(c.ui.hasScroll(k)?k.scrollHeight:e);t.parentData={element:k,left:q.left,top:q.top,width:h,height:s}}},resize:function(g,q){var t=c(this).data("resizable"),i=t.options,f=t.containerSize,p=t.containerOffset,m=t.size,n=t.position,r=t._aspectRatio||g.shiftKey,e={top:0,left:0},h=t.containerElement;if(h[0]!=document&&(/static/).test(h.css("position"))){e=p}if(n.left<(t._helper?p.left:0)){t.size.width=t.size.width+(t._helper?(t.position.left-p.left):(t.position.left-e.left));if(r){t.size.height=t.size.width/i.aspectRatio}t.position.left=i.helper?p.left:0}if(n.top<(t._helper?p.top:0)){t.size.height=t.size.height+(t._helper?(t.position.top-p.top):t.position.top);if(r){t.size.width=t.size.height*i.aspectRatio}t.position.top=t._helper?p.top:0}t.offset.left=t.parentData.left+t.position.left;t.offset.top=t.parentData.top+t.position.top;var l=Math.abs((t._helper?t.offset.left-e.left:(t.offset.left-e.left))+t.sizeDiff.width),s=Math.abs((t._helper?t.offset.top-e.top:(t.offset.top-p.top))+t.sizeDiff.height);var k=t.containerElement.get(0)==t.element.parent().get(0),j=/relative|absolute/.test(t.containerElement.css("position"));if(k&&j){l-=t.parentData.left}if(l+t.size.width>=t.parentData.width){t.size.width=t.parentData.width-l;if(r){t.size.height=t.size.width/t.aspectRatio}}if(s+t.size.height>=t.parentData.height){t.size.height=t.parentData.height-s;if(r){t.size.width=t.size.height*t.aspectRatio}}},stop:function(f,n){var q=c(this).data("resizable"),g=q.options,l=q.position,m=q.containerOffset,e=q.containerPosition,i=q.containerElement;var j=c(q.helper),r=j.offset(),p=j.outerWidth()-q.sizeDiff.width,k=j.outerHeight()-q.sizeDiff.height;if(q._helper&&!g.animate&&(/relative/).test(i.css("position"))){c(this).css({left:r.left-e.left-m.left,width:p,height:k})}if(q._helper&&!g.animate&&(/static/).test(i.css("position"))){c(this).css({left:r.left-e.left-m.left,width:p,height:k})}}});c.ui.plugin.add("resizable","ghost",{start:function(g,h){var e=c(this).data("resizable"),i=e.options,f=e.size;e.ghost=e.originalElement.clone();e.ghost.css({opacity:0.25,display:"block",position:"relative",height:f.height,width:f.width,margin:0,left:0,top:0}).addClass("ui-resizable-ghost").addClass(typeof i.ghost=="string"?i.ghost:"");e.ghost.appendTo(e.helper)},resize:function(f,g){var e=c(this).data("resizable"),h=e.options;if(e.ghost){e.ghost.css({position:"relative",height:e.size.height,width:e.size.width})}},stop:function(f,g){var e=c(this).data("resizable"),h=e.options;if(e.ghost&&e.helper){e.helper.get(0).removeChild(e.ghost.get(0))}}});c.ui.plugin.add("resizable","grid",{resize:function(e,m){var p=c(this).data("resizable"),h=p.options,k=p.size,i=p.originalSize,j=p.originalPosition,n=p.axis,l=h._aspectRatio||e.shiftKey;h.grid=typeof h.grid=="number"?[h.grid,h.grid]:h.grid;var g=Math.round((k.width-i.width)/(h.grid[0]||1))*(h.grid[0]||1),f=Math.round((k.height-i.height)/(h.grid[1]||1))*(h.grid[1]||1);if(/^(se|s|e)$/.test(n)){p.size.width=i.width+g;p.size.height=i.height+f}else{if(/^(ne)$/.test(n)){p.size.width=i.width+g;p.size.height=i.height+f;p.position.top=j.top-f}else{if(/^(sw)$/.test(n)){p.size.width=i.width+g;p.size.height=i.height+f;p.position.left=j.left-g}else{p.size.width=i.width+g;p.size.height=i.height+f;p.position.top=j.top-f;p.position.left=j.left-g}}}}});var b=function(e){return parseInt(e,10)||0};var a=function(e){return !isNaN(parseInt(e,10))}})(jQuery);/*! - * jQuery hashchange event - v1.3 - 7/21/2010 - * http://benalman.com/projects/jquery-hashchange-plugin/ - * - * Copyright (c) 2010 "Cowboy" Ben Alman - * Dual licensed under the MIT and GPL licenses. - * http://benalman.com/about/license/ - */ -(function($,e,b){var c="hashchange",h=document,f,g=$.event.special,i=h.documentMode,d="on"+c in e&&(i===b||i>7);function a(j){j=j||location.href;return"#"+j.replace(/^[^#]*#?(.*)$/,"$1")}$.fn[c]=function(j){return j?this.bind(c,j):this.trigger(c)};$.fn[c].delay=50;g[c]=$.extend(g[c],{setup:function(){if(d){return false}$(f.start)},teardown:function(){if(d){return false}$(f.stop)}});f=(function(){var j={},p,m=a(),k=function(q){return q},l=k,o=k;j.start=function(){p||n()};j.stop=function(){p&&clearTimeout(p);p=b};function n(){var r=a(),q=o(m);if(r!==m){l(m=r,q);$(e).trigger(c)}else{if(q!==m){location.href=location.href.replace(/#.*/,"")+q}}p=setTimeout(n,$.fn[c].delay)}$.browser.msie&&!d&&(function(){var q,r;j.start=function(){if(!q){r=$.fn[c].src;r=r&&r+a();q=$(' - - -
-
-
Modules
-
-
-
Here is a list of all modules:
-
[detail level 12]
- - - - - - - - - - - - - - - -
 Higher level methods, setters and getters
 Methods
 Getters and setters
 Lower level fun stuff methods
 Lower level servo drive methods and getters
 Methods
 Getters
 Lower level ultra sonic methods and getters
 Methods
 Setters and getters
 Lower level drives methods and getters
 Methods
 Getters
 Lower level LED methods
 Methods
- - - - - - - diff --git a/Doku/Doxygen/html/modules.js b/Doku/Doxygen/html/modules.js deleted file mode 100644 index 457b22f..0000000 --- a/Doku/Doxygen/html/modules.js +++ /dev/null @@ -1,9 +0,0 @@ -var modules = -[ - [ "Higher level methods, setters and getters", "d9/d80/group__higherlevel.html", "d9/d80/group__higherlevel" ], - [ "Lower level fun stuff methods", "d8/d7a/group__lowerlevelfun.html", "d8/d7a/group__lowerlevelfun" ], - [ "Lower level servo drive methods and getters", "d3/d17/group__lowerlevelservo.html", "d3/d17/group__lowerlevelservo" ], - [ "Lower level ultra sonic methods and getters", "da/daf/group__lowerlevelus.html", "da/daf/group__lowerlevelus" ], - [ "Lower level drives methods and getters", "d6/d98/group__lowerleveldrives.html", "d6/d98/group__lowerleveldrives" ], - [ "Lower level LED methods", "d7/d0f/group__lowerlevelled.html", "d7/d0f/group__lowerlevelled" ] -]; \ No newline at end of file diff --git a/Doku/Doxygen/html/nav_f.png b/Doku/Doxygen/html/nav_f.png deleted file mode 100644 index 72a58a5..0000000 Binary files a/Doku/Doxygen/html/nav_f.png and /dev/null differ diff --git a/Doku/Doxygen/html/nav_g.png b/Doku/Doxygen/html/nav_g.png deleted file mode 100644 index 2093a23..0000000 Binary files a/Doku/Doxygen/html/nav_g.png and /dev/null differ diff --git a/Doku/Doxygen/html/nav_h.png b/Doku/Doxygen/html/nav_h.png deleted file mode 100644 index 33389b1..0000000 Binary files a/Doku/Doxygen/html/nav_h.png and /dev/null differ diff --git a/Doku/Doxygen/html/navtree.css b/Doku/Doxygen/html/navtree.css deleted file mode 100644 index 0cc7e77..0000000 --- a/Doku/Doxygen/html/navtree.css +++ /dev/null @@ -1,146 +0,0 @@ -#nav-tree .children_ul { - margin:0; - padding:4px; -} - -#nav-tree ul { - list-style:none outside none; - margin:0px; - padding:0px; -} - -#nav-tree li { - white-space:nowrap; - margin:0px; - padding:0px; -} - -#nav-tree .plus { - margin:0px; -} - -#nav-tree .selected { - background-image: url('tab_a.png'); - background-repeat:repeat-x; - color: #fff; - text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); -} - -#nav-tree img { - margin:0px; - padding:0px; - border:0px; - vertical-align: middle; -} - -#nav-tree a { - text-decoration:none; - padding:0px; - margin:0px; - outline:none; -} - -#nav-tree .label { - margin:0px; - padding:0px; - font: 12px 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; -} - -#nav-tree .label a { - padding:2px; -} - -#nav-tree .selected a { - text-decoration:none; - color:#fff; -} - -#nav-tree .children_ul { - margin:0px; - padding:0px; -} - -#nav-tree .item { - margin:0px; - padding:0px; -} - -#nav-tree { - padding: 0px 0px; - background-color: #FAFAFF; - font-size:14px; - overflow:auto; -} - -#doc-content { - overflow:auto; - display:block; - padding:0px; - margin:0px; - -webkit-overflow-scrolling : touch; /* iOS 5+ */ -} - -#side-nav { - padding:0 6px 0 0; - margin: 0px; - display:block; - position: absolute; - left: 0px; - width: 250px; -} - -.ui-resizable .ui-resizable-handle { - display:block; -} - -.ui-resizable-e { - background-image:url("splitbar.png"); - background-size:100%; - background-repeat:no-repeat; - background-attachment: scroll; - cursor:ew-resize; - height:100%; - right:0; - top:0; - width:6px; -} - -.ui-resizable-handle { - display:none; - font-size:0.1px; - position:absolute; - z-index:1; -} - -#nav-tree-contents { - margin: 6px 0px 0px 0px; -} - -#nav-tree { - background-image:url('nav_h.png'); - background-repeat:repeat-x; - background-color: #F9FAFC; - -webkit-overflow-scrolling : touch; /* iOS 5+ */ -} - -#nav-sync { - position:absolute; - top:5px; - right:24px; - z-index:0; -} - -#nav-sync img { - opacity:0.3; -} - -#nav-sync img:hover { - opacity:0.9; -} - -@media print -{ - #nav-tree { display: none; } - div.ui-resizable-handle { display: none; position: relative; } -} - diff --git a/Doku/Doxygen/html/navtree.js b/Doku/Doxygen/html/navtree.js deleted file mode 100644 index e6d31b0..0000000 --- a/Doku/Doxygen/html/navtree.js +++ /dev/null @@ -1,517 +0,0 @@ -var navTreeSubIndices = new Array(); -var arrowDown = '▼'; -var arrowRight = '►'; - -function getData(varName) -{ - var i = varName.lastIndexOf('/'); - var n = i>=0 ? varName.substring(i+1) : varName; - return eval(n.replace(/\-/g,'_')); -} - -function stripPath(uri) -{ - return uri.substring(uri.lastIndexOf('/')+1); -} - -function stripPath2(uri) -{ - var i = uri.lastIndexOf('/'); - var s = uri.substring(i+1); - var m = uri.substring(0,i+1).match(/\/d\w\/d\w\w\/$/); - return m ? uri.substring(i-6) : s; -} - -function hashValue() -{ - return $(location).attr('hash').substring(1).replace(/[^\w\-]/g,''); -} - -function hashUrl() -{ - return '#'+hashValue(); -} - -function pathName() -{ - return $(location).attr('pathname').replace(/[^-A-Za-z0-9+&@#/%?=~_|!:,.;\(\)]/g, ''); -} - -function localStorageSupported() -{ - try { - return 'localStorage' in window && window['localStorage'] !== null && window.localStorage.getItem; - } - catch(e) { - return false; - } -} - - -function storeLink(link) -{ - if (!$("#nav-sync").hasClass('sync') && localStorageSupported()) { - window.localStorage.setItem('navpath',link); - } -} - -function deleteLink() -{ - if (localStorageSupported()) { - window.localStorage.setItem('navpath',''); - } -} - -function cachedLink() -{ - if (localStorageSupported()) { - return window.localStorage.getItem('navpath'); - } else { - return ''; - } -} - -function getScript(scriptName,func,show) -{ - var head = document.getElementsByTagName("head")[0]; - var script = document.createElement('script'); - script.id = scriptName; - script.type = 'text/javascript'; - script.onload = func; - script.src = scriptName+'.js'; - if ($.browser.msie && $.browser.version<=8) { - // script.onload does not work with older versions of IE - script.onreadystatechange = function() { - if (script.readyState=='complete' || script.readyState=='loaded') { - func(); if (show) showRoot(); - } - } - } - head.appendChild(script); -} - -function createIndent(o,domNode,node,level) -{ - var level=-1; - var n = node; - while (n.parentNode) { level++; n=n.parentNode; } - if (node.childrenData) { - var imgNode = document.createElement("span"); - imgNode.className = 'arrow'; - imgNode.style.paddingLeft=(16*level).toString()+'px'; - imgNode.innerHTML=arrowRight; - node.plus_img = imgNode; - node.expandToggle = document.createElement("a"); - node.expandToggle.href = "javascript:void(0)"; - node.expandToggle.onclick = function() { - if (node.expanded) { - $(node.getChildrenUL()).slideUp("fast"); - node.plus_img.innerHTML=arrowRight; - node.expanded = false; - } else { - expandNode(o, node, false, false); - } - } - node.expandToggle.appendChild(imgNode); - domNode.appendChild(node.expandToggle); - } else { - var span = document.createElement("span"); - span.className = 'arrow'; - span.style.width = 16*(level+1)+'px'; - span.innerHTML = ' '; - domNode.appendChild(span); - } -} - -var animationInProgress = false; - -function gotoAnchor(anchor,aname,updateLocation) -{ - var pos, docContent = $('#doc-content'); - var ancParent = $(anchor.parent()); - if (ancParent.hasClass('memItemLeft') || - ancParent.hasClass('fieldname') || - ancParent.hasClass('fieldtype') || - ancParent.is(':header')) - { - pos = ancParent.position().top; - } else if (anchor.position()) { - pos = anchor.position().top; - } - if (pos) { - var dist = Math.abs(Math.min( - pos-docContent.offset().top, - docContent[0].scrollHeight- - docContent.height()-docContent.scrollTop())); - animationInProgress=true; - docContent.animate({ - scrollTop: pos + docContent.scrollTop() - docContent.offset().top - },Math.max(50,Math.min(500,dist)),function(){ - if (updateLocation) window.location.href=aname; - animationInProgress=false; - }); - } -} - -function newNode(o, po, text, link, childrenData, lastNode) -{ - var node = new Object(); - node.children = Array(); - node.childrenData = childrenData; - node.depth = po.depth + 1; - node.relpath = po.relpath; - node.isLast = lastNode; - - node.li = document.createElement("li"); - po.getChildrenUL().appendChild(node.li); - node.parentNode = po; - - node.itemDiv = document.createElement("div"); - node.itemDiv.className = "item"; - - node.labelSpan = document.createElement("span"); - node.labelSpan.className = "label"; - - createIndent(o,node.itemDiv,node,0); - node.itemDiv.appendChild(node.labelSpan); - node.li.appendChild(node.itemDiv); - - var a = document.createElement("a"); - node.labelSpan.appendChild(a); - node.label = document.createTextNode(text); - node.expanded = false; - a.appendChild(node.label); - if (link) { - var url; - if (link.substring(0,1)=='^') { - url = link.substring(1); - link = url; - } else { - url = node.relpath+link; - } - a.className = stripPath(link.replace('#',':')); - if (link.indexOf('#')!=-1) { - var aname = '#'+link.split('#')[1]; - var srcPage = stripPath(pathName()); - var targetPage = stripPath(link.split('#')[0]); - a.href = srcPage!=targetPage ? url : "javascript:void(0)"; - a.onclick = function(){ - storeLink(link); - if (!$(a).parent().parent().hasClass('selected')) - { - $('.item').removeClass('selected'); - $('.item').removeAttr('id'); - $(a).parent().parent().addClass('selected'); - $(a).parent().parent().attr('id','selected'); - } - var anchor = $(aname); - gotoAnchor(anchor,aname,true); - }; - } else { - a.href = url; - a.onclick = function() { storeLink(link); } - } - } else { - if (childrenData != null) - { - a.className = "nolink"; - a.href = "javascript:void(0)"; - a.onclick = node.expandToggle.onclick; - } - } - - node.childrenUL = null; - node.getChildrenUL = function() { - if (!node.childrenUL) { - node.childrenUL = document.createElement("ul"); - node.childrenUL.className = "children_ul"; - node.childrenUL.style.display = "none"; - node.li.appendChild(node.childrenUL); - } - return node.childrenUL; - }; - - return node; -} - -function showRoot() -{ - var headerHeight = $("#top").height(); - var footerHeight = $("#nav-path").height(); - var windowHeight = $(window).height() - headerHeight - footerHeight; - (function (){ // retry until we can scroll to the selected item - try { - var navtree=$('#nav-tree'); - navtree.scrollTo('#selected',0,{offset:-windowHeight/2}); - } catch (err) { - setTimeout(arguments.callee, 0); - } - })(); -} - -function expandNode(o, node, imm, showRoot) -{ - if (node.childrenData && !node.expanded) { - if (typeof(node.childrenData)==='string') { - var varName = node.childrenData; - getScript(node.relpath+varName,function(){ - node.childrenData = getData(varName); - expandNode(o, node, imm, showRoot); - }, showRoot); - } else { - if (!node.childrenVisited) { - getNode(o, node); - } if (imm || ($.browser.msie && $.browser.version>8)) { - // somehow slideDown jumps to the start of tree for IE9 :-( - $(node.getChildrenUL()).show(); - } else { - $(node.getChildrenUL()).slideDown("fast"); - } - node.plus_img.innerHTML = arrowDown; - node.expanded = true; - } - } -} - -function glowEffect(n,duration) -{ - n.addClass('glow').delay(duration).queue(function(next){ - $(this).removeClass('glow');next(); - }); -} - -function highlightAnchor() -{ - var aname = hashUrl(); - var anchor = $(aname); - if (anchor.parent().attr('class')=='memItemLeft'){ - var rows = $('.memberdecls tr[class$="'+hashValue()+'"]'); - glowEffect(rows.children(),300); // member without details - } else if (anchor.parent().attr('class')=='fieldname'){ - glowEffect(anchor.parent().parent(),1000); // enum value - } else if (anchor.parent().attr('class')=='fieldtype'){ - glowEffect(anchor.parent().parent(),1000); // struct field - } else if (anchor.parent().is(":header")) { - glowEffect(anchor.parent(),1000); // section header - } else { - glowEffect(anchor.next(),1000); // normal member - } - gotoAnchor(anchor,aname,false); -} - -function selectAndHighlight(hash,n) -{ - var a; - if (hash) { - var link=stripPath(pathName())+':'+hash.substring(1); - a=$('.item a[class$="'+link+'"]'); - } - if (a && a.length) { - a.parent().parent().addClass('selected'); - a.parent().parent().attr('id','selected'); - highlightAnchor(); - } else if (n) { - $(n.itemDiv).addClass('selected'); - $(n.itemDiv).attr('id','selected'); - } - if ($('#nav-tree-contents .item:first').hasClass('selected')) { - $('#nav-sync').css('top','30px'); - } else { - $('#nav-sync').css('top','5px'); - } - showRoot(); -} - -function showNode(o, node, index, hash) -{ - if (node && node.childrenData) { - if (typeof(node.childrenData)==='string') { - var varName = node.childrenData; - getScript(node.relpath+varName,function(){ - node.childrenData = getData(varName); - showNode(o,node,index,hash); - },true); - } else { - if (!node.childrenVisited) { - getNode(o, node); - } - $(node.getChildrenUL()).css({'display':'block'}); - node.plus_img.innerHTML = arrowDown; - node.expanded = true; - var n = node.children[o.breadcrumbs[index]]; - if (index+11) hash = '#'+parts[1].replace(/[^\w\-]/g,''); - else hash=''; - } - if (hash.match(/^#l\d+$/)) { - var anchor=$('a[name='+hash.substring(1)+']'); - glowEffect(anchor.parent(),1000); // line number - hash=''; // strip line number anchors - } - var url=root+hash; - var i=-1; - while (NAVTREEINDEX[i+1]<=url) i++; - if (i==-1) { i=0; root=NAVTREE[0][1]; } // fallback: show index - if (navTreeSubIndices[i]) { - gotoNode(o,i,root,hash,relpath) - } else { - getScript(relpath+'navtreeindex'+i,function(){ - navTreeSubIndices[i] = eval('NAVTREEINDEX'+i); - if (navTreeSubIndices[i]) { - gotoNode(o,i,root,hash,relpath); - } - },true); - } -} - -function showSyncOff(n,relpath) -{ - n.html(''); -} - -function showSyncOn(n,relpath) -{ - n.html(''); -} - -function toggleSyncButton(relpath) -{ - var navSync = $('#nav-sync'); - if (navSync.hasClass('sync')) { - navSync.removeClass('sync'); - showSyncOff(navSync,relpath); - storeLink(stripPath2(pathName())+hashUrl()); - } else { - navSync.addClass('sync'); - showSyncOn(navSync,relpath); - deleteLink(); - } -} - -function initNavTree(toroot,relpath) -{ - var o = new Object(); - o.toroot = toroot; - o.node = new Object(); - o.node.li = document.getElementById("nav-tree-contents"); - o.node.childrenData = NAVTREE; - o.node.children = new Array(); - o.node.childrenUL = document.createElement("ul"); - o.node.getChildrenUL = function() { return o.node.childrenUL; }; - o.node.li.appendChild(o.node.childrenUL); - o.node.depth = 0; - o.node.relpath = relpath; - o.node.expanded = false; - o.node.isLast = true; - o.node.plus_img = document.createElement("span"); - o.node.plus_img.className = 'arrow'; - o.node.plus_img.innerHTML = arrowRight; - - if (localStorageSupported()) { - var navSync = $('#nav-sync'); - if (cachedLink()) { - showSyncOff(navSync,relpath); - navSync.removeClass('sync'); - } else { - showSyncOn(navSync,relpath); - } - navSync.click(function(){ toggleSyncButton(relpath); }); - } - - $(window).load(function(){ - navTo(o,toroot,hashUrl(),relpath); - showRoot(); - }); - - $(window).bind('hashchange', function(){ - if (window.location.hash && window.location.hash.length>1){ - var a; - if ($(location).attr('hash')){ - var clslink=stripPath(pathName())+':'+hashValue(); - a=$('.item a[class$="'+clslink.replace(/=desktop_vp) { - if (!collapsed) { - collapseExpand(); - } - } else if (width>desktop_vp && collapsedWidth0) { - restoreWidth(0); - collapsed=true; - } - else { - var width = readCookie('width'); - if (width>200 && width<$(window).width()) { restoreWidth(width); } else { restoreWidth(200); } - collapsed=false; - } - } - - header = $("#top"); - sidenav = $("#side-nav"); - content = $("#doc-content"); - navtree = $("#nav-tree"); - footer = $("#nav-path"); - $(".side-nav-resizable").resizable({resize: function(e, ui) { resizeWidth(); } }); - $(sidenav).resizable({ minWidth: 0 }); - $(window).resize(function() { resizeHeight(); }); - var device = navigator.userAgent.toLowerCase(); - var touch_device = device.match(/(iphone|ipod|ipad|android)/); - if (touch_device) { /* wider split bar for touch only devices */ - $(sidenav).css({ paddingRight:'20px' }); - $('.ui-resizable-e').css({ width:'20px' }); - $('#nav-sync').css({ right:'34px' }); - barWidth=20; - } - var width = readCookie('width'); - if (width) { restoreWidth(width); } else { resizeWidth(); } - resizeHeight(); - var url = location.href; - var i=url.indexOf("#"); - if (i>=0) window.location.hash=url.substr(i); - var _preventDefault = function(evt) { evt.preventDefault(); }; - $("#splitbar").bind("dragstart", _preventDefault).bind("selectstart", _preventDefault); - $(".ui-resizable-handle").dblclick(collapseExpand); - $(window).load(resizeHeight); -} - - diff --git a/Doku/Doxygen/html/search/all_0.html b/Doku/Doxygen/html/search/all_0.html deleted file mode 100644 index f25360b..0000000 --- a/Doku/Doxygen/html/search/all_0.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_0.js b/Doku/Doxygen/html/search/all_0.js deleted file mode 100644 index 8c13bd9..0000000 --- a/Doku/Doxygen/html/search/all_0.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['drive_5fbackward',['drive_backward',['../d2/d40/group__higherlevelmeths.html#ga98aa8a5a46f769d59e6c1067c8418cfb',1,'CodeRacer::drive_backward()'],['../d2/d40/group__higherlevelmeths.html#ga6cd8356ac76360b014db6170276b6b30',1,'CodeRacer::drive_backward(uint8_t left_speed, uint8_t right_speed)']]], - ['drive_5fforward',['drive_forward',['../d2/d40/group__higherlevelmeths.html#ga8be6a850099812153dcf5768d7fc8b8c',1,'CodeRacer::drive_forward()'],['../d2/d40/group__higherlevelmeths.html#gaae6fc379ec43cbe2cb2f63fbd12dbe0d',1,'CodeRacer::drive_forward(uint8_t left_speed, uint8_t right_speed)']]], - ['drive_5fleft_5fspeed',['drive_left_speed',['../d0/d0a/group__lowerleveldrivesgetters.html#ga804a45724f3788fd2fdb9631c66d1377',1,'CodeRacer']]], - ['drive_5fright_5fspeed',['drive_right_speed',['../d0/d0a/group__lowerleveldrivesgetters.html#ga09359a792e3299b1c20f6b99939ea7b3',1,'CodeRacer']]], - ['drives_5fsettings',['drives_settings',['../d1/d8a/group__lowerleveldrivesmeths.html#ga5812df751da5b480240ccd633c515b83',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/all_1.html b/Doku/Doxygen/html/search/all_1.html deleted file mode 100644 index b13f0f7..0000000 --- a/Doku/Doxygen/html/search/all_1.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_1.js b/Doku/Doxygen/html/search/all_1.js deleted file mode 100644 index cc2645a..0000000 --- a/Doku/Doxygen/html/search/all_1.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['getters_20and_20setters',['Getters and setters',['../d7/d45/group__higherlevelgetters.html',1,'']]], - ['getters',['Getters',['../d0/d0a/group__lowerleveldrivesgetters.html',1,'']]], - ['getters',['Getters',['../d4/df4/group__lowerlevelservogetters.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/all_2.html b/Doku/Doxygen/html/search/all_2.html deleted file mode 100644 index 9543c57..0000000 --- a/Doku/Doxygen/html/search/all_2.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_2.js b/Doku/Doxygen/html/search/all_2.js deleted file mode 100644 index 51cafb8..0000000 --- a/Doku/Doxygen/html/search/all_2.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['higher_20level_20methods_2c_20setters_20and_20getters',['Higher level methods, setters and getters',['../d9/d80/group__higherlevel.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/all_3.html b/Doku/Doxygen/html/search/all_3.html deleted file mode 100644 index 03405c0..0000000 --- a/Doku/Doxygen/html/search/all_3.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_3.js b/Doku/Doxygen/html/search/all_3.js deleted file mode 100644 index e1d5c34..0000000 --- a/Doku/Doxygen/html/search/all_3.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['is_5factive',['is_active',['../d7/d45/group__higherlevelgetters.html#gaa0ab4d6a754a23ea13664a553bcc8ff2',1,'CodeRacer']]], - ['is_5fdriving',['is_driving',['../d7/d45/group__higherlevelgetters.html#ga33dcd96e9b12dec794c56be85ec1ee05',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/all_4.html b/Doku/Doxygen/html/search/all_4.html deleted file mode 100644 index 8e1f4b9..0000000 --- a/Doku/Doxygen/html/search/all_4.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_4.js b/Doku/Doxygen/html/search/all_4.js deleted file mode 100644 index 2115eb7..0000000 --- a/Doku/Doxygen/html/search/all_4.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['kitt',['kitt',['../d8/d7a/group__lowerlevelfun.html#ga3b6f819fb82d910888fbc87abff1470c',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/all_5.html b/Doku/Doxygen/html/search/all_5.html deleted file mode 100644 index 89a879e..0000000 --- a/Doku/Doxygen/html/search/all_5.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_5.js b/Doku/Doxygen/html/search/all_5.js deleted file mode 100644 index b9240a2..0000000 --- a/Doku/Doxygen/html/search/all_5.js +++ /dev/null @@ -1,9 +0,0 @@ -var searchData= -[ - ['look_5faround',['look_around',['../d8/d7a/group__lowerlevelfun.html#ga04309a38252639a8eaa43809c04c11c8',1,'CodeRacer']]], - ['lower_20level_20drives_20methods_20and_20getters',['Lower level drives methods and getters',['../d6/d98/group__lowerleveldrives.html',1,'']]], - ['lower_20level_20fun_20stuff_20methods',['Lower level fun stuff methods',['../d8/d7a/group__lowerlevelfun.html',1,'']]], - ['lower_20level_20led_20methods',['Lower level LED methods',['../d7/d0f/group__lowerlevelled.html',1,'']]], - ['lower_20level_20servo_20drive_20methods_20and_20getters',['Lower level servo drive methods and getters',['../d3/d17/group__lowerlevelservo.html',1,'']]], - ['lower_20level_20ultra_20sonic_20methods_20and_20getters',['Lower level ultra sonic methods and getters',['../da/daf/group__lowerlevelus.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/all_6.html b/Doku/Doxygen/html/search/all_6.html deleted file mode 100644 index 6afac06..0000000 --- a/Doku/Doxygen/html/search/all_6.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_6.js b/Doku/Doxygen/html/search/all_6.js deleted file mode 100644 index de441f6..0000000 --- a/Doku/Doxygen/html/search/all_6.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['methods',['Methods',['../d2/d40/group__higherlevelmeths.html',1,'']]], - ['methods',['Methods',['../d1/d8a/group__lowerleveldrivesmeths.html',1,'']]], - ['methods',['Methods',['../dd/dff/group__lowerlevelledmeths.html',1,'']]], - ['methods',['Methods',['../db/dd5/group__lowerlevelservomeths.html',1,'']]], - ['methods',['Methods',['../d6/dfc/group__lowerlevelusmeths.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/all_7.html b/Doku/Doxygen/html/search/all_7.html deleted file mode 100644 index de19107..0000000 --- a/Doku/Doxygen/html/search/all_7.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_7.js b/Doku/Doxygen/html/search/all_7.js deleted file mode 100644 index a4c8366..0000000 --- a/Doku/Doxygen/html/search/all_7.js +++ /dev/null @@ -1,34 +0,0 @@ -var searchData= -[ - ['setters_20and_20getters',['Setters and getters',['../db/ddd/group__lowerlevelusgetters.html',1,'']]], - ['servo_5fposition',['servo_position',['../d4/df4/group__lowerlevelservogetters.html#ga451b3ecd272e9a11de4b221f8d771432',1,'CodeRacer']]], - ['servo_5fposition_5feta_5fin_5fms',['servo_position_eta_in_ms',['../d4/df4/group__lowerlevelservogetters.html#ga84ba256b9ccdf0e9f4280279da68a509',1,'CodeRacer']]], - ['servo_5fposition_5fset_5fat_5fms',['servo_position_set_at_ms',['../d4/df4/group__lowerlevelservogetters.html#gaeed05a3d4e06adccebdfce207b734b2f',1,'CodeRacer']]], - ['servo_5fset_5fposition',['servo_set_position',['../db/dd5/group__lowerlevelservomeths.html#gab8831340049de6dbddeda997745725e6',1,'CodeRacer']]], - ['servo_5fset_5fposition_5fwait',['servo_set_position_wait',['../db/dd5/group__lowerlevelservomeths.html#ga0149226288bff2290d52ed1cbd674edd',1,'CodeRacer']]], - ['servo_5fset_5fto_5fcenter',['servo_set_to_center',['../db/dd5/group__lowerlevelservomeths.html#gad1f28aa91079e88fc3093e3074edfb32',1,'CodeRacer']]], - ['servo_5fset_5fto_5fleft',['servo_set_to_left',['../db/dd5/group__lowerlevelservomeths.html#gaef7d1903b65a0a8ab4fafdc53080b07d',1,'CodeRacer']]], - ['servo_5fset_5fto_5fright',['servo_set_to_right',['../db/dd5/group__lowerlevelservomeths.html#gaac73bf99cf2d19f7b1987156aa842b74',1,'CodeRacer']]], - ['servo_5fsettings',['servo_settings',['../db/dd5/group__lowerlevelservomeths.html#ga687beb327e20f4d0541d1ac9e29c01c3',1,'CodeRacer']]], - ['servo_5fsweep',['servo_sweep',['../db/dd5/group__lowerlevelservomeths.html#ga1e9afe1f27dfc9796b4c9b3dba245365',1,'CodeRacer']]], - ['set_5factive',['set_active',['../d7/d45/group__higherlevelgetters.html#ga415c69930f291d5e06b7211b31843310',1,'CodeRacer']]], - ['set_5fdrive_5fleft_5fspeed',['set_drive_left_speed',['../d1/d8a/group__lowerleveldrivesmeths.html#ga1ee3da20ec98a821ab97ced070974861',1,'CodeRacer']]], - ['set_5fdrive_5fleft_5fstate',['set_drive_left_state',['../d1/d8a/group__lowerleveldrivesmeths.html#ga1eeb3cb47503c3011562f9c42828fab9',1,'CodeRacer']]], - ['set_5fdrive_5fright_5fspeed',['set_drive_right_speed',['../d1/d8a/group__lowerleveldrivesmeths.html#gaf8805d0d620a2fb78c576f36a2c81073',1,'CodeRacer']]], - ['set_5fdrive_5fright_5fstate',['set_drive_right_state',['../d1/d8a/group__lowerleveldrivesmeths.html#ga1b34ec9cee1f21cd15db310167a2faa5',1,'CodeRacer']]], - ['set_5fdrive_5fspeed',['set_drive_speed',['../d1/d8a/group__lowerleveldrivesmeths.html#ga5d67c84606d5b39996a99fcd6e7eb314',1,'CodeRacer']]], - ['set_5fdrive_5fstate',['set_drive_state',['../d1/d8a/group__lowerleveldrivesmeths.html#ga3b69cf4a718c842fbe758d3f4267214e',1,'CodeRacer']]], - ['set_5fdrives_5fspeed_5fleft_5fright',['set_drives_speed_left_right',['../d1/d8a/group__lowerleveldrivesmeths.html#ga3d3ffb41783d34589e33cf61fed46c70',1,'CodeRacer']]], - ['set_5fdrives_5fstates_5fleft_5fright',['set_drives_states_left_right',['../d1/d8a/group__lowerleveldrivesmeths.html#ga802d2646d9cc0d766e1ac799c7917fa8',1,'CodeRacer']]], - ['set_5fdrives_5fstop_5fleft_5fright',['set_drives_stop_left_right',['../d1/d8a/group__lowerleveldrivesmeths.html#ga61ed9e0415a62a290cc5c59a0f740304',1,'CodeRacer']]], - ['set_5finactive',['set_inactive',['../d7/d45/group__higherlevelgetters.html#ga62f1c0eea56e27d0853cb58f30eb140d',1,'CodeRacer']]], - ['set_5fleds_5fall',['set_leds_all',['../dd/dff/group__lowerlevelledmeths.html#gab4319e66963b1b71a34370d73962fa78',1,'CodeRacer']]], - ['set_5fleds_5fall_5foff',['set_leds_all_off',['../dd/dff/group__lowerlevelledmeths.html#gaa3f2ad08103127f2cb49344c33b666ea',1,'CodeRacer']]], - ['set_5fleds_5fall_5fon',['set_leds_all_on',['../dd/dff/group__lowerlevelledmeths.html#ga0c8b3d6ce992e1dcfd13fd86c9f89846',1,'CodeRacer']]], - ['set_5fleds_5fleft_5fstop_5ffrwd_5fright',['set_leds_left_stop_frwd_right',['../dd/dff/group__lowerlevelledmeths.html#gab2514ca3994de3d64337dd6536fa6ef3',1,'CodeRacer']]], - ['start_5fstop',['start_stop',['../d2/d40/group__higherlevelmeths.html#ga34e2fe2123e76fd844482dfef6c5a9c8',1,'CodeRacer']]], - ['start_5fstop_5fat_5fmin_5fdistance',['start_stop_at_min_distance',['../d2/d40/group__higherlevelmeths.html#ga128683caea019a89bce06f722ba92556',1,'CodeRacer::start_stop_at_min_distance()'],['../d2/d40/group__higherlevelmeths.html#ga64bc1b2a8ed5bc3ec5e706fa70a1385d',1,'CodeRacer::start_stop_at_min_distance(unsigned long min_distance_cm)']]], - ['stop_5fdriving',['stop_driving',['../d2/d40/group__higherlevelmeths.html#ga71df7ac5e41ae776a6c786d3dc36f35a',1,'CodeRacer']]], - ['stop_5fstop_5fat_5fmin_5fdistance',['stop_stop_at_min_distance',['../d2/d40/group__higherlevelmeths.html#gac664109241d08b8dc52db5721f394b22',1,'CodeRacer']]], - ['stopped_5fat_5fmin_5fdistance',['stopped_at_min_distance',['../d7/d45/group__higherlevelgetters.html#gae8b8c0ab24ccb572281785aeca8541e1',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/all_8.html b/Doku/Doxygen/html/search/all_8.html deleted file mode 100644 index 11e27cd..0000000 --- a/Doku/Doxygen/html/search/all_8.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_8.js b/Doku/Doxygen/html/search/all_8.js deleted file mode 100644 index cc58d20..0000000 --- a/Doku/Doxygen/html/search/all_8.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['turn_5fleft',['turn_left',['../d2/d40/group__higherlevelmeths.html#ga86b7caf6ff46e9d1ad90ed507864b175',1,'CodeRacer::turn_left()'],['../d2/d40/group__higherlevelmeths.html#ga30e1ec3fbbc206f93ea66dbf91b5fd95',1,'CodeRacer::turn_left(unsigned long turn_for_ms)'],['../d2/d40/group__higherlevelmeths.html#gae6daa587199e5bf95b1aac675de53b0e',1,'CodeRacer::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)']]], - ['turn_5fleft_5ffor_5fms',['turn_left_for_ms',['../d7/d45/group__higherlevelgetters.html#gaf04fd16ca0e2ace656f9549c43d16459',1,'CodeRacer']]], - ['turn_5fright',['turn_right',['../d2/d40/group__higherlevelmeths.html#ga8969fb2d6e2b5ac44a99197931e6b8da',1,'CodeRacer::turn_right()'],['../d2/d40/group__higherlevelmeths.html#gae1f175aad98d773b0206f483ae0bb4ea',1,'CodeRacer::turn_right(unsigned long turn_for_ms)'],['../d2/d40/group__higherlevelmeths.html#gad10b3457489cc7e25ffb4d64c539528a',1,'CodeRacer::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)']]], - ['turn_5fright_5ffor_5fms',['turn_right_for_ms',['../d7/d45/group__higherlevelgetters.html#gac0698f02f6a21d9d1f5b9cf2820306cf',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/all_9.html b/Doku/Doxygen/html/search/all_9.html deleted file mode 100644 index f8abbbe..0000000 --- a/Doku/Doxygen/html/search/all_9.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/all_9.js b/Doku/Doxygen/html/search/all_9.js deleted file mode 100644 index bc703b3..0000000 --- a/Doku/Doxygen/html/search/all_9.js +++ /dev/null @@ -1,11 +0,0 @@ -var searchData= -[ - ['usonic_5fdistance_5fcm',['usonic_distance_cm',['../db/ddd/group__lowerlevelusgetters.html#gad59842c14196598e55644b2a22621454',1,'CodeRacer']]], - ['usonic_5fdistance_5fus',['usonic_distance_us',['../db/ddd/group__lowerlevelusgetters.html#ga917b90f21e731ef5f690d5198e7f4d3e',1,'CodeRacer']]], - ['usonic_5fmeasure_5fcm',['usonic_measure_cm',['../d6/dfc/group__lowerlevelusmeths.html#ga5f034198a28b069478c454c63dbfa225',1,'CodeRacer::usonic_measure_cm()'],['../d6/dfc/group__lowerlevelusmeths.html#gafdd5c75d7a8e7b7c993e512ee93dde9a',1,'CodeRacer::usonic_measure_cm(unsigned long max_echo_run_time_us)']]], - ['usonic_5fmeasure_5fsingle_5fshot_5fcm',['usonic_measure_single_shot_cm',['../d6/dfc/group__lowerlevelusmeths.html#ga0c00edbbf4a3169613c9ea84d6e7dc13',1,'CodeRacer::usonic_measure_single_shot_cm()'],['../d6/dfc/group__lowerlevelusmeths.html#gab413551ea8a67e1b60eda1671029b645',1,'CodeRacer::usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us)']]], - ['usonic_5fmeasure_5fsingle_5fshot_5fus',['usonic_measure_single_shot_us',['../d6/dfc/group__lowerlevelusmeths.html#gad4309b6da17085575fb0c55559e240b8',1,'CodeRacer::usonic_measure_single_shot_us()'],['../d6/dfc/group__lowerlevelusmeths.html#ga1b5b43372082f5daeee47410a09a590c',1,'CodeRacer::usonic_measure_single_shot_us(unsigned long max_echo_run_time_us)']]], - ['usonic_5fmeasure_5fus',['usonic_measure_us',['../d6/dfc/group__lowerlevelusmeths.html#gaa01602a576fd57609bc7e08f8ef32e58',1,'CodeRacer::usonic_measure_us()'],['../d6/dfc/group__lowerlevelusmeths.html#ga1f3401ef472cb11997e7dc98ef3e2424',1,'CodeRacer::usonic_measure_us(unsigned long max_echo_run_time_us)']]], - ['usonic_5fset_5fstop_5fdistance_5fcm',['usonic_set_stop_distance_cm',['../db/ddd/group__lowerlevelusgetters.html#gaa7c5a6563a5736ed38d12f616de480df',1,'CodeRacer']]], - ['usonic_5fset_5fstop_5fdistance_5fus',['usonic_set_stop_distance_us',['../db/ddd/group__lowerlevelusgetters.html#ga2f06c193ae86c5b1cba450caf5adf146',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/close.png b/Doku/Doxygen/html/search/close.png deleted file mode 100644 index 9342d3d..0000000 Binary files a/Doku/Doxygen/html/search/close.png and /dev/null differ diff --git a/Doku/Doxygen/html/search/functions_0.html b/Doku/Doxygen/html/search/functions_0.html deleted file mode 100644 index 4e6d87d..0000000 --- a/Doku/Doxygen/html/search/functions_0.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/functions_0.js b/Doku/Doxygen/html/search/functions_0.js deleted file mode 100644 index 8c13bd9..0000000 --- a/Doku/Doxygen/html/search/functions_0.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['drive_5fbackward',['drive_backward',['../d2/d40/group__higherlevelmeths.html#ga98aa8a5a46f769d59e6c1067c8418cfb',1,'CodeRacer::drive_backward()'],['../d2/d40/group__higherlevelmeths.html#ga6cd8356ac76360b014db6170276b6b30',1,'CodeRacer::drive_backward(uint8_t left_speed, uint8_t right_speed)']]], - ['drive_5fforward',['drive_forward',['../d2/d40/group__higherlevelmeths.html#ga8be6a850099812153dcf5768d7fc8b8c',1,'CodeRacer::drive_forward()'],['../d2/d40/group__higherlevelmeths.html#gaae6fc379ec43cbe2cb2f63fbd12dbe0d',1,'CodeRacer::drive_forward(uint8_t left_speed, uint8_t right_speed)']]], - ['drive_5fleft_5fspeed',['drive_left_speed',['../d0/d0a/group__lowerleveldrivesgetters.html#ga804a45724f3788fd2fdb9631c66d1377',1,'CodeRacer']]], - ['drive_5fright_5fspeed',['drive_right_speed',['../d0/d0a/group__lowerleveldrivesgetters.html#ga09359a792e3299b1c20f6b99939ea7b3',1,'CodeRacer']]], - ['drives_5fsettings',['drives_settings',['../d1/d8a/group__lowerleveldrivesmeths.html#ga5812df751da5b480240ccd633c515b83',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/functions_1.html b/Doku/Doxygen/html/search/functions_1.html deleted file mode 100644 index b343e2d..0000000 --- a/Doku/Doxygen/html/search/functions_1.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/functions_1.js b/Doku/Doxygen/html/search/functions_1.js deleted file mode 100644 index e1d5c34..0000000 --- a/Doku/Doxygen/html/search/functions_1.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['is_5factive',['is_active',['../d7/d45/group__higherlevelgetters.html#gaa0ab4d6a754a23ea13664a553bcc8ff2',1,'CodeRacer']]], - ['is_5fdriving',['is_driving',['../d7/d45/group__higherlevelgetters.html#ga33dcd96e9b12dec794c56be85ec1ee05',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/functions_2.html b/Doku/Doxygen/html/search/functions_2.html deleted file mode 100644 index ecce2f3..0000000 --- a/Doku/Doxygen/html/search/functions_2.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/functions_2.js b/Doku/Doxygen/html/search/functions_2.js deleted file mode 100644 index 2115eb7..0000000 --- a/Doku/Doxygen/html/search/functions_2.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['kitt',['kitt',['../d8/d7a/group__lowerlevelfun.html#ga3b6f819fb82d910888fbc87abff1470c',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/functions_3.html b/Doku/Doxygen/html/search/functions_3.html deleted file mode 100644 index 15f06ab..0000000 --- a/Doku/Doxygen/html/search/functions_3.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/functions_3.js b/Doku/Doxygen/html/search/functions_3.js deleted file mode 100644 index 01a89fd..0000000 --- a/Doku/Doxygen/html/search/functions_3.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['look_5faround',['look_around',['../d8/d7a/group__lowerlevelfun.html#ga04309a38252639a8eaa43809c04c11c8',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/functions_4.html b/Doku/Doxygen/html/search/functions_4.html deleted file mode 100644 index 8985ff2..0000000 --- a/Doku/Doxygen/html/search/functions_4.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/functions_4.js b/Doku/Doxygen/html/search/functions_4.js deleted file mode 100644 index afc4066..0000000 --- a/Doku/Doxygen/html/search/functions_4.js +++ /dev/null @@ -1,33 +0,0 @@ -var searchData= -[ - ['servo_5fposition',['servo_position',['../d4/df4/group__lowerlevelservogetters.html#ga451b3ecd272e9a11de4b221f8d771432',1,'CodeRacer']]], - ['servo_5fposition_5feta_5fin_5fms',['servo_position_eta_in_ms',['../d4/df4/group__lowerlevelservogetters.html#ga84ba256b9ccdf0e9f4280279da68a509',1,'CodeRacer']]], - ['servo_5fposition_5fset_5fat_5fms',['servo_position_set_at_ms',['../d4/df4/group__lowerlevelservogetters.html#gaeed05a3d4e06adccebdfce207b734b2f',1,'CodeRacer']]], - ['servo_5fset_5fposition',['servo_set_position',['../db/dd5/group__lowerlevelservomeths.html#gab8831340049de6dbddeda997745725e6',1,'CodeRacer']]], - ['servo_5fset_5fposition_5fwait',['servo_set_position_wait',['../db/dd5/group__lowerlevelservomeths.html#ga0149226288bff2290d52ed1cbd674edd',1,'CodeRacer']]], - ['servo_5fset_5fto_5fcenter',['servo_set_to_center',['../db/dd5/group__lowerlevelservomeths.html#gad1f28aa91079e88fc3093e3074edfb32',1,'CodeRacer']]], - ['servo_5fset_5fto_5fleft',['servo_set_to_left',['../db/dd5/group__lowerlevelservomeths.html#gaef7d1903b65a0a8ab4fafdc53080b07d',1,'CodeRacer']]], - ['servo_5fset_5fto_5fright',['servo_set_to_right',['../db/dd5/group__lowerlevelservomeths.html#gaac73bf99cf2d19f7b1987156aa842b74',1,'CodeRacer']]], - ['servo_5fsettings',['servo_settings',['../db/dd5/group__lowerlevelservomeths.html#ga687beb327e20f4d0541d1ac9e29c01c3',1,'CodeRacer']]], - ['servo_5fsweep',['servo_sweep',['../db/dd5/group__lowerlevelservomeths.html#ga1e9afe1f27dfc9796b4c9b3dba245365',1,'CodeRacer']]], - ['set_5factive',['set_active',['../d7/d45/group__higherlevelgetters.html#ga415c69930f291d5e06b7211b31843310',1,'CodeRacer']]], - ['set_5fdrive_5fleft_5fspeed',['set_drive_left_speed',['../d1/d8a/group__lowerleveldrivesmeths.html#ga1ee3da20ec98a821ab97ced070974861',1,'CodeRacer']]], - ['set_5fdrive_5fleft_5fstate',['set_drive_left_state',['../d1/d8a/group__lowerleveldrivesmeths.html#ga1eeb3cb47503c3011562f9c42828fab9',1,'CodeRacer']]], - ['set_5fdrive_5fright_5fspeed',['set_drive_right_speed',['../d1/d8a/group__lowerleveldrivesmeths.html#gaf8805d0d620a2fb78c576f36a2c81073',1,'CodeRacer']]], - ['set_5fdrive_5fright_5fstate',['set_drive_right_state',['../d1/d8a/group__lowerleveldrivesmeths.html#ga1b34ec9cee1f21cd15db310167a2faa5',1,'CodeRacer']]], - ['set_5fdrive_5fspeed',['set_drive_speed',['../d1/d8a/group__lowerleveldrivesmeths.html#ga5d67c84606d5b39996a99fcd6e7eb314',1,'CodeRacer']]], - ['set_5fdrive_5fstate',['set_drive_state',['../d1/d8a/group__lowerleveldrivesmeths.html#ga3b69cf4a718c842fbe758d3f4267214e',1,'CodeRacer']]], - ['set_5fdrives_5fspeed_5fleft_5fright',['set_drives_speed_left_right',['../d1/d8a/group__lowerleveldrivesmeths.html#ga3d3ffb41783d34589e33cf61fed46c70',1,'CodeRacer']]], - ['set_5fdrives_5fstates_5fleft_5fright',['set_drives_states_left_right',['../d1/d8a/group__lowerleveldrivesmeths.html#ga802d2646d9cc0d766e1ac799c7917fa8',1,'CodeRacer']]], - ['set_5fdrives_5fstop_5fleft_5fright',['set_drives_stop_left_right',['../d1/d8a/group__lowerleveldrivesmeths.html#ga61ed9e0415a62a290cc5c59a0f740304',1,'CodeRacer']]], - ['set_5finactive',['set_inactive',['../d7/d45/group__higherlevelgetters.html#ga62f1c0eea56e27d0853cb58f30eb140d',1,'CodeRacer']]], - ['set_5fleds_5fall',['set_leds_all',['../dd/dff/group__lowerlevelledmeths.html#gab4319e66963b1b71a34370d73962fa78',1,'CodeRacer']]], - ['set_5fleds_5fall_5foff',['set_leds_all_off',['../dd/dff/group__lowerlevelledmeths.html#gaa3f2ad08103127f2cb49344c33b666ea',1,'CodeRacer']]], - ['set_5fleds_5fall_5fon',['set_leds_all_on',['../dd/dff/group__lowerlevelledmeths.html#ga0c8b3d6ce992e1dcfd13fd86c9f89846',1,'CodeRacer']]], - ['set_5fleds_5fleft_5fstop_5ffrwd_5fright',['set_leds_left_stop_frwd_right',['../dd/dff/group__lowerlevelledmeths.html#gab2514ca3994de3d64337dd6536fa6ef3',1,'CodeRacer']]], - ['start_5fstop',['start_stop',['../d2/d40/group__higherlevelmeths.html#ga34e2fe2123e76fd844482dfef6c5a9c8',1,'CodeRacer']]], - ['start_5fstop_5fat_5fmin_5fdistance',['start_stop_at_min_distance',['../d2/d40/group__higherlevelmeths.html#ga128683caea019a89bce06f722ba92556',1,'CodeRacer::start_stop_at_min_distance()'],['../d2/d40/group__higherlevelmeths.html#ga64bc1b2a8ed5bc3ec5e706fa70a1385d',1,'CodeRacer::start_stop_at_min_distance(unsigned long min_distance_cm)']]], - ['stop_5fdriving',['stop_driving',['../d2/d40/group__higherlevelmeths.html#ga71df7ac5e41ae776a6c786d3dc36f35a',1,'CodeRacer']]], - ['stop_5fstop_5fat_5fmin_5fdistance',['stop_stop_at_min_distance',['../d2/d40/group__higherlevelmeths.html#gac664109241d08b8dc52db5721f394b22',1,'CodeRacer']]], - ['stopped_5fat_5fmin_5fdistance',['stopped_at_min_distance',['../d7/d45/group__higherlevelgetters.html#gae8b8c0ab24ccb572281785aeca8541e1',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/functions_5.html b/Doku/Doxygen/html/search/functions_5.html deleted file mode 100644 index 0314918..0000000 --- a/Doku/Doxygen/html/search/functions_5.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/functions_5.js b/Doku/Doxygen/html/search/functions_5.js deleted file mode 100644 index cc58d20..0000000 --- a/Doku/Doxygen/html/search/functions_5.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['turn_5fleft',['turn_left',['../d2/d40/group__higherlevelmeths.html#ga86b7caf6ff46e9d1ad90ed507864b175',1,'CodeRacer::turn_left()'],['../d2/d40/group__higherlevelmeths.html#ga30e1ec3fbbc206f93ea66dbf91b5fd95',1,'CodeRacer::turn_left(unsigned long turn_for_ms)'],['../d2/d40/group__higherlevelmeths.html#gae6daa587199e5bf95b1aac675de53b0e',1,'CodeRacer::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)']]], - ['turn_5fleft_5ffor_5fms',['turn_left_for_ms',['../d7/d45/group__higherlevelgetters.html#gaf04fd16ca0e2ace656f9549c43d16459',1,'CodeRacer']]], - ['turn_5fright',['turn_right',['../d2/d40/group__higherlevelmeths.html#ga8969fb2d6e2b5ac44a99197931e6b8da',1,'CodeRacer::turn_right()'],['../d2/d40/group__higherlevelmeths.html#gae1f175aad98d773b0206f483ae0bb4ea',1,'CodeRacer::turn_right(unsigned long turn_for_ms)'],['../d2/d40/group__higherlevelmeths.html#gad10b3457489cc7e25ffb4d64c539528a',1,'CodeRacer::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)']]], - ['turn_5fright_5ffor_5fms',['turn_right_for_ms',['../d7/d45/group__higherlevelgetters.html#gac0698f02f6a21d9d1f5b9cf2820306cf',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/functions_6.html b/Doku/Doxygen/html/search/functions_6.html deleted file mode 100644 index c506123..0000000 --- a/Doku/Doxygen/html/search/functions_6.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/functions_6.js b/Doku/Doxygen/html/search/functions_6.js deleted file mode 100644 index bc703b3..0000000 --- a/Doku/Doxygen/html/search/functions_6.js +++ /dev/null @@ -1,11 +0,0 @@ -var searchData= -[ - ['usonic_5fdistance_5fcm',['usonic_distance_cm',['../db/ddd/group__lowerlevelusgetters.html#gad59842c14196598e55644b2a22621454',1,'CodeRacer']]], - ['usonic_5fdistance_5fus',['usonic_distance_us',['../db/ddd/group__lowerlevelusgetters.html#ga917b90f21e731ef5f690d5198e7f4d3e',1,'CodeRacer']]], - ['usonic_5fmeasure_5fcm',['usonic_measure_cm',['../d6/dfc/group__lowerlevelusmeths.html#ga5f034198a28b069478c454c63dbfa225',1,'CodeRacer::usonic_measure_cm()'],['../d6/dfc/group__lowerlevelusmeths.html#gafdd5c75d7a8e7b7c993e512ee93dde9a',1,'CodeRacer::usonic_measure_cm(unsigned long max_echo_run_time_us)']]], - ['usonic_5fmeasure_5fsingle_5fshot_5fcm',['usonic_measure_single_shot_cm',['../d6/dfc/group__lowerlevelusmeths.html#ga0c00edbbf4a3169613c9ea84d6e7dc13',1,'CodeRacer::usonic_measure_single_shot_cm()'],['../d6/dfc/group__lowerlevelusmeths.html#gab413551ea8a67e1b60eda1671029b645',1,'CodeRacer::usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us)']]], - ['usonic_5fmeasure_5fsingle_5fshot_5fus',['usonic_measure_single_shot_us',['../d6/dfc/group__lowerlevelusmeths.html#gad4309b6da17085575fb0c55559e240b8',1,'CodeRacer::usonic_measure_single_shot_us()'],['../d6/dfc/group__lowerlevelusmeths.html#ga1b5b43372082f5daeee47410a09a590c',1,'CodeRacer::usonic_measure_single_shot_us(unsigned long max_echo_run_time_us)']]], - ['usonic_5fmeasure_5fus',['usonic_measure_us',['../d6/dfc/group__lowerlevelusmeths.html#gaa01602a576fd57609bc7e08f8ef32e58',1,'CodeRacer::usonic_measure_us()'],['../d6/dfc/group__lowerlevelusmeths.html#ga1f3401ef472cb11997e7dc98ef3e2424',1,'CodeRacer::usonic_measure_us(unsigned long max_echo_run_time_us)']]], - ['usonic_5fset_5fstop_5fdistance_5fcm',['usonic_set_stop_distance_cm',['../db/ddd/group__lowerlevelusgetters.html#gaa7c5a6563a5736ed38d12f616de480df',1,'CodeRacer']]], - ['usonic_5fset_5fstop_5fdistance_5fus',['usonic_set_stop_distance_us',['../db/ddd/group__lowerlevelusgetters.html#ga2f06c193ae86c5b1cba450caf5adf146',1,'CodeRacer']]] -]; diff --git a/Doku/Doxygen/html/search/groups_0.html b/Doku/Doxygen/html/search/groups_0.html deleted file mode 100644 index 1ede28d..0000000 --- a/Doku/Doxygen/html/search/groups_0.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/groups_0.js b/Doku/Doxygen/html/search/groups_0.js deleted file mode 100644 index cc2645a..0000000 --- a/Doku/Doxygen/html/search/groups_0.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['getters_20and_20setters',['Getters and setters',['../d7/d45/group__higherlevelgetters.html',1,'']]], - ['getters',['Getters',['../d0/d0a/group__lowerleveldrivesgetters.html',1,'']]], - ['getters',['Getters',['../d4/df4/group__lowerlevelservogetters.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/groups_1.html b/Doku/Doxygen/html/search/groups_1.html deleted file mode 100644 index 3c05216..0000000 --- a/Doku/Doxygen/html/search/groups_1.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/groups_1.js b/Doku/Doxygen/html/search/groups_1.js deleted file mode 100644 index 51cafb8..0000000 --- a/Doku/Doxygen/html/search/groups_1.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['higher_20level_20methods_2c_20setters_20and_20getters',['Higher level methods, setters and getters',['../d9/d80/group__higherlevel.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/groups_2.html b/Doku/Doxygen/html/search/groups_2.html deleted file mode 100644 index 7191495..0000000 --- a/Doku/Doxygen/html/search/groups_2.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/groups_2.js b/Doku/Doxygen/html/search/groups_2.js deleted file mode 100644 index 19a5eac..0000000 --- a/Doku/Doxygen/html/search/groups_2.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['lower_20level_20drives_20methods_20and_20getters',['Lower level drives methods and getters',['../d6/d98/group__lowerleveldrives.html',1,'']]], - ['lower_20level_20fun_20stuff_20methods',['Lower level fun stuff methods',['../d8/d7a/group__lowerlevelfun.html',1,'']]], - ['lower_20level_20led_20methods',['Lower level LED methods',['../d7/d0f/group__lowerlevelled.html',1,'']]], - ['lower_20level_20servo_20drive_20methods_20and_20getters',['Lower level servo drive methods and getters',['../d3/d17/group__lowerlevelservo.html',1,'']]], - ['lower_20level_20ultra_20sonic_20methods_20and_20getters',['Lower level ultra sonic methods and getters',['../da/daf/group__lowerlevelus.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/groups_3.html b/Doku/Doxygen/html/search/groups_3.html deleted file mode 100644 index 3af27ea..0000000 --- a/Doku/Doxygen/html/search/groups_3.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/groups_3.js b/Doku/Doxygen/html/search/groups_3.js deleted file mode 100644 index de441f6..0000000 --- a/Doku/Doxygen/html/search/groups_3.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['methods',['Methods',['../d2/d40/group__higherlevelmeths.html',1,'']]], - ['methods',['Methods',['../d1/d8a/group__lowerleveldrivesmeths.html',1,'']]], - ['methods',['Methods',['../dd/dff/group__lowerlevelledmeths.html',1,'']]], - ['methods',['Methods',['../db/dd5/group__lowerlevelservomeths.html',1,'']]], - ['methods',['Methods',['../d6/dfc/group__lowerlevelusmeths.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/groups_4.html b/Doku/Doxygen/html/search/groups_4.html deleted file mode 100644 index e7abc74..0000000 --- a/Doku/Doxygen/html/search/groups_4.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
-
Loading...
-
- -
Searching...
-
No Matches
- -
- - diff --git a/Doku/Doxygen/html/search/groups_4.js b/Doku/Doxygen/html/search/groups_4.js deleted file mode 100644 index d9b5375..0000000 --- a/Doku/Doxygen/html/search/groups_4.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['setters_20and_20getters',['Setters and getters',['../db/ddd/group__lowerlevelusgetters.html',1,'']]] -]; diff --git a/Doku/Doxygen/html/search/mag_sel.png b/Doku/Doxygen/html/search/mag_sel.png deleted file mode 100644 index 81f6040..0000000 Binary files a/Doku/Doxygen/html/search/mag_sel.png and /dev/null differ diff --git a/Doku/Doxygen/html/search/nomatches.html b/Doku/Doxygen/html/search/nomatches.html deleted file mode 100644 index b1ded27..0000000 --- a/Doku/Doxygen/html/search/nomatches.html +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - -
-
No Matches
-
- - diff --git a/Doku/Doxygen/html/search/search.css b/Doku/Doxygen/html/search/search.css deleted file mode 100644 index 3cf9df9..0000000 --- a/Doku/Doxygen/html/search/search.css +++ /dev/null @@ -1,271 +0,0 @@ -/*---------------- Search Box */ - -#FSearchBox { - float: left; -} - -#MSearchBox { - white-space : nowrap; - float: none; - margin-top: 8px; - right: 0px; - width: 170px; - height: 24px; - z-index: 102; -} - -#MSearchBox .left -{ - display:block; - position:absolute; - left:10px; - width:20px; - height:19px; - background:url('search_l.png') no-repeat; - background-position:right; -} - -#MSearchSelect { - display:block; - position:absolute; - width:20px; - height:19px; -} - -.left #MSearchSelect { - left:4px; -} - -.right #MSearchSelect { - right:5px; -} - -#MSearchField { - display:block; - position:absolute; - height:19px; - background:url('search_m.png') repeat-x; - border:none; - width:115px; - margin-left:20px; - padding-left:4px; - color: #909090; - outline: none; - font: 9pt Arial, Verdana, sans-serif; - -webkit-border-radius: 0px; -} - -#FSearchBox #MSearchField { - margin-left:15px; -} - -#MSearchBox .right { - display:block; - position:absolute; - right:10px; - top:8px; - width:20px; - height:19px; - background:url('search_r.png') no-repeat; - background-position:left; -} - -#MSearchClose { - display: none; - position: absolute; - top: 4px; - background : none; - border: none; - margin: 0px 4px 0px 0px; - padding: 0px 0px; - outline: none; -} - -.left #MSearchClose { - left: 6px; -} - -.right #MSearchClose { - right: 2px; -} - -.MSearchBoxActive #MSearchField { - color: #000000; -} - -/*---------------- Search filter selection */ - -#MSearchSelectWindow { - display: none; - position: absolute; - left: 0; top: 0; - border: 1px solid #90A5CE; - background-color: #F9FAFC; - z-index: 10001; - padding-top: 4px; - padding-bottom: 4px; - -moz-border-radius: 4px; - -webkit-border-top-left-radius: 4px; - -webkit-border-top-right-radius: 4px; - -webkit-border-bottom-left-radius: 4px; - -webkit-border-bottom-right-radius: 4px; - -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -} - -.SelectItem { - font: 8pt Arial, Verdana, sans-serif; - padding-left: 2px; - padding-right: 12px; - border: 0px; -} - -span.SelectionMark { - margin-right: 4px; - font-family: monospace; - outline-style: none; - text-decoration: none; -} - -a.SelectItem { - display: block; - outline-style: none; - color: #000000; - text-decoration: none; - padding-left: 6px; - padding-right: 12px; -} - -a.SelectItem:focus, -a.SelectItem:active { - color: #000000; - outline-style: none; - text-decoration: none; -} - -a.SelectItem:hover { - color: #FFFFFF; - background-color: #3D578C; - outline-style: none; - text-decoration: none; - cursor: pointer; - display: block; -} - -/*---------------- Search results window */ - -iframe#MSearchResults { - width: 60ex; - height: 15em; -} - -#MSearchResultsWindow { - display: none; - position: absolute; - left: 0; top: 0; - border: 1px solid #000; - background-color: #EEF1F7; - z-index:10000; -} - -/* ----------------------------------- */ - - -#SRIndex { - clear:both; - padding-bottom: 15px; -} - -.SREntry { - font-size: 10pt; - padding-left: 1ex; -} - -.SRPage .SREntry { - font-size: 8pt; - padding: 1px 5px; -} - -body.SRPage { - margin: 5px 2px; -} - -.SRChildren { - padding-left: 3ex; padding-bottom: .5em -} - -.SRPage .SRChildren { - display: none; -} - -.SRSymbol { - font-weight: bold; - color: #425E97; - font-family: Arial, Verdana, sans-serif; - text-decoration: none; - outline: none; -} - -a.SRScope { - display: block; - color: #425E97; - font-family: Arial, Verdana, sans-serif; - text-decoration: none; - outline: none; -} - -a.SRSymbol:focus, a.SRSymbol:active, -a.SRScope:focus, a.SRScope:active { - text-decoration: underline; -} - -span.SRScope { - padding-left: 4px; -} - -.SRPage .SRStatus { - padding: 2px 5px; - font-size: 8pt; - font-style: italic; -} - -.SRResult { - display: none; -} - -DIV.searchresults { - margin-left: 10px; - margin-right: 10px; -} - -/*---------------- External search page results */ - -.searchresult { - background-color: #F0F3F8; -} - -.pages b { - color: white; - padding: 5px 5px 3px 5px; - background-image: url("../tab_a.png"); - background-repeat: repeat-x; - text-shadow: 0 1px 1px #000000; -} - -.pages { - line-height: 17px; - margin-left: 4px; - text-decoration: none; -} - -.hl { - font-weight: bold; -} - -#searchresults { - margin-bottom: 20px; -} - -.searchpages { - margin-top: 10px; -} - diff --git a/Doku/Doxygen/html/search/search.js b/Doku/Doxygen/html/search/search.js deleted file mode 100644 index dedce3b..0000000 --- a/Doku/Doxygen/html/search/search.js +++ /dev/null @@ -1,791 +0,0 @@ -function convertToId(search) -{ - var result = ''; - for (i=0;i do a search - { - this.Search(); - } - } - - this.OnSearchSelectKey = function(evt) - { - var e = (evt) ? evt : window.event; // for IE - if (e.keyCode==40 && this.searchIndex0) // Up - { - this.searchIndex--; - this.OnSelectItem(this.searchIndex); - } - else if (e.keyCode==13 || e.keyCode==27) - { - this.OnSelectItem(this.searchIndex); - this.CloseSelectionWindow(); - this.DOMSearchField().focus(); - } - return false; - } - - // --------- Actions - - // Closes the results window. - this.CloseResultsWindow = function() - { - this.DOMPopupSearchResultsWindow().style.display = 'none'; - this.DOMSearchClose().style.display = 'none'; - this.Activate(false); - } - - this.CloseSelectionWindow = function() - { - this.DOMSearchSelectWindow().style.display = 'none'; - } - - // Performs a search. - this.Search = function() - { - this.keyTimeout = 0; - - // strip leading whitespace - var searchValue = this.DOMSearchField().value.replace(/^ +/, ""); - - var code = searchValue.toLowerCase().charCodeAt(0); - var idxChar = searchValue.substr(0, 1).toLowerCase(); - if ( 0xD800 <= code && code <= 0xDBFF && searchValue > 1) // surrogate pair - { - idxChar = searchValue.substr(0, 2); - } - - var resultsPage; - var resultsPageWithSearch; - var hasResultsPage; - - var idx = indexSectionsWithContent[this.searchIndex].indexOf(idxChar); - if (idx!=-1) - { - var hexCode=idx.toString(16); - resultsPage = this.resultsPath + '/' + indexSectionNames[this.searchIndex] + '_' + hexCode + '.html'; - resultsPageWithSearch = resultsPage+'?'+escape(searchValue); - hasResultsPage = true; - } - else // nothing available for this search term - { - resultsPage = this.resultsPath + '/nomatches.html'; - resultsPageWithSearch = resultsPage; - hasResultsPage = false; - } - - window.frames.MSearchResults.location = resultsPageWithSearch; - var domPopupSearchResultsWindow = this.DOMPopupSearchResultsWindow(); - - if (domPopupSearchResultsWindow.style.display!='block') - { - var domSearchBox = this.DOMSearchBox(); - this.DOMSearchClose().style.display = 'inline'; - if (this.insideFrame) - { - var domPopupSearchResults = this.DOMPopupSearchResults(); - domPopupSearchResultsWindow.style.position = 'relative'; - domPopupSearchResultsWindow.style.display = 'block'; - var width = document.body.clientWidth - 8; // the -8 is for IE :-( - domPopupSearchResultsWindow.style.width = width + 'px'; - domPopupSearchResults.style.width = width + 'px'; - } - else - { - var domPopupSearchResults = this.DOMPopupSearchResults(); - var left = getXPos(domSearchBox) + 150; // domSearchBox.offsetWidth; - var top = getYPos(domSearchBox) + 20; // domSearchBox.offsetHeight + 1; - domPopupSearchResultsWindow.style.display = 'block'; - left -= domPopupSearchResults.offsetWidth; - domPopupSearchResultsWindow.style.top = top + 'px'; - domPopupSearchResultsWindow.style.left = left + 'px'; - } - } - - this.lastSearchValue = searchValue; - this.lastResultsPage = resultsPage; - } - - // -------- Activation Functions - - // Activates or deactivates the search panel, resetting things to - // their default values if necessary. - this.Activate = function(isActive) - { - if (isActive || // open it - this.DOMPopupSearchResultsWindow().style.display == 'block' - ) - { - this.DOMSearchBox().className = 'MSearchBoxActive'; - - var searchField = this.DOMSearchField(); - - if (searchField.value == this.searchLabel) // clear "Search" term upon entry - { - searchField.value = ''; - this.searchActive = true; - } - } - else if (!isActive) // directly remove the panel - { - this.DOMSearchBox().className = 'MSearchBoxInactive'; - this.DOMSearchField().value = this.searchLabel; - this.searchActive = false; - this.lastSearchValue = '' - this.lastResultsPage = ''; - } - } -} - -// ----------------------------------------------------------------------- - -// The class that handles everything on the search results page. -function SearchResults(name) -{ - // The number of matches from the last run of . - this.lastMatchCount = 0; - this.lastKey = 0; - this.repeatOn = false; - - // Toggles the visibility of the passed element ID. - this.FindChildElement = function(id) - { - var parentElement = document.getElementById(id); - var element = parentElement.firstChild; - - while (element && element!=parentElement) - { - if (element.nodeName == 'DIV' && element.className == 'SRChildren') - { - return element; - } - - if (element.nodeName == 'DIV' && element.hasChildNodes()) - { - element = element.firstChild; - } - else if (element.nextSibling) - { - element = element.nextSibling; - } - else - { - do - { - element = element.parentNode; - } - while (element && element!=parentElement && !element.nextSibling); - - if (element && element!=parentElement) - { - element = element.nextSibling; - } - } - } - } - - this.Toggle = function(id) - { - var element = this.FindChildElement(id); - if (element) - { - if (element.style.display == 'block') - { - element.style.display = 'none'; - } - else - { - element.style.display = 'block'; - } - } - } - - // Searches for the passed string. If there is no parameter, - // it takes it from the URL query. - // - // Always returns true, since other documents may try to call it - // and that may or may not be possible. - this.Search = function(search) - { - if (!search) // get search word from URL - { - search = window.location.search; - search = search.substring(1); // Remove the leading '?' - search = unescape(search); - } - - search = search.replace(/^ +/, ""); // strip leading spaces - search = search.replace(/ +$/, ""); // strip trailing spaces - search = search.toLowerCase(); - search = convertToId(search); - - var resultRows = document.getElementsByTagName("div"); - var matches = 0; - - var i = 0; - while (i < resultRows.length) - { - var row = resultRows.item(i); - if (row.className == "SRResult") - { - var rowMatchName = row.id.toLowerCase(); - rowMatchName = rowMatchName.replace(/^sr\d*_/, ''); // strip 'sr123_' - - if (search.length<=rowMatchName.length && - rowMatchName.substr(0, search.length)==search) - { - row.style.display = 'block'; - matches++; - } - else - { - row.style.display = 'none'; - } - } - i++; - } - document.getElementById("Searching").style.display='none'; - if (matches == 0) // no results - { - document.getElementById("NoMatches").style.display='block'; - } - else // at least one result - { - document.getElementById("NoMatches").style.display='none'; - } - this.lastMatchCount = matches; - return true; - } - - // return the first item with index index or higher that is visible - this.NavNext = function(index) - { - var focusItem; - while (1) - { - var focusName = 'Item'+index; - focusItem = document.getElementById(focusName); - if (focusItem && focusItem.parentNode.parentNode.style.display=='block') - { - break; - } - else if (!focusItem) // last element - { - break; - } - focusItem=null; - index++; - } - return focusItem; - } - - this.NavPrev = function(index) - { - var focusItem; - while (1) - { - var focusName = 'Item'+index; - focusItem = document.getElementById(focusName); - if (focusItem && focusItem.parentNode.parentNode.style.display=='block') - { - break; - } - else if (!focusItem) // last element - { - break; - } - focusItem=null; - index--; - } - return focusItem; - } - - this.ProcessKeys = function(e) - { - if (e.type == "keydown") - { - this.repeatOn = false; - this.lastKey = e.keyCode; - } - else if (e.type == "keypress") - { - if (!this.repeatOn) - { - if (this.lastKey) this.repeatOn = true; - return false; // ignore first keypress after keydown - } - } - else if (e.type == "keyup") - { - this.lastKey = 0; - this.repeatOn = false; - } - return this.lastKey!=0; - } - - this.Nav = function(evt,itemIndex) - { - var e = (evt) ? evt : window.event; // for IE - if (e.keyCode==13) return true; - if (!this.ProcessKeys(e)) return false; - - if (this.lastKey==38) // Up - { - var newIndex = itemIndex-1; - var focusItem = this.NavPrev(newIndex); - if (focusItem) - { - var child = this.FindChildElement(focusItem.parentNode.parentNode.id); - if (child && child.style.display == 'block') // children visible - { - var n=0; - var tmpElem; - while (1) // search for last child - { - tmpElem = document.getElementById('Item'+newIndex+'_c'+n); - if (tmpElem) - { - focusItem = tmpElem; - } - else // found it! - { - break; - } - n++; - } - } - } - if (focusItem) - { - focusItem.focus(); - } - else // return focus to search field - { - parent.document.getElementById("MSearchField").focus(); - } - } - else if (this.lastKey==40) // Down - { - var newIndex = itemIndex+1; - var focusItem; - var item = document.getElementById('Item'+itemIndex); - var elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem && elem.style.display == 'block') // children visible - { - focusItem = document.getElementById('Item'+itemIndex+'_c0'); - } - if (!focusItem) focusItem = this.NavNext(newIndex); - if (focusItem) focusItem.focus(); - } - else if (this.lastKey==39) // Right - { - var item = document.getElementById('Item'+itemIndex); - var elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem) elem.style.display = 'block'; - } - else if (this.lastKey==37) // Left - { - var item = document.getElementById('Item'+itemIndex); - var elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem) elem.style.display = 'none'; - } - else if (this.lastKey==27) // Escape - { - parent.searchBox.CloseResultsWindow(); - parent.document.getElementById("MSearchField").focus(); - } - else if (this.lastKey==13) // Enter - { - return true; - } - return false; - } - - this.NavChild = function(evt,itemIndex,childIndex) - { - var e = (evt) ? evt : window.event; // for IE - if (e.keyCode==13) return true; - if (!this.ProcessKeys(e)) return false; - - if (this.lastKey==38) // Up - { - if (childIndex>0) - { - var newIndex = childIndex-1; - document.getElementById('Item'+itemIndex+'_c'+newIndex).focus(); - } - else // already at first child, jump to parent - { - document.getElementById('Item'+itemIndex).focus(); - } - } - else if (this.lastKey==40) // Down - { - var newIndex = childIndex+1; - var elem = document.getElementById('Item'+itemIndex+'_c'+newIndex); - if (!elem) // last child, jump to parent next parent - { - elem = this.NavNext(itemIndex+1); - } - if (elem) - { - elem.focus(); - } - } - else if (this.lastKey==27) // Escape - { - parent.searchBox.CloseResultsWindow(); - parent.document.getElementById("MSearchField").focus(); - } - else if (this.lastKey==13) // Enter - { - return true; - } - return false; - } -} - -function setKeyActions(elem,action) -{ - elem.setAttribute('onkeydown',action); - elem.setAttribute('onkeypress',action); - elem.setAttribute('onkeyup',action); -} - -function setClassAttr(elem,attr) -{ - elem.setAttribute('class',attr); - elem.setAttribute('className',attr); -} - -function createResults() -{ - var results = document.getElementById("SRResults"); - for (var e=0; eli>h1,.sm>li>h2,.sm>li>h3,.sm>li>h4,.sm>li>h5,.sm>li>h6{margin:0;padding:0}.sm ul{display:none}.sm li,.sm a{position:relative}.sm a{display:block}.sm a.disabled{cursor:not-allowed}.sm:after{content:"\00a0";display:block;height:0;font:0/0 serif;clear:both;visibility:hidden;overflow:hidden}.sm,.sm *,.sm *:before,.sm *:after{-moz-box-sizing:border-box;-webkit-box-sizing:border-box;box-sizing:border-box}#doc-content{overflow:auto;display:block;padding:0;margin:0;-webkit-overflow-scrolling:touch}.sm-dox{background-image:url("tab_b.png")}.sm-dox a,.sm-dox a:focus,.sm-dox a:hover,.sm-dox a:active{padding:0 12px;padding-right:43px;font-family:"Lucida Grande","Geneva","Helvetica",Arial,sans-serif;font-size:13px;font-weight:bold;line-height:36px;text-decoration:none;text-shadow:0 1px 1px rgba(255,255,255,0.9);color:#283a5d;outline:0}.sm-dox a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:white;text-shadow:0 1px 1px black}.sm-dox a.current{color:#d23600}.sm-dox a.disabled{color:#bbb}.sm-dox a span.sub-arrow{position:absolute;top:50%;margin-top:-14px;left:auto;right:3px;width:28px;height:28px;overflow:hidden;font:bold 12px/28px monospace!important;text-align:center;text-shadow:none;background:rgba(255,255,255,0.5);-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox a.highlighted span.sub-arrow:before{display:block;content:'-'}.sm-dox>li:first-child>a,.sm-dox>li:first-child>:not(ul) a{-moz-border-radius:5px 5px 0 0;-webkit-border-radius:5px;border-radius:5px 5px 0 0}.sm-dox>li:last-child>a,.sm-dox>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul{-moz-border-radius:0 0 5px 5px;-webkit-border-radius:0;border-radius:0 0 5px 5px}.sm-dox>li:last-child>a.highlighted,.sm-dox>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted{-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox ul{background:rgba(162,162,162,0.1)}.sm-dox ul a,.sm-dox ul a:focus,.sm-dox ul a:hover,.sm-dox ul a:active{font-size:12px;border-left:8px solid transparent;line-height:36px;text-shadow:none;background-color:white;background-image:none}.sm-dox ul a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:white;text-shadow:0 1px 1px black}.sm-dox ul ul a,.sm-dox ul ul a:hover,.sm-dox ul ul a:focus,.sm-dox ul ul a:active{border-left:16px solid transparent}.sm-dox ul ul ul a,.sm-dox ul ul ul a:hover,.sm-dox ul ul ul a:focus,.sm-dox ul ul ul a:active{border-left:24px solid transparent}.sm-dox ul ul ul ul a,.sm-dox ul ul ul ul a:hover,.sm-dox ul ul ul ul a:focus,.sm-dox ul ul ul ul a:active{border-left:32px solid transparent}.sm-dox ul ul ul ul ul a,.sm-dox ul ul ul ul ul a:hover,.sm-dox ul ul ul ul ul a:focus,.sm-dox ul ul ul ul ul a:active{border-left:40px solid transparent}@media(min-width:768px){.sm-dox ul{position:absolute;width:12em}.sm-dox li{float:left}.sm-dox.sm-rtl li{float:right}.sm-dox ul li,.sm-dox.sm-rtl ul li,.sm-dox.sm-vertical li{float:none}.sm-dox a{white-space:nowrap}.sm-dox ul a,.sm-dox.sm-vertical a{white-space:normal}.sm-dox .sm-nowrap>li>a,.sm-dox .sm-nowrap>li>:not(ul) a{white-space:nowrap}.sm-dox{padding:0 10px;background-image:url("tab_b.png");line-height:36px}.sm-dox a span.sub-arrow{top:50%;margin-top:-2px;right:12px;width:0;height:0;border-width:4px;border-style:solid dashed dashed dashed;border-color:#283a5d transparent transparent transparent;background:transparent;-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox a,.sm-dox a:focus,.sm-dox a:active,.sm-dox a:hover,.sm-dox a.highlighted{padding:0 12px;background-image:url("tab_s.png");background-repeat:no-repeat;background-position:right;-moz-border-radius:0!important;-webkit-border-radius:0;border-radius:0!important}.sm-dox a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:white;text-shadow:0 1px 1px black}.sm-dox a:hover span.sub-arrow{border-color:white transparent transparent transparent}.sm-dox a.has-submenu{padding-right:24px}.sm-dox li{border-top:0}.sm-dox>li>ul:before,.sm-dox>li>ul:after{content:'';position:absolute;top:-18px;left:30px;width:0;height:0;overflow:hidden;border-width:9px;border-style:dashed dashed solid dashed;border-color:transparent transparent #bbb transparent}.sm-dox>li>ul:after{top:-16px;left:31px;border-width:8px;border-color:transparent transparent #fff transparent}.sm-dox ul{border:1px solid #bbb;padding:5px 0;background:#fff;-moz-border-radius:5px!important;-webkit-border-radius:5px;border-radius:5px!important;-moz-box-shadow:0 5px 9px rgba(0,0,0,0.2);-webkit-box-shadow:0 5px 9px rgba(0,0,0,0.2);box-shadow:0 5px 9px rgba(0,0,0,0.2)}.sm-dox ul a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-color:transparent transparent transparent #555;border-style:dashed dashed dashed solid}.sm-dox ul a,.sm-dox ul a:hover,.sm-dox ul a:focus,.sm-dox ul a:active,.sm-dox ul a.highlighted{color:#555;background-image:none;border:0!important;color:#555;background-image:none}.sm-dox ul a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:white;text-shadow:0 1px 1px black}.sm-dox ul a:hover span.sub-arrow{border-color:transparent transparent transparent white}.sm-dox span.scroll-up,.sm-dox span.scroll-down{position:absolute;display:none;visibility:hidden;overflow:hidden;background:#fff;height:36px}.sm-dox span.scroll-up:hover,.sm-dox span.scroll-down:hover{background:#eee}.sm-dox span.scroll-up:hover span.scroll-up-arrow,.sm-dox span.scroll-up:hover span.scroll-down-arrow{border-color:transparent transparent #d23600 transparent}.sm-dox span.scroll-down:hover span.scroll-down-arrow{border-color:#d23600 transparent transparent transparent}.sm-dox span.scroll-up-arrow,.sm-dox span.scroll-down-arrow{position:absolute;top:0;left:50%;margin-left:-6px;width:0;height:0;overflow:hidden;border-width:6px;border-style:dashed dashed solid dashed;border-color:transparent transparent #555 transparent}.sm-dox span.scroll-down-arrow{top:8px;border-style:solid dashed dashed dashed;border-color:#555 transparent transparent transparent}.sm-dox.sm-rtl a.has-submenu{padding-right:12px;padding-left:24px}.sm-dox.sm-rtl a span.sub-arrow{right:auto;left:12px}.sm-dox.sm-rtl.sm-vertical a.has-submenu{padding:10px 20px}.sm-dox.sm-rtl.sm-vertical a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-rtl>li>ul:before{left:auto;right:30px}.sm-dox.sm-rtl>li>ul:after{left:auto;right:31px}.sm-dox.sm-rtl ul a.has-submenu{padding:10px 20px!important}.sm-dox.sm-rtl ul a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-vertical{padding:10px 0;-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox.sm-vertical a{padding:10px 20px}.sm-dox.sm-vertical a:hover,.sm-dox.sm-vertical a:focus,.sm-dox.sm-vertical a:active,.sm-dox.sm-vertical a.highlighted{background:#fff}.sm-dox.sm-vertical a.disabled{background-image:url("tab_b.png")}.sm-dox.sm-vertical a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-style:dashed dashed dashed solid;border-color:transparent transparent transparent #555}.sm-dox.sm-vertical>li>ul:before,.sm-dox.sm-vertical>li>ul:after{display:none}.sm-dox.sm-vertical ul a{padding:10px 20px}.sm-dox.sm-vertical ul a:hover,.sm-dox.sm-vertical ul a:focus,.sm-dox.sm-vertical ul a:active,.sm-dox.sm-vertical ul a.highlighted{background:#eee}.sm-dox.sm-vertical ul a.disabled{background:#fff}} \ No newline at end of file diff --git a/Doku/Doxygen/latex/Makefile b/Doku/Doxygen/latex/Makefile deleted file mode 100644 index 8cc3866..0000000 --- a/Doku/Doxygen/latex/Makefile +++ /dev/null @@ -1,21 +0,0 @@ -all: refman.pdf - -pdf: refman.pdf - -refman.pdf: clean refman.tex - pdflatex refman - makeindex refman.idx - pdflatex refman - latex_count=8 ; \ - while egrep -s 'Rerun (LaTeX|to get cross-references right)' refman.log && [ $$latex_count -gt 0 ] ;\ - do \ - echo "Rerunning latex...." ;\ - pdflatex refman ;\ - latex_count=`expr $$latex_count - 1` ;\ - done - makeindex refman.idx - pdflatex refman - - -clean: - rm -f *.ps *.dvi *.aux *.toc *.idx *.ind *.ilg *.log *.out *.brf *.blg *.bbl refman.pdf diff --git a/Doku/Doxygen/latex/coderace_logo.JPG b/Doku/Doxygen/latex/coderace_logo.JPG deleted file mode 100644 index 0b58ee1..0000000 Binary files a/Doku/Doxygen/latex/coderace_logo.JPG and /dev/null differ diff --git a/Doku/Doxygen/latex/d0/d0a/group__lowerleveldrivesgetters.tex b/Doku/Doxygen/latex/d0/d0a/group__lowerleveldrivesgetters.tex deleted file mode 100644 index 9c22894..0000000 --- a/Doku/Doxygen/latex/d0/d0a/group__lowerleveldrivesgetters.tex +++ /dev/null @@ -1,61 +0,0 @@ -\hypertarget{group__lowerleveldrivesgetters}{}\section{Getters} -\label{group__lowerleveldrivesgetters}\index{Getters@{Getters}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -uint8\+\_\+t \hyperlink{group__lowerleveldrivesgetters_ga09359a792e3299b1c20f6b99939ea7b3}{Code\+Racer\+::drive\+\_\+right\+\_\+speed} () -\begin{DoxyCompactList}\small\item\em Get the setting for the speed of the right side drive. \end{DoxyCompactList}\item -uint8\+\_\+t \hyperlink{group__lowerleveldrivesgetters_ga804a45724f3788fd2fdb9631c66d1377}{Code\+Racer\+::drive\+\_\+left\+\_\+speed} () -\begin{DoxyCompactList}\small\item\em Get the setting for the speed of the left side drive. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerleveldrivesgetters_ga09359a792e3299b1c20f6b99939ea7b3}\label{group__lowerleveldrivesgetters_ga09359a792e3299b1c20f6b99939ea7b3}} -\index{Getters@{Getters}!drive\+\_\+right\+\_\+speed@{drive\+\_\+right\+\_\+speed}} -\index{drive\+\_\+right\+\_\+speed@{drive\+\_\+right\+\_\+speed}!Getters@{Getters}} -\subsubsection{\texorpdfstring{drive\+\_\+right\+\_\+speed()}{drive\_right\_speed()}} -{\footnotesize\ttfamily uint8\+\_\+t Code\+Racer\+::drive\+\_\+right\+\_\+speed (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the setting for the speed of the right side drive. - -\begin{DoxyReturn}{Returns} -Speed of the right side drive -\end{DoxyReturn} - - -Definition at line 994 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -994 \{ -995 \textcolor{keywordflow}{return} \_drive\_right\_speed; -996 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesgetters_ga804a45724f3788fd2fdb9631c66d1377}\label{group__lowerleveldrivesgetters_ga804a45724f3788fd2fdb9631c66d1377}} -\index{Getters@{Getters}!drive\+\_\+left\+\_\+speed@{drive\+\_\+left\+\_\+speed}} -\index{drive\+\_\+left\+\_\+speed@{drive\+\_\+left\+\_\+speed}!Getters@{Getters}} -\subsubsection{\texorpdfstring{drive\+\_\+left\+\_\+speed()}{drive\_left\_speed()}} -{\footnotesize\ttfamily uint8\+\_\+t Code\+Racer\+::drive\+\_\+left\+\_\+speed (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the setting for the speed of the left side drive. - -\begin{DoxyReturn}{Returns} -Speed of the left side drive -\end{DoxyReturn} - - -Definition at line 1001 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -1001 \{ -1002 \textcolor{keywordflow}{return}(\_drive\_left\_speed); -1003 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/d1/d8a/group__lowerleveldrivesmeths.tex b/Doku/Doxygen/latex/d1/d8a/group__lowerleveldrivesmeths.tex deleted file mode 100644 index a2da2bb..0000000 --- a/Doku/Doxygen/latex/d1/d8a/group__lowerleveldrivesmeths.tex +++ /dev/null @@ -1,341 +0,0 @@ -\hypertarget{group__lowerleveldrivesmeths}{}\section{Methods} -\label{group__lowerleveldrivesmeths}\index{Methods@{Methods}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -void \hyperlink{group__lowerleveldrivesmeths_ga5812df751da5b480240ccd633c515b83}{Code\+Racer\+::drives\+\_\+settings} (uint8\+\_\+t drive\+\_\+left\+\_\+speed, uint8\+\_\+t drive\+\_\+right\+\_\+speed, unsigned long turn\+\_\+left\+\_\+ms, unsigned long turn\+\_\+right\+\_\+ms) -\begin{DoxyCompactList}\small\item\em Overwrites some drive settings. This will replace the defaults set by the values in the header file. \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga61ed9e0415a62a290cc5c59a0f740304}{Code\+Racer\+::set\+\_\+drives\+\_\+stop\+\_\+left\+\_\+right} () -\begin{DoxyCompactList}\small\item\em Stopps both drives. \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga802d2646d9cc0d766e1ac799c7917fa8}{Code\+Racer\+::set\+\_\+drives\+\_\+states\+\_\+left\+\_\+right} (drivestate stateleft, drivestate stateright) -\begin{DoxyCompactList}\small\item\em Sets both of the drives to a specified drivestate (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga1eeb3cb47503c3011562f9c42828fab9}{Code\+Racer\+::set\+\_\+drive\+\_\+left\+\_\+state} (drivestate state) -\begin{DoxyCompactList}\small\item\em Sets the left side drive to the specified drivestate (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga1b34ec9cee1f21cd15db310167a2faa5}{Code\+Racer\+::set\+\_\+drive\+\_\+right\+\_\+state} (drivestate state) -\begin{DoxyCompactList}\small\item\em Sets the right side drive to the specified drivestate (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga3b69cf4a718c842fbe758d3f4267214e}{Code\+Racer\+::set\+\_\+drive\+\_\+state} (drivestate state, uint8\+\_\+t frwdpin, uint8\+\_\+t backpin) -\begin{DoxyCompactList}\small\item\em Sets the specified drivestate for the drive connected to the sepecified pins (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga3d3ffb41783d34589e33cf61fed46c70}{Code\+Racer\+::set\+\_\+drives\+\_\+speed\+\_\+left\+\_\+right} (uint8\+\_\+t speedleft, uint8\+\_\+t speedright) -\begin{DoxyCompactList}\small\item\em Sets the speed for both of the drives. \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga1ee3da20ec98a821ab97ced070974861}{Code\+Racer\+::set\+\_\+drive\+\_\+left\+\_\+speed} (uint8\+\_\+t speed) -\begin{DoxyCompactList}\small\item\em Sets the speed for the left side drive. \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_gaf8805d0d620a2fb78c576f36a2c81073}{Code\+Racer\+::set\+\_\+drive\+\_\+right\+\_\+speed} (uint8\+\_\+t speed) -\begin{DoxyCompactList}\small\item\em Sets the speed for the right side drive. \end{DoxyCompactList}\item -void \hyperlink{group__lowerleveldrivesmeths_ga5d67c84606d5b39996a99fcd6e7eb314}{Code\+Racer\+::set\+\_\+drive\+\_\+speed} (uint8\+\_\+t speed, uint8\+\_\+t enablepin) -\begin{DoxyCompactList}\small\item\em Sets the speed for the drive of the enable pin connected to the specified pin. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga5812df751da5b480240ccd633c515b83}\label{group__lowerleveldrivesmeths_ga5812df751da5b480240ccd633c515b83}} -\index{Methods@{Methods}!drives\+\_\+settings@{drives\+\_\+settings}} -\index{drives\+\_\+settings@{drives\+\_\+settings}!Methods@{Methods}} -\subsubsection{\texorpdfstring{drives\+\_\+settings()}{drives\_settings()}} -{\footnotesize\ttfamily void Code\+Racer\+::drives\+\_\+settings (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{drive\+\_\+left\+\_\+speed, }\item[{uint8\+\_\+t}]{drive\+\_\+right\+\_\+speed, }\item[{unsigned long}]{turn\+\_\+left\+\_\+for\+\_\+ms, }\item[{unsigned long}]{turn\+\_\+right\+\_\+for\+\_\+ms }\end{DoxyParamCaption})} - - - -Overwrites some drive settings. This will replace the defaults set by the values in the header file. - - -\begin{DoxyParams}{Parameters} -{\em drive\+\_\+left\+\_\+speed} & Speed of the left side drive \\ -\hline -{\em drive\+\_\+right\+\_\+speed} & Speed of the right side drive \\ -\hline -{\em turn\+\_\+left\+\_\+for\+\_\+ms} & Time in ms the racer will turn to the left around its center if turn\+\_\+left() is called \\ -\hline -{\em turn\+\_\+right\+\_\+for\+\_\+ms} & Time in ms the racer will turn to the right around its center if turn\+\_\+right() is called \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 878 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -879 \{ -880 \_drive\_left\_speed = drive\_left\_speed; -881 \_drive\_right\_speed = drive\_right\_speed; -882 \_turn\_left\_for\_ms = turn\_left\_for\_ms; -883 \_turn\_right\_for\_ms = turn\_right\_for\_ms; -884 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga61ed9e0415a62a290cc5c59a0f740304}\label{group__lowerleveldrivesmeths_ga61ed9e0415a62a290cc5c59a0f740304}} -\index{Methods@{Methods}!set\+\_\+drives\+\_\+stop\+\_\+left\+\_\+right@{set\+\_\+drives\+\_\+stop\+\_\+left\+\_\+right}} -\index{set\+\_\+drives\+\_\+stop\+\_\+left\+\_\+right@{set\+\_\+drives\+\_\+stop\+\_\+left\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drives\+\_\+stop\+\_\+left\+\_\+right()}{set\_drives\_stop\_left\_right()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drives\+\_\+stop\+\_\+left\+\_\+right (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Stopps both drives. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 889 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -889 \{ -890 set\_drive\_left\_state(DRIVESTOP); -891 set\_drive\_right\_state(DRIVESTOP); -892 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga802d2646d9cc0d766e1ac799c7917fa8}\label{group__lowerleveldrivesmeths_ga802d2646d9cc0d766e1ac799c7917fa8}} -\index{Methods@{Methods}!set\+\_\+drives\+\_\+states\+\_\+left\+\_\+right@{set\+\_\+drives\+\_\+states\+\_\+left\+\_\+right}} -\index{set\+\_\+drives\+\_\+states\+\_\+left\+\_\+right@{set\+\_\+drives\+\_\+states\+\_\+left\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drives\+\_\+states\+\_\+left\+\_\+right()}{set\_drives\_states\_left\_right()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drives\+\_\+states\+\_\+left\+\_\+right (\begin{DoxyParamCaption}\item[{drivestate}]{stateleft, }\item[{drivestate}]{stateright }\end{DoxyParamCaption})} - - - -Sets both of the drives to a specified drivestate (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) - - -\begin{DoxyParams}{Parameters} -{\em stateleft} & drivestate to set for the left side drive \\ -\hline -{\em stateright} & drivestate to set for the right side drive \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 899 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -899 \{ -900 set\_drive\_left\_state(stateleft); -901 set\_drive\_right\_state(stateright); -902 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga1eeb3cb47503c3011562f9c42828fab9}\label{group__lowerleveldrivesmeths_ga1eeb3cb47503c3011562f9c42828fab9}} -\index{Methods@{Methods}!set\+\_\+drive\+\_\+left\+\_\+state@{set\+\_\+drive\+\_\+left\+\_\+state}} -\index{set\+\_\+drive\+\_\+left\+\_\+state@{set\+\_\+drive\+\_\+left\+\_\+state}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drive\+\_\+left\+\_\+state()}{set\_drive\_left\_state()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drive\+\_\+left\+\_\+state (\begin{DoxyParamCaption}\item[{drivestate}]{state }\end{DoxyParamCaption})} - - - -Sets the left side drive to the specified drivestate (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) - - -\begin{DoxyParams}{Parameters} -{\em state} & drivestate to set for the left side drive \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 908 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -908 \{ -909 set\_drive\_state(state, \_drive\_left\_frwd\_pin, \_drive\_left\_back\_pin); -910 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga1b34ec9cee1f21cd15db310167a2faa5}\label{group__lowerleveldrivesmeths_ga1b34ec9cee1f21cd15db310167a2faa5}} -\index{Methods@{Methods}!set\+\_\+drive\+\_\+right\+\_\+state@{set\+\_\+drive\+\_\+right\+\_\+state}} -\index{set\+\_\+drive\+\_\+right\+\_\+state@{set\+\_\+drive\+\_\+right\+\_\+state}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drive\+\_\+right\+\_\+state()}{set\_drive\_right\_state()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drive\+\_\+right\+\_\+state (\begin{DoxyParamCaption}\item[{drivestate}]{state }\end{DoxyParamCaption})} - - - -Sets the right side drive to the specified drivestate (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) - - -\begin{DoxyParams}{Parameters} -{\em state} & drivestate to set for the right side drive \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 916 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -916 \{ -917 set\_drive\_state(state, \_drive\_right\_frwd\_pin, \_drive\_right\_back\_pin); -918 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga3b69cf4a718c842fbe758d3f4267214e}\label{group__lowerleveldrivesmeths_ga3b69cf4a718c842fbe758d3f4267214e}} -\index{Methods@{Methods}!set\+\_\+drive\+\_\+state@{set\+\_\+drive\+\_\+state}} -\index{set\+\_\+drive\+\_\+state@{set\+\_\+drive\+\_\+state}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drive\+\_\+state()}{set\_drive\_state()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drive\+\_\+state (\begin{DoxyParamCaption}\item[{drivestate}]{state, }\item[{uint8\+\_\+t}]{frwdpin, }\item[{uint8\+\_\+t}]{backpin }\end{DoxyParamCaption})} - - - -Sets the specified drivestate for the drive connected to the sepecified pins (D\+R\+I\+V\+E\+S\+T\+OP, D\+R\+I\+V\+E\+F\+R\+WD, D\+R\+I\+V\+E\+B\+A\+CK) - - -\begin{DoxyParams}{Parameters} -{\em state} & drivestate to set for the connected drive \\ -\hline -{\em frwdpin} & Pin the forward signal of the drive device driver is connected at \\ -\hline -{\em backpin} & Pin the backward signal of the drive device driver is connected at \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 926 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -926 \{ -927 \textcolor{keywordflow}{switch} (state) \{ -928 \textcolor{keywordflow}{case} DRIVESTOP: -929 digitalWrite(frwdpin, LOW); -930 digitalWrite(backpin, LOW); -931 \textcolor{keywordflow}{break}; -932 \textcolor{keywordflow}{case} DRIVEFRWD: -933 digitalWrite(frwdpin, HIGH); -934 digitalWrite(backpin, LOW); -935 \textcolor{keywordflow}{break}; -936 \textcolor{keywordflow}{case} DRIVEBACK: -937 digitalWrite(frwdpin, LOW); -938 digitalWrite(backpin, HIGH); -939 \textcolor{keywordflow}{break}; -940 \} -941 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga3d3ffb41783d34589e33cf61fed46c70}\label{group__lowerleveldrivesmeths_ga3d3ffb41783d34589e33cf61fed46c70}} -\index{Methods@{Methods}!set\+\_\+drives\+\_\+speed\+\_\+left\+\_\+right@{set\+\_\+drives\+\_\+speed\+\_\+left\+\_\+right}} -\index{set\+\_\+drives\+\_\+speed\+\_\+left\+\_\+right@{set\+\_\+drives\+\_\+speed\+\_\+left\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drives\+\_\+speed\+\_\+left\+\_\+right()}{set\_drives\_speed\_left\_right()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drives\+\_\+speed\+\_\+left\+\_\+right (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{speedleft, }\item[{uint8\+\_\+t}]{speedright }\end{DoxyParamCaption})} - - - -Sets the speed for both of the drives. - -The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set\+\_\+drive\+\_\+state methods before -\begin{DoxyParams}{Parameters} -{\em speedleft} & speed of the left side drive. 0$<$=speed$<$=255 \\ -\hline -{\em speedright} & speed of the right side drive. 0$<$=speed$<$=255 \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 950 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -950 \{ -951 set\_drive\_left\_speed(speedleft); -952 set\_drive\_right\_speed(speedright); -953 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga1ee3da20ec98a821ab97ced070974861}\label{group__lowerleveldrivesmeths_ga1ee3da20ec98a821ab97ced070974861}} -\index{Methods@{Methods}!set\+\_\+drive\+\_\+left\+\_\+speed@{set\+\_\+drive\+\_\+left\+\_\+speed}} -\index{set\+\_\+drive\+\_\+left\+\_\+speed@{set\+\_\+drive\+\_\+left\+\_\+speed}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drive\+\_\+left\+\_\+speed()}{set\_drive\_left\_speed()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drive\+\_\+left\+\_\+speed (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{speed }\end{DoxyParamCaption})} - - - -Sets the speed for the left side drive. - -The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set\+\_\+drive\+\_\+state methods before -\begin{DoxyParams}{Parameters} -{\em speed} & speed of the left side drive. 0$<$=speed$<$=255 \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 961 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -961 \{ -962 set\_drive\_speed(speed, \_drive\_left\_enable\_pin); -963 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_gaf8805d0d620a2fb78c576f36a2c81073}\label{group__lowerleveldrivesmeths_gaf8805d0d620a2fb78c576f36a2c81073}} -\index{Methods@{Methods}!set\+\_\+drive\+\_\+right\+\_\+speed@{set\+\_\+drive\+\_\+right\+\_\+speed}} -\index{set\+\_\+drive\+\_\+right\+\_\+speed@{set\+\_\+drive\+\_\+right\+\_\+speed}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drive\+\_\+right\+\_\+speed()}{set\_drive\_right\_speed()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drive\+\_\+right\+\_\+speed (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{speed }\end{DoxyParamCaption})} - - - -Sets the speed for the right side drive. - -The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set\+\_\+drive\+\_\+state methods before -\begin{DoxyParams}{Parameters} -{\em speed} & speed of the right side drive. 0$<$=speed$<$=255 \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 971 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -971 \{ -972 set\_drive\_speed(speed, \_drive\_right\_enable\_pin); -973 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerleveldrivesmeths_ga5d67c84606d5b39996a99fcd6e7eb314}\label{group__lowerleveldrivesmeths_ga5d67c84606d5b39996a99fcd6e7eb314}} -\index{Methods@{Methods}!set\+\_\+drive\+\_\+speed@{set\+\_\+drive\+\_\+speed}} -\index{set\+\_\+drive\+\_\+speed@{set\+\_\+drive\+\_\+speed}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+drive\+\_\+speed()}{set\_drive\_speed()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+drive\+\_\+speed (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{speed, }\item[{uint8\+\_\+t}]{enablepin }\end{DoxyParamCaption})} - - - -Sets the speed for the drive of the enable pin connected to the specified pin. - -The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set\+\_\+drive\+\_\+state methods before -\begin{DoxyParams}{Parameters} -{\em speed} & speed of the drive. 0$<$=speed$<$=255 \\ -\hline -{\em enablepin} & Pin the drives device driver enable pin is connected at \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 982 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -982 \{ -983 \_analog\_write(enablepin, (\textcolor{keywordtype}{int})speed); -984 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths.tex b/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths.tex deleted file mode 100644 index ce2c1ce..0000000 --- a/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths.tex +++ /dev/null @@ -1,494 +0,0 @@ -\hypertarget{group__higherlevelmeths}{}\section{Methods} -\label{group__higherlevelmeths}\index{Methods@{Methods}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -void \hyperlink{group__higherlevelmeths_ga71df7ac5e41ae776a6c786d3dc36f35a}{Code\+Racer\+::stop\+\_\+driving} () -\begin{DoxyCompactList}\small\item\em Stops the racer and sets status L\+E\+Ds. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c}{Code\+Racer\+::drive\+\_\+forward} () -\begin{DoxyCompactList}\small\item\em Sets the speed and the directions of both drives so that it will move forward. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_gaae6fc379ec43cbe2cb2f63fbd12dbe0d}{Code\+Racer\+::drive\+\_\+forward} (uint8\+\_\+t left\+\_\+speed, uint8\+\_\+t right\+\_\+speed) -\begin{DoxyCompactList}\small\item\em Sets the speed as specified for both drives and the directions of both drives so that it will move forward. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga98aa8a5a46f769d59e6c1067c8418cfb}{Code\+Racer\+::drive\+\_\+backward} () -\begin{DoxyCompactList}\small\item\em Sets the speed and the directions of both drives so that it will move backward. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga6cd8356ac76360b014db6170276b6b30}{Code\+Racer\+::drive\+\_\+backward} (uint8\+\_\+t left\+\_\+speed, uint8\+\_\+t right\+\_\+speed) -\begin{DoxyCompactList}\small\item\em Sets the speed as specified for both drives and the directions of both drives so that it will move backward. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga86b7caf6ff46e9d1ad90ed507864b175}{Code\+Racer\+::turn\+\_\+left} () -\begin{DoxyCompactList}\small\item\em Will turn the racer to the left for the internally stroe time in ms and with the internally stored speed. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga30e1ec3fbbc206f93ea66dbf91b5fd95}{Code\+Racer\+::turn\+\_\+left} (unsigned long turn\+\_\+for\+\_\+ms) -\begin{DoxyCompactList}\small\item\em Will turn the racer to the left for the specified time in ms and with the internally stored speed. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_gae6daa587199e5bf95b1aac675de53b0e}{Code\+Racer\+::turn\+\_\+left} (unsigned long turn\+\_\+for\+\_\+ms, uint8\+\_\+t left\+\_\+speed, uint8\+\_\+t right\+\_\+speed) -\begin{DoxyCompactList}\small\item\em Will turn the racer to the left for the specified time in ms and with the specified speed. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga8969fb2d6e2b5ac44a99197931e6b8da}{Code\+Racer\+::turn\+\_\+right} () -\begin{DoxyCompactList}\small\item\em Will turn the racer to the right for the internally stroe time in ms and with the internally stored speed. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_gae1f175aad98d773b0206f483ae0bb4ea}{Code\+Racer\+::turn\+\_\+right} (unsigned long turn\+\_\+for\+\_\+ms) -\begin{DoxyCompactList}\small\item\em Will turn the racer to the right for the specified time in ms and with the internally stored speed. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_gad10b3457489cc7e25ffb4d64c539528a}{Code\+Racer\+::turn\+\_\+right} (unsigned long turn\+\_\+for\+\_\+ms, uint8\+\_\+t left\+\_\+speed, uint8\+\_\+t right\+\_\+speed) -\begin{DoxyCompactList}\small\item\em Will turn the racer to the right for the specified time in ms and with the specified speed. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga128683caea019a89bce06f722ba92556}{Code\+Racer\+::start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance} () -\begin{DoxyCompactList}\small\item\em Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_ga64bc1b2a8ed5bc3ec5e706fa70a1385d}{Code\+Racer\+::start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance} (unsigned long min\+\_\+distance\+\_\+cm) -\begin{DoxyCompactList}\small\item\em Enables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelmeths_gac664109241d08b8dc52db5721f394b22}{Code\+Racer\+::stop\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance} () -\begin{DoxyCompactList}\small\item\em Disables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. \end{DoxyCompactList}\item -bool \hyperlink{group__higherlevelmeths_ga34e2fe2123e76fd844482dfef6c5a9c8}{Code\+Racer\+::start\+\_\+stop} () -\begin{DoxyCompactList}\small\item\em This will return if the codracer is in active mode or not. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__higherlevelmeths_ga71df7ac5e41ae776a6c786d3dc36f35a}\label{group__higherlevelmeths_ga71df7ac5e41ae776a6c786d3dc36f35a}} -\index{Methods@{Methods}!stop\+\_\+driving@{stop\+\_\+driving}} -\index{stop\+\_\+driving@{stop\+\_\+driving}!Methods@{Methods}} -\subsubsection{\texorpdfstring{stop\+\_\+driving()}{stop\_driving()}} -{\footnotesize\ttfamily void Code\+Racer\+::stop\+\_\+driving (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Stops the racer and sets status L\+E\+Ds. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 161 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -161 \{ -162 \_servo\_sweep = \textcolor{keyword}{false}; -163 \_drive = \textcolor{keyword}{false}; -164 set\_drives\_stop\_left\_right(); -165 set\_leds\_left\_stop\_frwd\_right(LEDOFF, LEDON, LEDOFF, LEDOFF); -166 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c}\label{group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c}} -\index{Methods@{Methods}!drive\+\_\+forward@{drive\+\_\+forward}} -\index{drive\+\_\+forward@{drive\+\_\+forward}!Methods@{Methods}} -\subsubsection{\texorpdfstring{drive\+\_\+forward()}{drive\_forward()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily void Code\+Racer\+::drive\+\_\+forward (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sets the speed and the directions of both drives so that it will move forward. - -The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section \begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 173 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -174 \{ -175 drive\_forward(\_drive\_left\_speed, \_drive\_right\_speed); -176 \} -\end{DoxyCode} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=206pt]{d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph} -\end{center} -\end{figure} -\mbox{\Hypertarget{group__higherlevelmeths_gaae6fc379ec43cbe2cb2f63fbd12dbe0d}\label{group__higherlevelmeths_gaae6fc379ec43cbe2cb2f63fbd12dbe0d}} -\index{Methods@{Methods}!drive\+\_\+forward@{drive\+\_\+forward}} -\index{drive\+\_\+forward@{drive\+\_\+forward}!Methods@{Methods}} -\subsubsection{\texorpdfstring{drive\+\_\+forward()}{drive\_forward()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily void Code\+Racer\+::drive\+\_\+forward (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{left\+\_\+speed, }\item[{uint8\+\_\+t}]{right\+\_\+speed }\end{DoxyParamCaption})} - - - -Sets the speed as specified for both drives and the directions of both drives so that it will move forward. - -The specified speed values for both drives will be stored internaly so next time if you use e.\+g. drive\+\_\+forward() exactly the here specified values will be taken. -\begin{DoxyParams}{Parameters} -{\em left\+\_\+speed} & speed for the left side drive. 0$<$=speed$<$=255 \\ -\hline -{\em right\+\_\+speed} & speed for the right side drive. 0$<$=speed$<$=255 \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 185 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -186 \{ -187 set\_drives\_states\_left\_right(DRIVEFRWD, DRIVEFRWD); -188 set\_drives\_speed\_left\_right(left\_speed, right\_speed); -189 set\_leds\_left\_stop\_frwd\_right(LEDOFF, LEDOFF, LEDON, LEDOFF); -190 \_drive = \textcolor{keyword}{true}; -191 \_drive\_set\_at\_ms = millis(); -192 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga98aa8a5a46f769d59e6c1067c8418cfb}\label{group__higherlevelmeths_ga98aa8a5a46f769d59e6c1067c8418cfb}} -\index{Methods@{Methods}!drive\+\_\+backward@{drive\+\_\+backward}} -\index{drive\+\_\+backward@{drive\+\_\+backward}!Methods@{Methods}} -\subsubsection{\texorpdfstring{drive\+\_\+backward()}{drive\_backward()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily void Code\+Racer\+::drive\+\_\+backward (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sets the speed and the directions of both drives so that it will move backward. - -The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section \begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 199 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -200 \{ -201 drive\_backward(\_drive\_left\_speed, \_drive\_right\_speed); -202 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga6cd8356ac76360b014db6170276b6b30}\label{group__higherlevelmeths_ga6cd8356ac76360b014db6170276b6b30}} -\index{Methods@{Methods}!drive\+\_\+backward@{drive\+\_\+backward}} -\index{drive\+\_\+backward@{drive\+\_\+backward}!Methods@{Methods}} -\subsubsection{\texorpdfstring{drive\+\_\+backward()}{drive\_backward()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily void Code\+Racer\+::drive\+\_\+backward (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{left\+\_\+speed, }\item[{uint8\+\_\+t}]{right\+\_\+speed }\end{DoxyParamCaption})} - - - -Sets the speed as specified for both drives and the directions of both drives so that it will move backward. - -The specified speed values for both drives will be stored internaly so next time if you use e.\+g. drive\+\_\+backward() exactly the here specified values will be taken. -\begin{DoxyParams}{Parameters} -{\em left\+\_\+speed} & speed for the left side drive. 0$<$=speed$<$=255 \\ -\hline -{\em right\+\_\+speed} & speed for the right side drive. 0$<$=speed$<$=255 \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 211 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -212 \{ -213 set\_drives\_states\_left\_right(DRIVEBACK, DRIVEBACK); -214 set\_drives\_speed\_left\_right(left\_speed, right\_speed); -215 set\_leds\_left\_stop\_frwd\_right(LEDOFF, LEDON, LEDON, LEDOFF); -216 \_drive = \textcolor{keyword}{true}; -217 \_drive\_set\_at\_ms = millis(); -218 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga86b7caf6ff46e9d1ad90ed507864b175}\label{group__higherlevelmeths_ga86b7caf6ff46e9d1ad90ed507864b175}} -\index{Methods@{Methods}!turn\+\_\+left@{turn\+\_\+left}} -\index{turn\+\_\+left@{turn\+\_\+left}!Methods@{Methods}} -\subsubsection{\texorpdfstring{turn\+\_\+left()}{turn\_left()}\hspace{0.1cm}{\footnotesize\ttfamily [1/3]}} -{\footnotesize\ttfamily void Code\+Racer\+::turn\+\_\+left (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Will turn the racer to the left for the internally stroe time in ms and with the internally stored speed. - -The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to left time can be set by thoose methods as well. The method is delayed until the racer has turned. \begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 226 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -227 \{ -228 turn\_left(\_turn\_left\_for\_ms, \_drive\_left\_speed, \_drive\_right\_speed); -229 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga30e1ec3fbbc206f93ea66dbf91b5fd95}\label{group__higherlevelmeths_ga30e1ec3fbbc206f93ea66dbf91b5fd95}} -\index{Methods@{Methods}!turn\+\_\+left@{turn\+\_\+left}} -\index{turn\+\_\+left@{turn\+\_\+left}!Methods@{Methods}} -\subsubsection{\texorpdfstring{turn\+\_\+left()}{turn\_left()}\hspace{0.1cm}{\footnotesize\ttfamily [2/3]}} -{\footnotesize\ttfamily void Code\+Racer\+::turn\+\_\+left (\begin{DoxyParamCaption}\item[{unsigned long}]{turn\+\_\+for\+\_\+ms }\end{DoxyParamCaption})} - - - -Will turn the racer to the left for the specified time in ms and with the internally stored speed. - -The specified duration of time is stored internally and will be used next time by e.\+g. turn\+\_\+left() -\begin{DoxyParams}{Parameters} -{\em turn\+\_\+for\+\_\+ms} & duration of time in ms to turn the racer \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 237 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -238 \{ -239 turn\_left(turn\_for\_ms, \_drive\_left\_speed, \_drive\_right\_speed); -240 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_gae6daa587199e5bf95b1aac675de53b0e}\label{group__higherlevelmeths_gae6daa587199e5bf95b1aac675de53b0e}} -\index{Methods@{Methods}!turn\+\_\+left@{turn\+\_\+left}} -\index{turn\+\_\+left@{turn\+\_\+left}!Methods@{Methods}} -\subsubsection{\texorpdfstring{turn\+\_\+left()}{turn\_left()}\hspace{0.1cm}{\footnotesize\ttfamily [3/3]}} -{\footnotesize\ttfamily void Code\+Racer\+::turn\+\_\+left (\begin{DoxyParamCaption}\item[{unsigned long}]{turn\+\_\+for\+\_\+ms, }\item[{uint8\+\_\+t}]{left\+\_\+speed, }\item[{uint8\+\_\+t}]{right\+\_\+speed }\end{DoxyParamCaption})} - - - -Will turn the racer to the left for the specified time in ms and with the specified speed. - -The specified duration of time and the specified speeds are stored internally and will be used next time by e.\+g. turn\+\_\+left() -\begin{DoxyParams}{Parameters} -{\em turn\+\_\+for\+\_\+ms} & duration of time in ms to turn the racer \\ -\hline -{\em left\+\_\+speed} & speed for the left side drive \\ -\hline -{\em right\+\_\+speed} & speed for the right side drive \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 250 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -251 \{ -252 \_drive = \textcolor{keyword}{false}; -253 set\_leds\_left\_stop\_frwd\_right(LEDON, LEDOFF, LEDOFF, LEDOFF); \textcolor{comment}{// LEDs setzen} -254 set\_drives\_states\_left\_right(DRIVEBACK, DRIVEFRWD); -255 set\_drives\_speed\_left\_right(left\_speed, right\_speed); -256 \textcolor{comment}{// wait set delay for the timed turn} -257 \_turn\_left\_for\_ms = turn\_for\_ms; -258 delay(\_turn\_left\_for\_ms); -259 \textcolor{comment}{// stop drives again} -260 set\_drives\_stop\_left\_right(); -261 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga8969fb2d6e2b5ac44a99197931e6b8da}\label{group__higherlevelmeths_ga8969fb2d6e2b5ac44a99197931e6b8da}} -\index{Methods@{Methods}!turn\+\_\+right@{turn\+\_\+right}} -\index{turn\+\_\+right@{turn\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{turn\+\_\+right()}{turn\_right()}\hspace{0.1cm}{\footnotesize\ttfamily [1/3]}} -{\footnotesize\ttfamily void Code\+Racer\+::turn\+\_\+right (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Will turn the racer to the right for the internally stroe time in ms and with the internally stored speed. - -The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to right time can be set by thoose methods as well. The method is delayed until the racer has turned. \begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 269 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -270 \{ -271 turn\_right(\_turn\_right\_for\_ms, \_drive\_left\_speed, \_drive\_right\_speed); -272 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_gae1f175aad98d773b0206f483ae0bb4ea}\label{group__higherlevelmeths_gae1f175aad98d773b0206f483ae0bb4ea}} -\index{Methods@{Methods}!turn\+\_\+right@{turn\+\_\+right}} -\index{turn\+\_\+right@{turn\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{turn\+\_\+right()}{turn\_right()}\hspace{0.1cm}{\footnotesize\ttfamily [2/3]}} -{\footnotesize\ttfamily void Code\+Racer\+::turn\+\_\+right (\begin{DoxyParamCaption}\item[{unsigned long}]{turn\+\_\+for\+\_\+ms }\end{DoxyParamCaption})} - - - -Will turn the racer to the right for the specified time in ms and with the internally stored speed. - -The specified duration of time is stored internally and will be used next time by e.\+g. turn\+\_\+right() -\begin{DoxyParams}{Parameters} -{\em turn\+\_\+for\+\_\+ms} & duration of time in ms to turn the racer \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 280 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -281 \{ -282 turn\_right(turn\_for\_ms, \_drive\_left\_speed, \_drive\_right\_speed); -283 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_gad10b3457489cc7e25ffb4d64c539528a}\label{group__higherlevelmeths_gad10b3457489cc7e25ffb4d64c539528a}} -\index{Methods@{Methods}!turn\+\_\+right@{turn\+\_\+right}} -\index{turn\+\_\+right@{turn\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{turn\+\_\+right()}{turn\_right()}\hspace{0.1cm}{\footnotesize\ttfamily [3/3]}} -{\footnotesize\ttfamily void Code\+Racer\+::turn\+\_\+right (\begin{DoxyParamCaption}\item[{unsigned long}]{turn\+\_\+for\+\_\+ms, }\item[{uint8\+\_\+t}]{left\+\_\+speed, }\item[{uint8\+\_\+t}]{right\+\_\+speed }\end{DoxyParamCaption})} - - - -Will turn the racer to the right for the specified time in ms and with the specified speed. - -The specified duration of time and the specified speeds are stored internally and will be used next time by e.\+g. turn\+\_\+right() -\begin{DoxyParams}{Parameters} -{\em turn\+\_\+for\+\_\+ms} & duration of time in ms to turn the racer \\ -\hline -{\em left\+\_\+speed} & speed for the left side drive \\ -\hline -{\em right\+\_\+speed} & speed for the right side drive \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 293 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -294 \{ -295 \_drive = \textcolor{keyword}{false}; -296 set\_leds\_left\_stop\_frwd\_right(LEDOFF, LEDOFF, LEDOFF, LEDON); \textcolor{comment}{// LEDs setzen} -297 set\_drives\_states\_left\_right(DRIVEFRWD, DRIVEBACK); -298 set\_drives\_speed\_left\_right(left\_speed, right\_speed); -299 \textcolor{comment}{// wait set delay for the timed turn} -300 \_turn\_right\_for\_ms = turn\_for\_ms; -301 delay(\_turn\_right\_for\_ms); -302 \textcolor{comment}{// stop drives again} -303 set\_drives\_stop\_left\_right(); -304 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga128683caea019a89bce06f722ba92556}\label{group__higherlevelmeths_ga128683caea019a89bce06f722ba92556}} -\index{Methods@{Methods}!start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance@{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance}} -\index{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance@{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance}!Methods@{Methods}} -\subsubsection{\texorpdfstring{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance()}{start\_stop\_at\_min\_distance()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily void Code\+Racer\+::start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance. - -This allow all of the none-\/single shot ultra sonic measurement methods to stopp the racer in the case the measured distance is smaller than minimal distance. This is just the enablement -\/ you have to call one of the none-\/single-\/shot ultra sonic measurement methods continously while driving and maybe sweeping the servo. If the racer was stopped can be checked with stopped\+\_\+at\+\_\+min\+\_\+distance() -\/ it will return true in that case. The minimal distance can be set by the ultrasonic sensor setter methods. There is an example coming with the coderacer libary that you can load and get an idea how that works. \begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 314 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -314 \{ -315 start\_stop\_at\_min\_distance(\_usonic\_stop\_distance\_cm); -316 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga64bc1b2a8ed5bc3ec5e706fa70a1385d}\label{group__higherlevelmeths_ga64bc1b2a8ed5bc3ec5e706fa70a1385d}} -\index{Methods@{Methods}!start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance@{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance}} -\index{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance@{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance}!Methods@{Methods}} -\subsubsection{\texorpdfstring{start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance()}{start\_stop\_at\_min\_distance()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily void Code\+Racer\+::start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance (\begin{DoxyParamCaption}\item[{unsigned long}]{min\+\_\+distance\+\_\+cm }\end{DoxyParamCaption})} - - - -Enables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. - -This is almos the same as described for start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance(). You can specify the distance in cm here -\/ this value will be stored internally and used by start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance() next time. -\begin{DoxyParams}{Parameters} -{\em min\+\_\+distance\+\_\+cm} & the minimal disctance in cm \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 324 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -324 \{ -325 \textcolor{keywordflow}{if} (\textcolor{keyword}{false} == \_coderacer\_stop\_at\_distance\_enabled) \{ -326 \_coderacer\_stopped\_at\_min\_distance = \textcolor{keyword}{false}; -327 usonic\_set\_stop\_distance\_cm(min\_distance\_cm); -328 \_coderacer\_stop\_at\_distance\_enabled = \textcolor{keyword}{true}; -329 \} -330 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_gac664109241d08b8dc52db5721f394b22}\label{group__higherlevelmeths_gac664109241d08b8dc52db5721f394b22}} -\index{Methods@{Methods}!stop\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance@{stop\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance}} -\index{stop\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance@{stop\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance}!Methods@{Methods}} -\subsubsection{\texorpdfstring{stop\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance()}{stop\_stop\_at\_min\_distance()}} -{\footnotesize\ttfamily void Code\+Racer\+::stop\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Disables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 335 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -335 \{ -336 \_coderacer\_stop\_at\_distance\_enabled = \textcolor{keyword}{false}; -337 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelmeths_ga34e2fe2123e76fd844482dfef6c5a9c8}\label{group__higherlevelmeths_ga34e2fe2123e76fd844482dfef6c5a9c8}} -\index{Methods@{Methods}!start\+\_\+stop@{start\+\_\+stop}} -\index{start\+\_\+stop@{start\+\_\+stop}!Methods@{Methods}} -\subsubsection{\texorpdfstring{start\+\_\+stop()}{start\_stop()}} -{\footnotesize\ttfamily bool Code\+Racer\+::start\+\_\+stop (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -This will return if the codracer is in active mode or not. - -There is a button used to toogle between active and inactive each time it is pressed This may help you to start driving and scanning the distance by pressing the button -\/ and as well to stop the racer by pressing the button. This method will set the L\+E\+Ds depending on the mode and sets the servo back to center and stopps the racer when leaving the active mode. You can leave or enter the active mode as well by setting using set\+\_\+active() and set\+\_\+inactive(). The button itself triggers and internall interrupt event and sets the active state -\/ but you have to continously call that method to switch between inactive and active mode depending on the active state. If in inactive mode and fun is enabeld by just setting the coderacer\+\_\+fun\+\_\+enabled = true ... some fun will happen \+:-\/) - -\begin{DoxyReturn}{Returns} -True if the coderacer is in active mode. False if in inactive mode. -\end{DoxyReturn} - - -Definition at line 348 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -348 \{ -349 \textcolor{keywordflow}{if} (\_coderracer\_activ != coderracer\_activ) \{ -350 \_coderracer\_activ = coderracer\_activ; -351 \textcolor{keywordflow}{if} (\textcolor{keyword}{true} == \_coderracer\_activ) \{ -352 set\_leds\_all\_off(); -353 delay(500); -354 \} -355 \textcolor{keywordflow}{else} \{ -356 stop\_driving(); -357 set\_leds\_all\_on(); -358 delay(200); -359 servo\_set\_to\_center(); -360 \_servo\_look\_around\_at\_ms = millis() + random(20000, 120000); -361 \} -362 \} -363 -364 \textcolor{keywordflow}{if} ((\textcolor{keyword}{false} == \_coderracer\_activ) && (\textcolor{keyword}{true} == coderacer\_fun\_enabled)) \{ -365 kitt(); -366 look\_around(); -367 \} -368 -369 \textcolor{keywordflow}{return}(\_coderracer\_activ); -370 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.md5 b/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.md5 deleted file mode 100644 index 8f0ac29..0000000 --- a/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4b1e3a7d2ca636524434d6a1e7321989 \ No newline at end of file diff --git a/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.pdf b/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.pdf deleted file mode 100644 index 39351de..0000000 Binary files a/Doku/Doxygen/latex/d2/d40/group__higherlevelmeths_ga8be6a850099812153dcf5768d7fc8b8c_cgraph.pdf and /dev/null differ diff --git a/Doku/Doxygen/latex/d3/d17/group__lowerlevelservo.tex b/Doku/Doxygen/latex/d3/d17/group__lowerlevelservo.tex deleted file mode 100644 index 22bb177..0000000 --- a/Doku/Doxygen/latex/d3/d17/group__lowerlevelservo.tex +++ /dev/null @@ -1,12 +0,0 @@ -\hypertarget{group__lowerlevelservo}{}\section{Lower level servo drive methods and getters} -\label{group__lowerlevelservo}\index{Lower level servo drive methods and getters@{Lower level servo drive methods and getters}} -\subsection*{Modules} -\begin{DoxyCompactItemize} -\item -\hyperlink{group__lowerlevelservomeths}{Methods} -\item -\hyperlink{group__lowerlevelservogetters}{Getters} -\end{DoxyCompactItemize} - - -\subsection{Detailed Description} diff --git a/Doku/Doxygen/latex/d4/df4/group__lowerlevelservogetters.tex b/Doku/Doxygen/latex/d4/df4/group__lowerlevelservogetters.tex deleted file mode 100644 index 0128d12..0000000 --- a/Doku/Doxygen/latex/d4/df4/group__lowerlevelservogetters.tex +++ /dev/null @@ -1,86 +0,0 @@ -\hypertarget{group__lowerlevelservogetters}{}\section{Getters} -\label{group__lowerlevelservogetters}\index{Getters@{Getters}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -uint8\+\_\+t \hyperlink{group__lowerlevelservogetters_ga451b3ecd272e9a11de4b221f8d771432}{Code\+Racer\+::servo\+\_\+position} () -\begin{DoxyCompactList}\small\item\em Get the actual position of the servo. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelservogetters_gaeed05a3d4e06adccebdfce207b734b2f}{Code\+Racer\+::servo\+\_\+position\+\_\+set\+\_\+at\+\_\+ms} () -\begin{DoxyCompactList}\small\item\em Get the system time in ms the servo was set to the actual position. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelservogetters_ga84ba256b9ccdf0e9f4280279da68a509}{Code\+Racer\+::servo\+\_\+position\+\_\+eta\+\_\+in\+\_\+ms} () -\begin{DoxyCompactList}\small\item\em Get the system time in ms the servo will reach its position This is an estimated time. If this is a time in the future, the servo may still moving. If this is a time in the past , the servo should have reached its postion already. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerlevelservogetters_ga451b3ecd272e9a11de4b221f8d771432}\label{group__lowerlevelservogetters_ga451b3ecd272e9a11de4b221f8d771432}} -\index{Getters@{Getters}!servo\+\_\+position@{servo\+\_\+position}} -\index{servo\+\_\+position@{servo\+\_\+position}!Getters@{Getters}} -\subsubsection{\texorpdfstring{servo\+\_\+position()}{servo\_position()}} -{\footnotesize\ttfamily uint8\+\_\+t Code\+Racer\+::servo\+\_\+position (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the actual position of the servo. - -\begin{DoxyReturn}{Returns} -Actual position of the servo -\end{DoxyReturn} - - -Definition at line 632 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -632 \{ -633 \textcolor{keywordflow}{return}(\_servo\_position); -634 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservogetters_gaeed05a3d4e06adccebdfce207b734b2f}\label{group__lowerlevelservogetters_gaeed05a3d4e06adccebdfce207b734b2f}} -\index{Getters@{Getters}!servo\+\_\+position\+\_\+set\+\_\+at\+\_\+ms@{servo\+\_\+position\+\_\+set\+\_\+at\+\_\+ms}} -\index{servo\+\_\+position\+\_\+set\+\_\+at\+\_\+ms@{servo\+\_\+position\+\_\+set\+\_\+at\+\_\+ms}!Getters@{Getters}} -\subsubsection{\texorpdfstring{servo\+\_\+position\+\_\+set\+\_\+at\+\_\+ms()}{servo\_position\_set\_at\_ms()}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::servo\+\_\+position\+\_\+set\+\_\+at\+\_\+ms (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the system time in ms the servo was set to the actual position. - -\begin{DoxyReturn}{Returns} -System time in ms the servo was set -\end{DoxyReturn} - - -Definition at line 639 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -639 \{ -640 \textcolor{keywordflow}{return}(\_servo\_position\_set\_at\_ms); -641 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservogetters_ga84ba256b9ccdf0e9f4280279da68a509}\label{group__lowerlevelservogetters_ga84ba256b9ccdf0e9f4280279da68a509}} -\index{Getters@{Getters}!servo\+\_\+position\+\_\+eta\+\_\+in\+\_\+ms@{servo\+\_\+position\+\_\+eta\+\_\+in\+\_\+ms}} -\index{servo\+\_\+position\+\_\+eta\+\_\+in\+\_\+ms@{servo\+\_\+position\+\_\+eta\+\_\+in\+\_\+ms}!Getters@{Getters}} -\subsubsection{\texorpdfstring{servo\+\_\+position\+\_\+eta\+\_\+in\+\_\+ms()}{servo\_position\_eta\_in\_ms()}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::servo\+\_\+position\+\_\+eta\+\_\+in\+\_\+ms (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the system time in ms the servo will reach its position This is an estimated time. If this is a time in the future, the servo may still moving. If this is a time in the past , the servo should have reached its postion already. - -\begin{DoxyReturn}{Returns} -System time in ms the servo will reach its position -\end{DoxyReturn} - - -Definition at line 649 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -649 \{ -650 \textcolor{keywordflow}{return}(\_servo\_position\_eta\_in\_ms); -651 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/d6/d98/group__lowerleveldrives.tex b/Doku/Doxygen/latex/d6/d98/group__lowerleveldrives.tex deleted file mode 100644 index 946be3d..0000000 --- a/Doku/Doxygen/latex/d6/d98/group__lowerleveldrives.tex +++ /dev/null @@ -1,12 +0,0 @@ -\hypertarget{group__lowerleveldrives}{}\section{Lower level drives methods and getters} -\label{group__lowerleveldrives}\index{Lower level drives methods and getters@{Lower level drives methods and getters}} -\subsection*{Modules} -\begin{DoxyCompactItemize} -\item -\hyperlink{group__lowerleveldrivesmeths}{Methods} -\item -\hyperlink{group__lowerleveldrivesgetters}{Getters} -\end{DoxyCompactItemize} - - -\subsection{Detailed Description} diff --git a/Doku/Doxygen/latex/d6/dfc/group__lowerlevelusmeths.tex b/Doku/Doxygen/latex/d6/dfc/group__lowerlevelusmeths.tex deleted file mode 100644 index 5953eb0..0000000 --- a/Doku/Doxygen/latex/d6/dfc/group__lowerlevelusmeths.tex +++ /dev/null @@ -1,292 +0,0 @@ -\hypertarget{group__lowerlevelusmeths}{}\section{Methods} -\label{group__lowerlevelusmeths}\index{Methods@{Methods}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -unsigned long \hyperlink{group__lowerlevelusmeths_ga5f034198a28b069478c454c63dbfa225}{Code\+Racer\+::usonic\+\_\+measure\+\_\+cm} () -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in cm. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusmeths_gaa01602a576fd57609bc7e08f8ef32e58}{Code\+Racer\+::usonic\+\_\+measure\+\_\+us} () -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in microseconds. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusmeths_gafdd5c75d7a8e7b7c993e512ee93dde9a}{Code\+Racer\+::usonic\+\_\+measure\+\_\+cm} (unsigned long max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us) -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in cm. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusmeths_ga1f3401ef472cb11997e7dc98ef3e2424}{Code\+Racer\+::usonic\+\_\+measure\+\_\+us} (unsigned long max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us) -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in microseconds. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusmeths_ga0c00edbbf4a3169613c9ea84d6e7dc13}{Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm} () -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in cm. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusmeths_gad4309b6da17085575fb0c55559e240b8}{Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us} () -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in microseconds. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusmeths_gab413551ea8a67e1b60eda1671029b645}{Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm} (unsigned long max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us) -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in cm. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusmeths_ga1b5b43372082f5daeee47410a09a590c}{Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us} (unsigned long max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us) -\begin{DoxyCompactList}\small\item\em Measures the distance to the next object in front of the ultra sonic sensor in microseconds. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerlevelusmeths_ga5f034198a28b069478c454c63dbfa225}\label{group__lowerlevelusmeths_ga5f034198a28b069478c454c63dbfa225}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+cm@{usonic\+\_\+measure\+\_\+cm}} -\index{usonic\+\_\+measure\+\_\+cm@{usonic\+\_\+measure\+\_\+cm}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+cm()}{usonic\_measure\_cm()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+cm (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in cm. - -This is the medium one out of 3 measurements. The maximum measured distance is about 100cm and defined by the U\+S\+\_\+\+M\+A\+X\+\_\+\+E\+C\+H\+O\+\_\+\+T\+I\+M\+E\+\_\+\+US setting in the header file. \begin{DoxyReturn}{Returns} -The measured distance in cm. -\end{DoxyReturn} - - -Definition at line 672 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -673 \{ -674 \textcolor{keywordflow}{return}(usonic\_measure\_cm(US\_MAX\_ECHO\_TIME\_US)); -675 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusmeths_gaa01602a576fd57609bc7e08f8ef32e58}\label{group__lowerlevelusmeths_gaa01602a576fd57609bc7e08f8ef32e58}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+us@{usonic\+\_\+measure\+\_\+us}} -\index{usonic\+\_\+measure\+\_\+us@{usonic\+\_\+measure\+\_\+us}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+us()}{usonic\_measure\_us()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+us (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in microseconds. - -This is the medium one out of 3 measurements. The maximum measured distance is about 6000 microseconds and defined by the U\+S\+\_\+\+M\+A\+X\+\_\+\+E\+C\+H\+O\+\_\+\+T\+I\+M\+E\+\_\+\+US setting in the header file. \begin{DoxyReturn}{Returns} -The measured distance in microseconds. -\end{DoxyReturn} - - -Definition at line 682 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -683 \{ -684 \textcolor{keywordflow}{return}(usonic\_measure\_us(US\_MAX\_ECHO\_TIME\_US)); -685 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusmeths_gafdd5c75d7a8e7b7c993e512ee93dde9a}\label{group__lowerlevelusmeths_gafdd5c75d7a8e7b7c993e512ee93dde9a}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+cm@{usonic\+\_\+measure\+\_\+cm}} -\index{usonic\+\_\+measure\+\_\+cm@{usonic\+\_\+measure\+\_\+cm}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+cm()}{usonic\_measure\_cm()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+cm (\begin{DoxyParamCaption}\item[{unsigned long}]{max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in cm. - -This is the medium one out of 3 measurements. Be careful with high values for max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us -\/ this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm. -\begin{DoxyParams}{Parameters} -{\em max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us} & Defines the maximum echo run time and by that the maximum of distance that can be measured. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The measured distance in cm. -\end{DoxyReturn} - - -Definition at line 694 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -695 \{ -696 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} echo\_runtime\_us = usonic\_measure\_us(max\_echo\_run\_time\_us); -697 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} distance\_cm = echo\_runtime\_us * 0.0172; -698 \textcolor{comment}{//Serial.print("MEASURE\_DISTANCE. Distance in cm is: ");} -699 \textcolor{comment}{//Serial.println(distance\_cm);} -700 \_usonic\_distance\_cm = distance\_cm; -701 \textcolor{keywordflow}{return}(distance\_cm); -702 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusmeths_ga1f3401ef472cb11997e7dc98ef3e2424}\label{group__lowerlevelusmeths_ga1f3401ef472cb11997e7dc98ef3e2424}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+us@{usonic\+\_\+measure\+\_\+us}} -\index{usonic\+\_\+measure\+\_\+us@{usonic\+\_\+measure\+\_\+us}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+us()}{usonic\_measure\_us()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+us (\begin{DoxyParamCaption}\item[{unsigned long}]{max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in microseconds. - -This is the medium one out of 3 measurements. Be careful with high values for max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us -\/ this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm. -\begin{DoxyParams}{Parameters} -{\em max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us} & Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The measured distance in microseconds. -\end{DoxyReturn} - - -Definition at line 711 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -712 \{ -713 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} echo\_runtime\_us[3] = \{ 0,0,0 \}; -714 uint8\_t measnr = 0; -715 -716 \textcolor{keywordflow}{do} \{ -717 echo\_runtime\_us[measnr] = usonic\_measure\_single\_shot\_us(max\_echo\_run\_time\_us); -718 \textcolor{keywordflow}{if} (echo\_runtime\_us[measnr] > 200) \{ -719 measnr++; -720 \} -721 \} \textcolor{keywordflow}{while} (measnr < 3); -722 -723 \textcolor{comment}{// we will take the medium out of 3 values ... } -724 \textcolor{keywordflow}{if} (echo\_runtime\_us[0] > echo\_runtime\_us[1]) \{ std::swap(echo\_runtime\_us[0], echo\_runtime\_us[1]); \} -725 \textcolor{keywordflow}{if} (echo\_runtime\_us[1] > echo\_runtime\_us[2]) \{ std::swap(echo\_runtime\_us[1], echo\_runtime\_us[2]); \} -726 \textcolor{keywordflow}{if} (echo\_runtime\_us[0] > echo\_runtime\_us[1]) \{ std::swap(echo\_runtime\_us[0], echo\_runtime\_us[1]); \} -727 -728 \textcolor{comment}{//Serial.print("MEASURE\_DISTANCE\_US. Echo runtime in us is: ");} -729 \textcolor{comment}{//Serial.println(echo\_runtime\_us[1]);} -730 -731 \textcolor{comment}{// if the stop at minimal distance is enabeled - check for minimal distance is reached} -732 \textcolor{keywordflow}{if} (\textcolor{keyword}{true} == \_coderacer\_stop\_at\_distance\_enabled) \{ -733 \textcolor{keywordflow}{if} (echo\_runtime\_us[1] <= \_usonic\_stop\_distance\_us) \{ -734 \_coderacer\_stopped\_at\_min\_distance = \textcolor{keyword}{true}; -735 stop\_driving(); -736 \_coderacer\_stop\_at\_distance\_enabled = \textcolor{keyword}{false}; -737 \} -738 \} -739 \_usonic\_distance\_us = echo\_runtime\_us[1]; -740 \textcolor{keywordflow}{return}(echo\_runtime\_us[1]); -741 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusmeths_ga0c00edbbf4a3169613c9ea84d6e7dc13}\label{group__lowerlevelusmeths_ga0c00edbbf4a3169613c9ea84d6e7dc13}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm}} -\index{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm()}{usonic\_measure\_single\_shot\_cm()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in cm. - -This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the U\+S\+\_\+\+M\+A\+X\+\_\+\+E\+C\+H\+O\+\_\+\+T\+I\+M\+E\+\_\+\+US setting in the header file. \begin{DoxyReturn}{Returns} -The measured distance in cm. -\end{DoxyReturn} - - -Definition at line 748 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -749 \{ -750 \textcolor{keywordflow}{return}(usonic\_measure\_single\_shot\_cm(US\_MAX\_ECHO\_TIME\_US)); -751 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusmeths_gad4309b6da17085575fb0c55559e240b8}\label{group__lowerlevelusmeths_gad4309b6da17085575fb0c55559e240b8}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us}} -\index{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us()}{usonic\_measure\_single\_shot\_us()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in microseconds. - -This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the U\+S\+\_\+\+M\+A\+X\+\_\+\+E\+C\+H\+O\+\_\+\+T\+I\+M\+E\+\_\+\+US setting in the header file. \begin{DoxyReturn}{Returns} -The measured distance in microseconds. -\end{DoxyReturn} - - -Definition at line 758 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -759 \{ -760 \textcolor{keywordflow}{return}(usonic\_measure\_single\_shot\_us(US\_MAX\_ECHO\_TIME\_US)); -761 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusmeths_gab413551ea8a67e1b60eda1671029b645}\label{group__lowerlevelusmeths_gab413551ea8a67e1b60eda1671029b645}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm}} -\index{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm()}{usonic\_measure\_single\_shot\_cm()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+cm (\begin{DoxyParamCaption}\item[{unsigned long}]{max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in cm. - -This is a one shot measurement. Be careful with high values for max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us -\/ this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm. -\begin{DoxyParams}{Parameters} -{\em max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us} & Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The measured distance in cm. -\end{DoxyReturn} - - -Definition at line 770 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -771 \{ -772 \textcolor{comment}{// convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or - 0,0344cm/microsec} -773 \textcolor{comment}{// the echo has to go the distance twice - forth and back - so the duration has to be the half of the - measured one} -774 \textcolor{comment}{// distance\_cm = echo\_duration/2 * 0,0344 or distance\_cm = echo\_duration/2 / 29,1 or distance\_cm = - echo\_duration * 0,0172} -775 \textcolor{comment}{// distance\_cm = (echo\_duration/2) / 29.1;} -776 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} echo\_runtime\_us = usonic\_measure\_single\_shot\_us(max\_echo\_run\_time\_us); -777 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} distance\_cm = echo\_runtime\_us * 0.0172; -778 \textcolor{comment}{//Serial.print("MEASURE\_DISTANCE. Distance in cm is: ");} -779 \textcolor{comment}{//Serial.println(distance\_cm);} -780 \_usonic\_distance\_cm = distance\_cm; -781 \textcolor{keywordflow}{return}(distance\_cm); -782 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusmeths_ga1b5b43372082f5daeee47410a09a590c}\label{group__lowerlevelusmeths_ga1b5b43372082f5daeee47410a09a590c}} -\index{Methods@{Methods}!usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us}} -\index{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us@{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us}!Methods@{Methods}} -\subsubsection{\texorpdfstring{usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us()}{usonic\_measure\_single\_shot\_us()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+measure\+\_\+single\+\_\+shot\+\_\+us (\begin{DoxyParamCaption}\item[{unsigned long}]{max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us }\end{DoxyParamCaption})} - - - -Measures the distance to the next object in front of the ultra sonic sensor in microseconds. - -This is a one shot measurement. Be careful with high values for max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us -\/ this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. The maximum range the sensor is specified for is about 300cm. -\begin{DoxyParams}{Parameters} -{\em max\+\_\+echo\+\_\+run\+\_\+time\+\_\+us} & Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The measured distance in microseconds. -\end{DoxyReturn} - - -Definition at line 791 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -792 \{ -793 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} echo\_runtime\_us; -794 \textcolor{comment}{// start measurement - send a short pulse "HIGH" to the TRIG pin of the ultrasonic sensor} -795 pinMode(\_us\_echo\_pin, OUTPUT); -796 pinMode(\_us\_echo\_pin, INPUT); -797 digitalWrite(\_us\_trigger\_pin, LOW); -798 delayMicroseconds(2); -799 digitalWrite(\_us\_trigger\_pin, HIGH); -800 delayMicroseconds(10); -801 digitalWrite(\_us\_trigger\_pin, LOW); -802 \textcolor{comment}{// measure runtime in microseconds until the ECHO pin aof the sensor goes HIGH} -803 echo\_runtime\_us = pulseInLong(\_us\_echo\_pin, HIGH, max\_echo\_run\_time\_us); -804 \textcolor{keywordflow}{if} (echo\_runtime\_us == 0) \{ -805 echo\_runtime\_us = max\_echo\_run\_time\_us; \textcolor{comment}{// US\_MAX\_ECHO\_TIME\_US;} -806 \} -807 \textcolor{comment}{//Serial.print("MEASURE\_DISTANCE\_US. Echo runtime in us is: ");} -808 \textcolor{comment}{//Serial.println(echo\_runtime\_us);} -809 \_usonic\_distance\_us = echo\_runtime\_us; -810 \textcolor{keywordflow}{return}(echo\_runtime\_us); -811 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/d7/d0f/group__lowerlevelled.tex b/Doku/Doxygen/latex/d7/d0f/group__lowerlevelled.tex deleted file mode 100644 index 8f7aa14..0000000 --- a/Doku/Doxygen/latex/d7/d0f/group__lowerlevelled.tex +++ /dev/null @@ -1,10 +0,0 @@ -\hypertarget{group__lowerlevelled}{}\section{Lower level L\+ED methods} -\label{group__lowerlevelled}\index{Lower level L\+E\+D methods@{Lower level L\+E\+D methods}} -\subsection*{Modules} -\begin{DoxyCompactItemize} -\item -\hyperlink{group__lowerlevelledmeths}{Methods} -\end{DoxyCompactItemize} - - -\subsection{Detailed Description} diff --git a/Doku/Doxygen/latex/d7/d45/group__higherlevelgetters.tex b/Doku/Doxygen/latex/d7/d45/group__higherlevelgetters.tex deleted file mode 100644 index 0c89822..0000000 --- a/Doku/Doxygen/latex/d7/d45/group__higherlevelgetters.tex +++ /dev/null @@ -1,186 +0,0 @@ -\hypertarget{group__higherlevelgetters}{}\section{Getters and setters} -\label{group__higherlevelgetters}\index{Getters and setters@{Getters and setters}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -bool \hyperlink{group__higherlevelgetters_gae8b8c0ab24ccb572281785aeca8541e1}{Code\+Racer\+::stopped\+\_\+at\+\_\+min\+\_\+distance} () -\begin{DoxyCompactList}\small\item\em Returns true if the racer was stopped at minimum distance. This set to false each time start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance() is called. \end{DoxyCompactList}\item -bool \hyperlink{group__higherlevelgetters_ga33dcd96e9b12dec794c56be85ec1ee05}{Code\+Racer\+::is\+\_\+driving} () -\begin{DoxyCompactList}\small\item\em Return true if the racer is driving -\/ forward or backward. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__higherlevelgetters_gaf04fd16ca0e2ace656f9549c43d16459}{Code\+Racer\+::turn\+\_\+left\+\_\+for\+\_\+ms} () -\begin{DoxyCompactList}\small\item\em Returns the duration of time that is internally stored and used for turning the racer left. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__higherlevelgetters_gac0698f02f6a21d9d1f5b9cf2820306cf}{Code\+Racer\+::turn\+\_\+right\+\_\+for\+\_\+ms} () -\begin{DoxyCompactList}\small\item\em Returns the duration of time that is internally stored and used for turning the racer left. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelgetters_ga62f1c0eea56e27d0853cb58f30eb140d}{Code\+Racer\+::set\+\_\+inactive} () -\begin{DoxyCompactList}\small\item\em Sets the coderracer\+\_\+active state to inactive. If start\+\_\+stop() is used -\/ the inactive mode will be entered. \end{DoxyCompactList}\item -void \hyperlink{group__higherlevelgetters_ga415c69930f291d5e06b7211b31843310}{Code\+Racer\+::set\+\_\+active} () -\begin{DoxyCompactList}\small\item\em Sets the coderracer\+\_\+active state to active. If start\+\_\+stop() is used -\/ the active mode will be entered. \end{DoxyCompactList}\item -bool \hyperlink{group__higherlevelgetters_gaa0ab4d6a754a23ea13664a553bcc8ff2}{Code\+Racer\+::is\+\_\+active} () -\begin{DoxyCompactList}\small\item\em Checks if coderracer\+\_\+activ is set. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__higherlevelgetters_gae8b8c0ab24ccb572281785aeca8541e1}\label{group__higherlevelgetters_gae8b8c0ab24ccb572281785aeca8541e1}} -\index{Getters and setters@{Getters and setters}!stopped\+\_\+at\+\_\+min\+\_\+distance@{stopped\+\_\+at\+\_\+min\+\_\+distance}} -\index{stopped\+\_\+at\+\_\+min\+\_\+distance@{stopped\+\_\+at\+\_\+min\+\_\+distance}!Getters and setters@{Getters and setters}} -\subsubsection{\texorpdfstring{stopped\+\_\+at\+\_\+min\+\_\+distance()}{stopped\_at\_min\_distance()}} -{\footnotesize\ttfamily bool Code\+Racer\+::stopped\+\_\+at\+\_\+min\+\_\+distance (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Returns true if the racer was stopped at minimum distance. This set to false each time start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance() is called. - -\begin{DoxyReturn}{Returns} -True if stopped. -\end{DoxyReturn} - - -Definition at line 380 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -380 \{ -381 \textcolor{keywordflow}{return}(\_coderacer\_stopped\_at\_min\_distance); -382 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelgetters_ga33dcd96e9b12dec794c56be85ec1ee05}\label{group__higherlevelgetters_ga33dcd96e9b12dec794c56be85ec1ee05}} -\index{Getters and setters@{Getters and setters}!is\+\_\+driving@{is\+\_\+driving}} -\index{is\+\_\+driving@{is\+\_\+driving}!Getters and setters@{Getters and setters}} -\subsubsection{\texorpdfstring{is\+\_\+driving()}{is\_driving()}} -{\footnotesize\ttfamily bool Code\+Racer\+::is\+\_\+driving (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Return true if the racer is driving -\/ forward or backward. - -\begin{DoxyReturn}{Returns} -True if driving forward or backward -\end{DoxyReturn} - - -Definition at line 387 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -387 \{ -388 \textcolor{keywordflow}{return}(\_drive); -389 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelgetters_gaf04fd16ca0e2ace656f9549c43d16459}\label{group__higherlevelgetters_gaf04fd16ca0e2ace656f9549c43d16459}} -\index{Getters and setters@{Getters and setters}!turn\+\_\+left\+\_\+for\+\_\+ms@{turn\+\_\+left\+\_\+for\+\_\+ms}} -\index{turn\+\_\+left\+\_\+for\+\_\+ms@{turn\+\_\+left\+\_\+for\+\_\+ms}!Getters and setters@{Getters and setters}} -\subsubsection{\texorpdfstring{turn\+\_\+left\+\_\+for\+\_\+ms()}{turn\_left\_for\_ms()}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::turn\+\_\+left\+\_\+for\+\_\+ms (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Returns the duration of time that is internally stored and used for turning the racer left. - -\begin{DoxyReturn}{Returns} -Time to turn left in ms -\end{DoxyReturn} - - -Definition at line 394 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -394 \{ -395 \textcolor{keywordflow}{return}(\_turn\_left\_for\_ms); -396 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelgetters_gac0698f02f6a21d9d1f5b9cf2820306cf}\label{group__higherlevelgetters_gac0698f02f6a21d9d1f5b9cf2820306cf}} -\index{Getters and setters@{Getters and setters}!turn\+\_\+right\+\_\+for\+\_\+ms@{turn\+\_\+right\+\_\+for\+\_\+ms}} -\index{turn\+\_\+right\+\_\+for\+\_\+ms@{turn\+\_\+right\+\_\+for\+\_\+ms}!Getters and setters@{Getters and setters}} -\subsubsection{\texorpdfstring{turn\+\_\+right\+\_\+for\+\_\+ms()}{turn\_right\_for\_ms()}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::turn\+\_\+right\+\_\+for\+\_\+ms (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Returns the duration of time that is internally stored and used for turning the racer left. - -\begin{DoxyReturn}{Returns} -Time to turn left in ms -\end{DoxyReturn} - - -Definition at line 401 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -401 \{ -402 \textcolor{keywordflow}{return}(\_turn\_right\_for\_ms); -403 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelgetters_ga62f1c0eea56e27d0853cb58f30eb140d}\label{group__higherlevelgetters_ga62f1c0eea56e27d0853cb58f30eb140d}} -\index{Getters and setters@{Getters and setters}!set\+\_\+inactive@{set\+\_\+inactive}} -\index{set\+\_\+inactive@{set\+\_\+inactive}!Getters and setters@{Getters and setters}} -\subsubsection{\texorpdfstring{set\+\_\+inactive()}{set\_inactive()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+inactive (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sets the coderracer\+\_\+active state to inactive. If start\+\_\+stop() is used -\/ the inactive mode will be entered. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 408 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -408 \{ -409 coderracer\_activ = \textcolor{keyword}{false}; -410 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelgetters_ga415c69930f291d5e06b7211b31843310}\label{group__higherlevelgetters_ga415c69930f291d5e06b7211b31843310}} -\index{Getters and setters@{Getters and setters}!set\+\_\+active@{set\+\_\+active}} -\index{set\+\_\+active@{set\+\_\+active}!Getters and setters@{Getters and setters}} -\subsubsection{\texorpdfstring{set\+\_\+active()}{set\_active()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+active (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sets the coderracer\+\_\+active state to active. If start\+\_\+stop() is used -\/ the active mode will be entered. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 415 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -415 \{ -416 coderracer\_activ = \textcolor{keyword}{true}; -417 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__higherlevelgetters_gaa0ab4d6a754a23ea13664a553bcc8ff2}\label{group__higherlevelgetters_gaa0ab4d6a754a23ea13664a553bcc8ff2}} -\index{Getters and setters@{Getters and setters}!is\+\_\+active@{is\+\_\+active}} -\index{is\+\_\+active@{is\+\_\+active}!Getters and setters@{Getters and setters}} -\subsubsection{\texorpdfstring{is\+\_\+active()}{is\_active()}} -{\footnotesize\ttfamily bool Code\+Racer\+::is\+\_\+active (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Checks if coderracer\+\_\+activ is set. - -coderracer\+\_\+activ is toggled each time the button is pressed. After power on coderracer\+\_\+activ is set to False. \begin{DoxyReturn}{Returns} -True id coderracer\+\_\+activ is set -\/ False if not. -\end{DoxyReturn} - - -Definition at line 424 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -424 \{ -425 \textcolor{keywordflow}{return}(coderracer\_activ); -426 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/d8/d7a/group__lowerlevelfun.tex b/Doku/Doxygen/latex/d8/d7a/group__lowerlevelfun.tex deleted file mode 100644 index 357630e..0000000 --- a/Doku/Doxygen/latex/d8/d7a/group__lowerlevelfun.tex +++ /dev/null @@ -1,99 +0,0 @@ -\hypertarget{group__lowerlevelfun}{}\section{Lower level fun stuff methods} -\label{group__lowerlevelfun}\index{Lower level fun stuff methods@{Lower level fun stuff methods}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -void \hyperlink{group__lowerlevelfun_ga04309a38252639a8eaa43809c04c11c8}{Code\+Racer\+::look\+\_\+around} () -\begin{DoxyCompactList}\small\item\em Fun stuff -\/ will move the servo around after a random amount of time. \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelfun_ga3b6f819fb82d910888fbc87abff1470c}{Code\+Racer\+::kitt} () -\begin{DoxyCompactList}\small\item\em Fun stuff -\/ you know Knightrider... \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerlevelfun_ga04309a38252639a8eaa43809c04c11c8}\label{group__lowerlevelfun_ga04309a38252639a8eaa43809c04c11c8}} -\index{Lower level fun stuff methods@{Lower level fun stuff methods}!look\+\_\+around@{look\+\_\+around}} -\index{look\+\_\+around@{look\+\_\+around}!Lower level fun stuff methods@{Lower level fun stuff methods}} -\subsubsection{\texorpdfstring{look\+\_\+around()}{look\_around()}} -{\footnotesize\ttfamily void Code\+Racer\+::look\+\_\+around (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Fun stuff -\/ will move the servo around after a random amount of time. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 440 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -441 \{ -442 \textcolor{keywordflow}{if} (\_servo\_look\_around\_at\_ms < millis()) \{ -443 \_servo\_look\_around\_at\_ms = millis() + random(FUN\_MIN\_PAUSE\_MS, FUN\_MAX\_PAUSE\_MS); -444 servo\_set\_to\_left(); -445 delay(500); -446 servo\_set\_to\_right(); -447 delay(800); -448 servo\_set\_to\_center(); -449 delay(300); -450 servo\_set\_to\_left(); -451 delay(100); -452 servo\_set\_to\_center(); -453 \} -454 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelfun_ga3b6f819fb82d910888fbc87abff1470c}\label{group__lowerlevelfun_ga3b6f819fb82d910888fbc87abff1470c}} -\index{Lower level fun stuff methods@{Lower level fun stuff methods}!kitt@{kitt}} -\index{kitt@{kitt}!Lower level fun stuff methods@{Lower level fun stuff methods}} -\subsubsection{\texorpdfstring{kitt()}{kitt()}} -{\footnotesize\ttfamily void Code\+Racer\+::kitt (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Fun stuff -\/ you know Knightrider... - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 459 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -460 \{ -461 \textcolor{keywordflow}{if} (millis() - \_last\_led\_switched\_at\_ms > LED\_SWITCH\_MS) \{ -462 \_last\_led\_switched\_at\_ms = millis(); -463 \textcolor{keywordflow}{if} (\_last\_led\_on >= 5) \{ -464 \_led\_count = -1; -465 \} -466 \textcolor{keywordflow}{else} \textcolor{keywordflow}{if} (\_last\_led\_on <= 0) \{ -467 \_led\_count = 1; -468 \} -469 \_last\_led\_on = \_last\_led\_on + \_led\_count; -470 \textcolor{keywordflow}{switch} (\_last\_led\_on) \{ -471 \textcolor{keywordflow}{case} 0: -472 set\_leds\_left\_stop\_frwd\_right(LEDON, LEDOFF, LEDOFF, LEDOFF); -473 \textcolor{keywordflow}{break}; -474 \textcolor{keywordflow}{case} 1: -475 set\_leds\_left\_stop\_frwd\_right(LEDON, LEDOFF, LEDOFF, LEDOFF); -476 \textcolor{keywordflow}{break}; -477 \textcolor{keywordflow}{case} 2: -478 set\_leds\_left\_stop\_frwd\_right(LEDOFF, LEDON, LEDOFF, LEDOFF); -479 \textcolor{keywordflow}{break}; -480 \textcolor{keywordflow}{case} 3: -481 set\_leds\_left\_stop\_frwd\_right(LEDOFF, LEDOFF, LEDON, LEDOFF); -482 \textcolor{keywordflow}{break}; -483 \textcolor{keywordflow}{case} 4: -484 \textcolor{keywordflow}{case} 5: -485 set\_leds\_left\_stop\_frwd\_right(LEDOFF, LEDOFF, LEDOFF, LEDON); -486 \textcolor{keywordflow}{break}; -487 \} -488 \} -489 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/d9/d80/group__higherlevel.tex b/Doku/Doxygen/latex/d9/d80/group__higherlevel.tex deleted file mode 100644 index aaba17f..0000000 --- a/Doku/Doxygen/latex/d9/d80/group__higherlevel.tex +++ /dev/null @@ -1,12 +0,0 @@ -\hypertarget{group__higherlevel}{}\section{Higher level methods, setters and getters} -\label{group__higherlevel}\index{Higher level methods, setters and getters@{Higher level methods, setters and getters}} -\subsection*{Modules} -\begin{DoxyCompactItemize} -\item -\hyperlink{group__higherlevelmeths}{Methods} -\item -\hyperlink{group__higherlevelgetters}{Getters and setters} -\end{DoxyCompactItemize} - - -\subsection{Detailed Description} diff --git a/Doku/Doxygen/latex/da/daf/group__lowerlevelus.tex b/Doku/Doxygen/latex/da/daf/group__lowerlevelus.tex deleted file mode 100644 index e5752a6..0000000 --- a/Doku/Doxygen/latex/da/daf/group__lowerlevelus.tex +++ /dev/null @@ -1,12 +0,0 @@ -\hypertarget{group__lowerlevelus}{}\section{Lower level ultra sonic methods and getters} -\label{group__lowerlevelus}\index{Lower level ultra sonic methods and getters@{Lower level ultra sonic methods and getters}} -\subsection*{Modules} -\begin{DoxyCompactItemize} -\item -\hyperlink{group__lowerlevelusmeths}{Methods} -\item -\hyperlink{group__lowerlevelusgetters}{Setters and getters} -\end{DoxyCompactItemize} - - -\subsection{Detailed Description} diff --git a/Doku/Doxygen/latex/db/dd5/group__lowerlevelservomeths.tex b/Doku/Doxygen/latex/db/dd5/group__lowerlevelservomeths.tex deleted file mode 100644 index fa51feb..0000000 --- a/Doku/Doxygen/latex/db/dd5/group__lowerlevelservomeths.tex +++ /dev/null @@ -1,233 +0,0 @@ -\hypertarget{group__lowerlevelservomeths}{}\section{Methods} -\label{group__lowerlevelservomeths}\index{Methods@{Methods}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -void \hyperlink{group__lowerlevelservomeths_ga687beb327e20f4d0541d1ac9e29c01c3}{Code\+Racer\+::servo\+\_\+settings} (uint8\+\_\+t pos\+\_\+center, uint8\+\_\+t pos\+\_\+left, uint8\+\_\+t pos\+\_\+right, uint8\+\_\+t sweep\+\_\+left\+\_\+pos, uint8\+\_\+t sweep\+\_\+right\+\_\+pos) -\begin{DoxyCompactList}\small\item\em Overwrites the default settings taken from header file by the parameters given to this method. \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelservomeths_ga1e9afe1f27dfc9796b4c9b3dba245365}{Code\+Racer\+::servo\+\_\+sweep} () -\begin{DoxyCompactList}\small\item\em Turns sweeping of the servo from left to right and back on. \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelservomeths_gaac73bf99cf2d19f7b1987156aa842b74}{Code\+Racer\+::servo\+\_\+set\+\_\+to\+\_\+right} () -\begin{DoxyCompactList}\small\item\em Drives the servo to the postion that is defined by \#servo\+\_\+right\+\_\+pos. \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelservomeths_gaef7d1903b65a0a8ab4fafdc53080b07d}{Code\+Racer\+::servo\+\_\+set\+\_\+to\+\_\+left} () -\begin{DoxyCompactList}\small\item\em Drives the servo to the postion that is defined by \#servo\+\_\+left\+\_\+pos. \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelservomeths_gad1f28aa91079e88fc3093e3074edfb32}{Code\+Racer\+::servo\+\_\+set\+\_\+to\+\_\+center} () -\begin{DoxyCompactList}\small\item\em Drives the servo to the postion that is defined by \#servo\+\_\+center\+\_\+pos. \end{DoxyCompactList}\item -uint8\+\_\+t \hyperlink{group__lowerlevelservomeths_ga0149226288bff2290d52ed1cbd674edd}{Code\+Racer\+::servo\+\_\+set\+\_\+position\+\_\+wait} (uint8\+\_\+t position) -\begin{DoxyCompactList}\small\item\em Drive the servo to the postion given to this method. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelservomeths_gab8831340049de6dbddeda997745725e6}{Code\+Racer\+::servo\+\_\+set\+\_\+position} (uint8\+\_\+t position) -\begin{DoxyCompactList}\small\item\em Drive the servo to the postion given to this method. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerlevelservomeths_ga687beb327e20f4d0541d1ac9e29c01c3}\label{group__lowerlevelservomeths_ga687beb327e20f4d0541d1ac9e29c01c3}} -\index{Methods@{Methods}!servo\+\_\+settings@{servo\+\_\+settings}} -\index{servo\+\_\+settings@{servo\+\_\+settings}!Methods@{Methods}} -\subsubsection{\texorpdfstring{servo\+\_\+settings()}{servo\_settings()}} -{\footnotesize\ttfamily void Code\+Racer\+::servo\+\_\+settings (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{pos\+\_\+center, }\item[{uint8\+\_\+t}]{pos\+\_\+left, }\item[{uint8\+\_\+t}]{pos\+\_\+right, }\item[{uint8\+\_\+t}]{sweep\+\_\+left\+\_\+pos, }\item[{uint8\+\_\+t}]{sweep\+\_\+right\+\_\+pos }\end{DoxyParamCaption})} - - - -Overwrites the default settings taken from header file by the parameters given to this method. - - -\begin{DoxyParams}{Parameters} -{\em pos\+\_\+center} & The postion at which the servo moves to straight forward. Default is 90. Allowed 10 $<$= pos\+\_\+center $<$= 170. \\ -\hline -{\em pos\+\_\+left} & The postion at which the servo moves to the left. Default is 170. Allowed 10 $<$= pos\+\_\+center $<$= 170. \\ -\hline -{\em pos\+\_\+right} & The postion at which the servo moves to the right. Default is 10. Allowed 10 $<$= pos\+\_\+center $<$= 170. \\ -\hline -{\em sweep\+\_\+left\+\_\+pos} & If the servo is sweeping from left to the right -\/ this defines the most left postion. Default is 140. Allowed 10 $<$= pos\+\_\+center $<$= 170. \\ -\hline -{\em sweep\+\_\+right\+\_\+pos} & If the servo is sweeping from left to the right -\/ this defines the most right postion. Default is 40. Allowed 10 $<$= pos\+\_\+center $<$= 170. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 510 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -511 \{ -512 servo\_center\_pos = pos\_center; -513 servo\_left\_pos = pos\_left; -514 servo\_right\_pos = pos\_right; -515 servo\_sweep\_left\_pos = sweep\_left\_pos; -516 servo\_sweep\_right\_pos = sweep\_right\_pos; -517 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservomeths_ga1e9afe1f27dfc9796b4c9b3dba245365}\label{group__lowerlevelservomeths_ga1e9afe1f27dfc9796b4c9b3dba245365}} -\index{Methods@{Methods}!servo\+\_\+sweep@{servo\+\_\+sweep}} -\index{servo\+\_\+sweep@{servo\+\_\+sweep}!Methods@{Methods}} -\subsubsection{\texorpdfstring{servo\+\_\+sweep()}{servo\_sweep()}} -{\footnotesize\ttfamily void Code\+Racer\+::servo\+\_\+sweep (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Turns sweeping of the servo from left to right and back on. - -The sweeping range is defind by \#servo\+\_\+sweep\+\_\+left\+\_\+pos and \#servo\+\_\+sweep\+\_\+right\+\_\+pos attributes. Both can be set by either servo\+\_\+settings() or as public members. Every time servo\+\_\+sweep() is called the servo is driven by 5 steps until either \#servo\+\_\+sweep\+\_\+left\+\_\+pos or \#servo\+\_\+sweep\+\_\+right\+\_\+pos is reached. Then it will turn the direction and step to the other side every time this method is called. \begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 526 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -527 \{ -528 uint8\_t position; -529 \_servo\_sweep = \textcolor{keyword}{true}; -530 \textcolor{keywordflow}{if} (millis() - \_servo\_position\_set\_at\_ms > SERVO\_SWEEP\_MS) \{ -531 position = \_servo\_position + \_servo\_sweep\_step; -532 \textcolor{comment}{//sprintf(\_debugmsg,"[%s] current position=%ld newpostion=%ld", \_\_func\_\_, \_servo\_position, - position);} -533 \textcolor{keywordflow}{if} ((position >= servo\_sweep\_left\_pos) || (position >= SERVO\_MAX\_POSITION)) \{ -534 position = servo\_sweep\_left\_pos; -535 \_servo\_sweep\_step = SERVO\_SWEEP\_TO\_RIGHT\_STEP; -536 \} -537 \textcolor{keywordflow}{if} ((position <= servo\_sweep\_right\_pos) || (position <= SERVO\_MIN\_POSITION)) \{ -538 position = servo\_sweep\_right\_pos; -539 \_servo\_sweep\_step = SERVO\_SWEEP\_TO\_LEFT\_STEP; -540 \} -541 \_servo\_set\_position(position); -542 \} -543 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservomeths_gaac73bf99cf2d19f7b1987156aa842b74}\label{group__lowerlevelservomeths_gaac73bf99cf2d19f7b1987156aa842b74}} -\index{Methods@{Methods}!servo\+\_\+set\+\_\+to\+\_\+right@{servo\+\_\+set\+\_\+to\+\_\+right}} -\index{servo\+\_\+set\+\_\+to\+\_\+right@{servo\+\_\+set\+\_\+to\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{servo\+\_\+set\+\_\+to\+\_\+right()}{servo\_set\_to\_right()}} -{\footnotesize\ttfamily void Code\+Racer\+::servo\+\_\+set\+\_\+to\+\_\+right (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Drives the servo to the postion that is defined by \#servo\+\_\+right\+\_\+pos. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 548 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -549 \{ -550 servo\_set\_position\_wait(servo\_right\_pos); -551 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservomeths_gaef7d1903b65a0a8ab4fafdc53080b07d}\label{group__lowerlevelservomeths_gaef7d1903b65a0a8ab4fafdc53080b07d}} -\index{Methods@{Methods}!servo\+\_\+set\+\_\+to\+\_\+left@{servo\+\_\+set\+\_\+to\+\_\+left}} -\index{servo\+\_\+set\+\_\+to\+\_\+left@{servo\+\_\+set\+\_\+to\+\_\+left}!Methods@{Methods}} -\subsubsection{\texorpdfstring{servo\+\_\+set\+\_\+to\+\_\+left()}{servo\_set\_to\_left()}} -{\footnotesize\ttfamily void Code\+Racer\+::servo\+\_\+set\+\_\+to\+\_\+left (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Drives the servo to the postion that is defined by \#servo\+\_\+left\+\_\+pos. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 556 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -557 \{ -558 servo\_set\_position\_wait(servo\_left\_pos); -559 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservomeths_gad1f28aa91079e88fc3093e3074edfb32}\label{group__lowerlevelservomeths_gad1f28aa91079e88fc3093e3074edfb32}} -\index{Methods@{Methods}!servo\+\_\+set\+\_\+to\+\_\+center@{servo\+\_\+set\+\_\+to\+\_\+center}} -\index{servo\+\_\+set\+\_\+to\+\_\+center@{servo\+\_\+set\+\_\+to\+\_\+center}!Methods@{Methods}} -\subsubsection{\texorpdfstring{servo\+\_\+set\+\_\+to\+\_\+center()}{servo\_set\_to\_center()}} -{\footnotesize\ttfamily void Code\+Racer\+::servo\+\_\+set\+\_\+to\+\_\+center (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Drives the servo to the postion that is defined by \#servo\+\_\+center\+\_\+pos. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 564 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -565 \{ -566 servo\_set\_position\_wait(servo\_center\_pos); -567 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservomeths_ga0149226288bff2290d52ed1cbd674edd}\label{group__lowerlevelservomeths_ga0149226288bff2290d52ed1cbd674edd}} -\index{Methods@{Methods}!servo\+\_\+set\+\_\+position\+\_\+wait@{servo\+\_\+set\+\_\+position\+\_\+wait}} -\index{servo\+\_\+set\+\_\+position\+\_\+wait@{servo\+\_\+set\+\_\+position\+\_\+wait}!Methods@{Methods}} -\subsubsection{\texorpdfstring{servo\+\_\+set\+\_\+position\+\_\+wait()}{servo\_set\_position\_wait()}} -{\footnotesize\ttfamily uint8\+\_\+t Code\+Racer\+::servo\+\_\+set\+\_\+position\+\_\+wait (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{position }\end{DoxyParamCaption})} - - - -Drive the servo to the postion given to this method. - -The method will wait until the servo has reached its new position. -\begin{DoxyParams}{Parameters} -{\em position} & Position the servo will be drived to. Allowed are values 10$<$=postion$<$=170. 10 is at the right hand side, 170 at the left hand side. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The new servo position -\end{DoxyReturn} - - -Definition at line 575 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -576 \{ -577 \_servo\_sweep = \textcolor{keyword}{false}; -578 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} wait\_time\_ms = \_servo\_set\_position(position); -579 delay(wait\_time\_ms); -580 \textcolor{keywordflow}{return}(\_servo\_position); -581 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelservomeths_gab8831340049de6dbddeda997745725e6}\label{group__lowerlevelservomeths_gab8831340049de6dbddeda997745725e6}} -\index{Methods@{Methods}!servo\+\_\+set\+\_\+position@{servo\+\_\+set\+\_\+position}} -\index{servo\+\_\+set\+\_\+position@{servo\+\_\+set\+\_\+position}!Methods@{Methods}} -\subsubsection{\texorpdfstring{servo\+\_\+set\+\_\+position()}{servo\_set\_position()}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::servo\+\_\+set\+\_\+position (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{position }\end{DoxyParamCaption})} - - - -Drive the servo to the postion given to this method. - -The method will not wait until the servo has reached its new position. -\begin{DoxyParams}{Parameters} -{\em position} & Position the servo will be drived to. Allowed are values 10$<$=postion$<$=170. 10 is at the right hand side, 170 at the left hand side. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The time in ms the servo will need to reach the new position -\end{DoxyReturn} - - -Definition at line 589 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -590 \{ -591 \_servo\_sweep = \textcolor{keyword}{false}; -592 \textcolor{keywordtype}{unsigned} \textcolor{keywordtype}{long} wait\_time\_ms = \_servo\_set\_position(position); -593 \textcolor{keywordflow}{return}(wait\_time\_ms); -594 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/db/ddd/group__lowerlevelusgetters.tex b/Doku/Doxygen/latex/db/ddd/group__lowerlevelusgetters.tex deleted file mode 100644 index 40cfb32..0000000 --- a/Doku/Doxygen/latex/db/ddd/group__lowerlevelusgetters.tex +++ /dev/null @@ -1,121 +0,0 @@ -\hypertarget{group__lowerlevelusgetters}{}\section{Setters and getters} -\label{group__lowerlevelusgetters}\index{Setters and getters@{Setters and getters}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -void \hyperlink{group__lowerlevelusgetters_gaa7c5a6563a5736ed38d12f616de480df}{Code\+Racer\+::usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+cm} (unsigned long stop\+\_\+distance\+\_\+cm) -\begin{DoxyCompactList}\small\item\em Sets the stop distance in cm. \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelusgetters_ga2f06c193ae86c5b1cba450caf5adf146}{Code\+Racer\+::usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+us} (unsigned long stop\+\_\+distance\+\_\+us) -\begin{DoxyCompactList}\small\item\em Sets the stop distance in cm. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusgetters_ga917b90f21e731ef5f690d5198e7f4d3e}{Code\+Racer\+::usonic\+\_\+distance\+\_\+us} () -\begin{DoxyCompactList}\small\item\em Returns the last measured distance in microseconds. \end{DoxyCompactList}\item -unsigned long \hyperlink{group__lowerlevelusgetters_gad59842c14196598e55644b2a22621454}{Code\+Racer\+::usonic\+\_\+distance\+\_\+cm} () -\begin{DoxyCompactList}\small\item\em Returns the last measured distance in cm. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerlevelusgetters_gaa7c5a6563a5736ed38d12f616de480df}\label{group__lowerlevelusgetters_gaa7c5a6563a5736ed38d12f616de480df}} -\index{Setters and getters@{Setters and getters}!usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+cm@{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+cm}} -\index{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+cm@{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+cm}!Setters and getters@{Setters and getters}} -\subsubsection{\texorpdfstring{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+cm()}{usonic\_set\_stop\_distance\_cm()}} -{\footnotesize\ttfamily void Code\+Racer\+::usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+cm (\begin{DoxyParamCaption}\item[{unsigned long}]{stop\+\_\+distance\+\_\+cm }\end{DoxyParamCaption})} - - - -Sets the stop distance in cm. - -If start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance() is used and distance measured with one of the measurement methods -\/ the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. Internally the stop distance will be set as both -\/ in cm and in microseconds. -\begin{DoxyParams}{Parameters} -{\em stop\+\_\+distance\+\_\+cm} & Distance in cm the racer will be stopped if that features was enabled by start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance() before. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 825 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -826 \{ -827 \_usonic\_stop\_distance\_us = stop\_distance\_cm * 58.14; -828 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusgetters_ga2f06c193ae86c5b1cba450caf5adf146}\label{group__lowerlevelusgetters_ga2f06c193ae86c5b1cba450caf5adf146}} -\index{Setters and getters@{Setters and getters}!usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+us@{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+us}} -\index{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+us@{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+us}!Setters and getters@{Setters and getters}} -\subsubsection{\texorpdfstring{usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+us()}{usonic\_set\_stop\_distance\_us()}} -{\footnotesize\ttfamily void Code\+Racer\+::usonic\+\_\+set\+\_\+stop\+\_\+distance\+\_\+us (\begin{DoxyParamCaption}\item[{unsigned long}]{stop\+\_\+distance\+\_\+us }\end{DoxyParamCaption})} - - - -Sets the stop distance in cm. - -If start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance() is used and distance measured with one of the measurement methods -\/ the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. Internally the stop distance will be set as both -\/ in cm and in microseconds. -\begin{DoxyParams}{Parameters} -{\em stop\+\_\+distance\+\_\+us} & Distance in cm the racer will be stopped if that features was enabled by start\+\_\+stop\+\_\+at\+\_\+min\+\_\+distance() before. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 837 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -838 \{ -839 \_usonic\_stop\_distance\_us = stop\_distance\_us; -840 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusgetters_ga917b90f21e731ef5f690d5198e7f4d3e}\label{group__lowerlevelusgetters_ga917b90f21e731ef5f690d5198e7f4d3e}} -\index{Setters and getters@{Setters and getters}!usonic\+\_\+distance\+\_\+us@{usonic\+\_\+distance\+\_\+us}} -\index{usonic\+\_\+distance\+\_\+us@{usonic\+\_\+distance\+\_\+us}!Setters and getters@{Setters and getters}} -\subsubsection{\texorpdfstring{usonic\+\_\+distance\+\_\+us()}{usonic\_distance\_us()}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+distance\+\_\+us (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Returns the last measured distance in microseconds. - -\begin{DoxyReturn}{Returns} -Distance in microseconds -\end{DoxyReturn} - - -Definition at line 845 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -845 \{ -846 \textcolor{keywordflow}{return}(\_usonic\_distance\_us); -847 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelusgetters_gad59842c14196598e55644b2a22621454}\label{group__lowerlevelusgetters_gad59842c14196598e55644b2a22621454}} -\index{Setters and getters@{Setters and getters}!usonic\+\_\+distance\+\_\+cm@{usonic\+\_\+distance\+\_\+cm}} -\index{usonic\+\_\+distance\+\_\+cm@{usonic\+\_\+distance\+\_\+cm}!Setters and getters@{Setters and getters}} -\subsubsection{\texorpdfstring{usonic\+\_\+distance\+\_\+cm()}{usonic\_distance\_cm()}} -{\footnotesize\ttfamily unsigned long Code\+Racer\+::usonic\+\_\+distance\+\_\+cm (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Returns the last measured distance in cm. - -\begin{DoxyReturn}{Returns} -Distance in cm -\end{DoxyReturn} - - -Definition at line 852 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -852 \{ -853 \textcolor{keywordflow}{return}(\_usonic\_distance\_cm); -854 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/dd/dff/group__lowerlevelledmeths.tex b/Doku/Doxygen/latex/dd/dff/group__lowerlevelledmeths.tex deleted file mode 100644 index 8705b88..0000000 --- a/Doku/Doxygen/latex/dd/dff/group__lowerlevelledmeths.tex +++ /dev/null @@ -1,134 +0,0 @@ -\hypertarget{group__lowerlevelledmeths}{}\section{Methods} -\label{group__lowerlevelledmeths}\index{Methods@{Methods}} -\subsection*{Functions} -\begin{DoxyCompactItemize} -\item -void \hyperlink{group__lowerlevelledmeths_gab2514ca3994de3d64337dd6536fa6ef3}{Code\+Racer\+::set\+\_\+leds\+\_\+left\+\_\+stop\+\_\+frwd\+\_\+right} (ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled) -\begin{DoxyCompactList}\small\item\em Sets all of the 4 L\+E\+Ds to a ledstate (L\+E\+D\+ON, L\+E\+D\+O\+FF) \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelledmeths_gab4319e66963b1b71a34370d73962fa78}{Code\+Racer\+::set\+\_\+leds\+\_\+all} (ledstate alleds) -\begin{DoxyCompactList}\small\item\em Sets all of the 4 L\+E\+Ds to the same ledstate (L\+E\+D\+ON, L\+E\+D\+O\+FF) \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelledmeths_gaa3f2ad08103127f2cb49344c33b666ea}{Code\+Racer\+::set\+\_\+leds\+\_\+all\+\_\+off} () -\begin{DoxyCompactList}\small\item\em Sets all of the 4 L\+E\+Ds to the ledstate L\+E\+D\+O\+FF. \end{DoxyCompactList}\item -void \hyperlink{group__lowerlevelledmeths_ga0c8b3d6ce992e1dcfd13fd86c9f89846}{Code\+Racer\+::set\+\_\+leds\+\_\+all\+\_\+on} () -\begin{DoxyCompactList}\small\item\em Sets all of the 4 L\+E\+Ds to the ledstate L\+E\+D\+ON. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\subsection{Detailed Description} - - -\subsection{Function Documentation} -\mbox{\Hypertarget{group__lowerlevelledmeths_gab2514ca3994de3d64337dd6536fa6ef3}\label{group__lowerlevelledmeths_gab2514ca3994de3d64337dd6536fa6ef3}} -\index{Methods@{Methods}!set\+\_\+leds\+\_\+left\+\_\+stop\+\_\+frwd\+\_\+right@{set\+\_\+leds\+\_\+left\+\_\+stop\+\_\+frwd\+\_\+right}} -\index{set\+\_\+leds\+\_\+left\+\_\+stop\+\_\+frwd\+\_\+right@{set\+\_\+leds\+\_\+left\+\_\+stop\+\_\+frwd\+\_\+right}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+leds\+\_\+left\+\_\+stop\+\_\+frwd\+\_\+right()}{set\_leds\_left\_stop\_frwd\_right()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+leds\+\_\+left\+\_\+stop\+\_\+frwd\+\_\+right (\begin{DoxyParamCaption}\item[{ledstate}]{leftled, }\item[{ledstate}]{stopled, }\item[{ledstate}]{frwdled, }\item[{ledstate}]{rightled }\end{DoxyParamCaption})} - - - -Sets all of the 4 L\+E\+Ds to a ledstate (L\+E\+D\+ON, L\+E\+D\+O\+FF) - - -\begin{DoxyParams}{Parameters} -{\em leftled} & set state of status left L\+ED (most left yellow led) \\ -\hline -{\em stopled} & set state of status stop L\+ED (red led) \\ -\hline -{\em frwdled} & set state of status forward L\+ED (green or blue led) \\ -\hline -{\em rightled} & set state of status right L\+ED (most right yellow led) \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 1037 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -1037 - \{ -1038 digitalWrite(\_led\_left\_pin, leftled); -1039 digitalWrite(\_led\_frwd\_pin, frwdled); -1040 digitalWrite(\_led\_right\_pin, rightled); -1041 digitalWrite(\_led\_stop\_pin, stopled); -1042 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelledmeths_gab4319e66963b1b71a34370d73962fa78}\label{group__lowerlevelledmeths_gab4319e66963b1b71a34370d73962fa78}} -\index{Methods@{Methods}!set\+\_\+leds\+\_\+all@{set\+\_\+leds\+\_\+all}} -\index{set\+\_\+leds\+\_\+all@{set\+\_\+leds\+\_\+all}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+leds\+\_\+all()}{set\_leds\_all()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+leds\+\_\+all (\begin{DoxyParamCaption}\item[{ledstate}]{alleds }\end{DoxyParamCaption})} - - - -Sets all of the 4 L\+E\+Ds to the same ledstate (L\+E\+D\+ON, L\+E\+D\+O\+FF) - - -\begin{DoxyParams}{Parameters} -{\em alleds} & set state to all status L\+E\+Ds \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 1048 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -1048 \{ -1049 digitalWrite(\_led\_left\_pin, alleds); -1050 digitalWrite(\_led\_frwd\_pin, alleds); -1051 digitalWrite(\_led\_right\_pin, alleds); -1052 digitalWrite(\_led\_stop\_pin, alleds); -1053 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelledmeths_gaa3f2ad08103127f2cb49344c33b666ea}\label{group__lowerlevelledmeths_gaa3f2ad08103127f2cb49344c33b666ea}} -\index{Methods@{Methods}!set\+\_\+leds\+\_\+all\+\_\+off@{set\+\_\+leds\+\_\+all\+\_\+off}} -\index{set\+\_\+leds\+\_\+all\+\_\+off@{set\+\_\+leds\+\_\+all\+\_\+off}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+leds\+\_\+all\+\_\+off()}{set\_leds\_all\_off()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+leds\+\_\+all\+\_\+off (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sets all of the 4 L\+E\+Ds to the ledstate L\+E\+D\+O\+FF. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 1058 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -1058 \{ -1059 set\_leds\_all(LEDOFF); -1060 \} -\end{DoxyCode} -\mbox{\Hypertarget{group__lowerlevelledmeths_ga0c8b3d6ce992e1dcfd13fd86c9f89846}\label{group__lowerlevelledmeths_ga0c8b3d6ce992e1dcfd13fd86c9f89846}} -\index{Methods@{Methods}!set\+\_\+leds\+\_\+all\+\_\+on@{set\+\_\+leds\+\_\+all\+\_\+on}} -\index{set\+\_\+leds\+\_\+all\+\_\+on@{set\+\_\+leds\+\_\+all\+\_\+on}!Methods@{Methods}} -\subsubsection{\texorpdfstring{set\+\_\+leds\+\_\+all\+\_\+on()}{set\_leds\_all\_on()}} -{\footnotesize\ttfamily void Code\+Racer\+::set\+\_\+leds\+\_\+all\+\_\+on (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sets all of the 4 L\+E\+Ds to the ledstate L\+E\+D\+ON. - -\begin{DoxyReturn}{Returns} -nothing -\end{DoxyReturn} - - -Definition at line 1065 of file Code\+Racer.\+cpp. - - -\begin{DoxyCode} -1065 \{ -1066 set\_leds\_all(LEDON); -1067 \} -\end{DoxyCode} diff --git a/Doku/Doxygen/latex/dir_11f10faf8e1af149a19b120728e5c8cd.tex b/Doku/Doxygen/latex/dir_11f10faf8e1af149a19b120728e5c8cd.tex deleted file mode 100644 index a78c840..0000000 --- a/Doku/Doxygen/latex/dir_11f10faf8e1af149a19b120728e5c8cd.tex +++ /dev/null @@ -1,2 +0,0 @@ -\hypertarget{dir_11f10faf8e1af149a19b120728e5c8cd}{}\section{C\+:/\+Users/jnoack/\+Documents/\+Arduino/libraries/\+Code\+Racer Directory Reference} -\label{dir_11f10faf8e1af149a19b120728e5c8cd}\index{C\+:/\+Users/jnoack/\+Documents/\+Arduino/libraries/\+Code\+Racer Directory Reference@{C\+:/\+Users/jnoack/\+Documents/\+Arduino/libraries/\+Code\+Racer Directory Reference}} diff --git a/Doku/Doxygen/latex/dir_481cc946b8a81b8d9363a4aad6201160.tex b/Doku/Doxygen/latex/dir_481cc946b8a81b8d9363a4aad6201160.tex deleted file mode 100644 index 20f5b75..0000000 --- a/Doku/Doxygen/latex/dir_481cc946b8a81b8d9363a4aad6201160.tex +++ /dev/null @@ -1,5 +0,0 @@ -\hypertarget{dir_481cc946b8a81b8d9363a4aad6201160}{}\section{C\+:/\+Users/jnoack/\+Documents/\+Arduino/libraries Directory Reference} -\label{dir_481cc946b8a81b8d9363a4aad6201160}\index{C\+:/\+Users/jnoack/\+Documents/\+Arduino/libraries Directory Reference@{C\+:/\+Users/jnoack/\+Documents/\+Arduino/libraries Directory Reference}} -\subsection*{Directories} -\begin{DoxyCompactItemize} -\end{DoxyCompactItemize} diff --git a/Doku/Doxygen/latex/dir_a991eec27578c865874ede3d8ec657c2.tex b/Doku/Doxygen/latex/dir_a991eec27578c865874ede3d8ec657c2.tex deleted file mode 100644 index c0aec85..0000000 --- a/Doku/Doxygen/latex/dir_a991eec27578c865874ede3d8ec657c2.tex +++ /dev/null @@ -1,2 +0,0 @@ -\hypertarget{dir_a991eec27578c865874ede3d8ec657c2}{}\section{C\+:/\+Users/jnoack/\+Documents/\+Arduino Directory Reference} -\label{dir_a991eec27578c865874ede3d8ec657c2}\index{C\+:/\+Users/jnoack/\+Documents/\+Arduino Directory Reference@{C\+:/\+Users/jnoack/\+Documents/\+Arduino Directory Reference}} diff --git a/Doku/Doxygen/latex/doxygen.sty b/Doku/Doxygen/latex/doxygen.sty deleted file mode 100644 index e457acc..0000000 --- a/Doku/Doxygen/latex/doxygen.sty +++ /dev/null @@ -1,503 +0,0 @@ -\NeedsTeXFormat{LaTeX2e} -\ProvidesPackage{doxygen} - -% Packages used by this style file -\RequirePackage{alltt} -\RequirePackage{array} -\RequirePackage{calc} -\RequirePackage{float} -\RequirePackage{ifthen} -\RequirePackage{verbatim} -\RequirePackage[table]{xcolor} -\RequirePackage{longtable} -\RequirePackage{tabu} -\RequirePackage{tabularx} -\RequirePackage{multirow} - -%---------- Internal commands used in this style file ---------------- - -\newcommand{\ensurespace}[1]{% - \begingroup% - \setlength{\dimen@}{#1}% - \vskip\z@\@plus\dimen@% - \penalty -100\vskip\z@\@plus -\dimen@% - \vskip\dimen@% - \penalty 9999% - \vskip -\dimen@% - \vskip\z@skip% hide the previous |\vskip| from |\addvspace| - \endgroup% -} - -\newcommand{\DoxyLabelFont}{} -\newcommand{\entrylabel}[1]{% - {% - \parbox[b]{\labelwidth-4pt}{% - \makebox[0pt][l]{\DoxyLabelFont#1}% - \vspace{1.5\baselineskip}% - }% - }% -} - -\newenvironment{DoxyDesc}[1]{% - \ensurespace{4\baselineskip}% - \begin{list}{}{% - \settowidth{\labelwidth}{20pt}% - \setlength{\parsep}{0pt}% - \setlength{\itemsep}{0pt}% - \setlength{\leftmargin}{\labelwidth+\labelsep}% - \renewcommand{\makelabel}{\entrylabel}% - }% - \item[#1]% -}{% - \end{list}% -} - -\newsavebox{\xrefbox} -\newlength{\xreflength} -\newcommand{\xreflabel}[1]{% - \sbox{\xrefbox}{#1}% - \setlength{\xreflength}{\wd\xrefbox}% - \ifthenelse{\xreflength>\labelwidth}{% - \begin{minipage}{\textwidth}% - \setlength{\parindent}{0pt}% - \hangindent=15pt\bfseries #1\vspace{1.2\itemsep}% - \end{minipage}% - }{% - \parbox[b]{\labelwidth}{\makebox[0pt][l]{\textbf{#1}}}% - }% -} - -%---------- Commands used by doxygen LaTeX output generator ---------- - -% Used by
 ... 
-\newenvironment{DoxyPre}{% - \small% - \begin{alltt}% -}{% - \end{alltt}% - \normalsize% -} - -% Used by @code ... @endcode -\newenvironment{DoxyCode}{% - \par% - \scriptsize% - \begin{alltt}% -}{% - \end{alltt}% - \normalsize% -} - -% Used by @example, @include, @includelineno and @dontinclude -\newenvironment{DoxyCodeInclude}{% - \DoxyCode% -}{% - \endDoxyCode% -} - -% Used by @verbatim ... @endverbatim -\newenvironment{DoxyVerb}{% - \footnotesize% - \verbatim% -}{% - \endverbatim% - \normalsize% -} - -% Used by @verbinclude -\newenvironment{DoxyVerbInclude}{% - \DoxyVerb% -}{% - \endDoxyVerb% -} - -% Used by numbered lists (using '-#' or
    ...
) -\newenvironment{DoxyEnumerate}{% - \enumerate% -}{% - \endenumerate% -} - -% Used by bullet lists (using '-', @li, @arg, or
    ...
) -\newenvironment{DoxyItemize}{% - \itemize% -}{% - \enditemize% -} - -% Used by description lists (using
...
) -\newenvironment{DoxyDescription}{% - \description% -}{% - \enddescription% -} - -% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc -% (only if caption is specified) -\newenvironment{DoxyImage}{% - \begin{figure}[H]% - \begin{center}% -}{% - \end{center}% - \end{figure}% -} - -% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc -% (only if no caption is specified) -\newenvironment{DoxyImageNoCaption}{% - \begin{center}% -}{% - \end{center}% -} - -% Used by @attention -\newenvironment{DoxyAttention}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @author and @authors -\newenvironment{DoxyAuthor}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @date -\newenvironment{DoxyDate}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @invariant -\newenvironment{DoxyInvariant}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @note -\newenvironment{DoxyNote}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @post -\newenvironment{DoxyPostcond}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @pre -\newenvironment{DoxyPrecond}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @copyright -\newenvironment{DoxyCopyright}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @remark -\newenvironment{DoxyRemark}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @return and @returns -\newenvironment{DoxyReturn}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @since -\newenvironment{DoxySince}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @see -\newenvironment{DoxySeeAlso}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @version -\newenvironment{DoxyVersion}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @warning -\newenvironment{DoxyWarning}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @internal -\newenvironment{DoxyInternal}[1]{% - \paragraph*{#1}% -}{% -} - -% Used by @par and @paragraph -\newenvironment{DoxyParagraph}[1]{% - \begin{list}{}{% - \settowidth{\labelwidth}{40pt}% - \setlength{\leftmargin}{\labelwidth}% - \setlength{\parsep}{0pt}% - \setlength{\itemsep}{-4pt}% - \renewcommand{\makelabel}{\entrylabel}% - }% - \item[#1]% -}{% - \end{list}% -} - -% Used by parameter lists -\newenvironment{DoxyParams}[2][]{% - \tabulinesep=1mm% - \par% - \ifthenelse{\equal{#1}{}}% - {\begin{longtabu} spread 0pt [l]{|X[-1,l]|X[-1,l]|}}% name + description - {\ifthenelse{\equal{#1}{1}}% - {\begin{longtabu} spread 0pt [l]{|X[-1,l]|X[-1,l]|X[-1,l]|}}% in/out + name + desc - {\begin{longtabu} spread 0pt [l]{|X[-1,l]|X[-1,l]|X[-1,l]|X[-1,l]|}}% in/out + type + name + desc - } - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu}% - \vspace{6pt}% -} - -% Used for fields of simple structs -\newenvironment{DoxyFields}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu} spread 0pt [l]{|X[-1,r]|X[-1,l]|X[-1,l]|}% - \multicolumn{3}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{3}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu}% - \vspace{6pt}% -} - -% Used for fields simple class style enums -\newenvironment{DoxyEnumFields}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu} spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu}% - \vspace{6pt}% -} - -% Used for parameters within a detailed function description -\newenvironment{DoxyParamCaption}{% - \renewcommand{\item}[2][]{\\ \hspace*{2.0cm} ##1 {\em ##2}}% -}{% -} - -% Used by return value lists -\newenvironment{DoxyRetVals}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu} spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu}% - \vspace{6pt}% -} - -% Used by exception lists -\newenvironment{DoxyExceptions}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu} spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu}% - \vspace{6pt}% -} - -% Used by template parameter lists -\newenvironment{DoxyTemplParams}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu} spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu}% - \vspace{6pt}% -} - -% Used for member lists -\newenvironment{DoxyCompactItemize}{% - \begin{itemize}% - \setlength{\itemsep}{-3pt}% - \setlength{\parsep}{0pt}% - \setlength{\topsep}{0pt}% - \setlength{\partopsep}{0pt}% -}{% - \end{itemize}% -} - -% Used for member descriptions -\newenvironment{DoxyCompactList}{% - \begin{list}{}{% - \setlength{\leftmargin}{0.5cm}% - \setlength{\itemsep}{0pt}% - \setlength{\parsep}{0pt}% - \setlength{\topsep}{0pt}% - \renewcommand{\makelabel}{\hfill}% - }% -}{% - \end{list}% -} - -% Used for reference lists (@bug, @deprecated, @todo, etc.) -\newenvironment{DoxyRefList}{% - \begin{list}{}{% - \setlength{\labelwidth}{10pt}% - \setlength{\leftmargin}{\labelwidth}% - \addtolength{\leftmargin}{\labelsep}% - \renewcommand{\makelabel}{\xreflabel}% - }% -}{% - \end{list}% -} - -% Used by @bug, @deprecated, @todo, etc. -\newenvironment{DoxyRefDesc}[1]{% - \begin{list}{}{% - \renewcommand\makelabel[1]{\textbf{##1}}% - \settowidth\labelwidth{\makelabel{#1}}% - \setlength\leftmargin{\labelwidth+\labelsep}% - }% -}{% - \end{list}% -} - -% Used by parameter lists and simple sections -\newenvironment{Desc} -{\begin{list}{}{% - \settowidth{\labelwidth}{20pt}% - \setlength{\parsep}{0pt}% - \setlength{\itemsep}{0pt}% - \setlength{\leftmargin}{\labelwidth+\labelsep}% - \renewcommand{\makelabel}{\entrylabel}% - } -}{% - \end{list}% -} - -% Used by tables -\newcommand{\PBS}[1]{\let\temp=\\#1\let\\=\temp}% -\newenvironment{TabularC}[1]% -{\tabulinesep=1mm -\begin{longtabu} spread 0pt [c]{*#1{|X[-1]}|}}% -{\end{longtabu}\par}% - -\newenvironment{TabularNC}[1]% -{\begin{tabu} spread 0pt [l]{*#1{|X[-1]}|}}% -{\end{tabu}\par}% - -% Used for member group headers -\newenvironment{Indent}{% - \begin{list}{}{% - \setlength{\leftmargin}{0.5cm}% - }% - \item[]\ignorespaces% -}{% - \unskip% - \end{list}% -} - -% Used when hyperlinks are turned off -\newcommand{\doxyref}[3]{% - \textbf{#1} (\textnormal{#2}\,\pageref{#3})% -} - -% Used to link to a table when hyperlinks are turned on -\newcommand{\doxytablelink}[2]{% - \ref{#1}% -} - -% Used to link to a table when hyperlinks are turned off -\newcommand{\doxytableref}[3]{% - \ref{#3}% -} - -% Used by @addindex -\newcommand{\lcurly}{\{} -\newcommand{\rcurly}{\}} - -% Colors used for syntax highlighting -\definecolor{comment}{rgb}{0.5,0.0,0.0} -\definecolor{keyword}{rgb}{0.0,0.5,0.0} -\definecolor{keywordtype}{rgb}{0.38,0.25,0.125} -\definecolor{keywordflow}{rgb}{0.88,0.5,0.0} -\definecolor{preprocessor}{rgb}{0.5,0.38,0.125} -\definecolor{stringliteral}{rgb}{0.0,0.125,0.25} -\definecolor{charliteral}{rgb}{0.0,0.5,0.5} -\definecolor{vhdldigit}{rgb}{1.0,0.0,1.0} -\definecolor{vhdlkeyword}{rgb}{0.43,0.0,0.43} -\definecolor{vhdllogic}{rgb}{1.0,0.0,0.0} -\definecolor{vhdlchar}{rgb}{0.0,0.0,0.0} - -% Color used for table heading -\newcommand{\tableheadbgcolor}{lightgray}% - -% Version of hypertarget with correct landing location -\newcommand{\Hypertarget}[1]{\Hy@raisedlink{\hypertarget{#1}{}}} - -% Define caption that is also suitable in a table -\makeatletter -\def\doxyfigcaption{% -\refstepcounter{figure}% -\@dblarg{\@caption{figure}}} -\makeatother diff --git a/Doku/Doxygen/latex/make.bat b/Doku/Doxygen/latex/make.bat deleted file mode 100644 index afcb4f7..0000000 --- a/Doku/Doxygen/latex/make.bat +++ /dev/null @@ -1,30 +0,0 @@ -set Dir_Old=%cd% -cd /D %~dp0 - -del /s /f *.ps *.dvi *.aux *.toc *.idx *.ind *.ilg *.log *.out *.brf *.blg *.bbl refman.pdf - -pdflatex refman -echo ---- -makeindex refman.idx -echo ---- -pdflatex refman - -setlocal enabledelayedexpansion -set count=8 -:repeat -set content=X -for /F "tokens=*" %%T in ( 'findstr /C:"Rerun LaTeX" refman.log' ) do set content="%%~T" -if !content! == X for /F "tokens=*" %%T in ( 'findstr /C:"Rerun to get cross-references right" refman.log' ) do set content="%%~T" -if !content! == X goto :skip -set /a count-=1 -if !count! EQU 0 goto :skip - -echo ---- -pdflatex refman -goto :repeat -:skip -endlocal -makeindex refman.idx -pdflatex refman -cd /D %Dir_Old% -set Dir_Old= diff --git a/Doku/Doxygen/latex/modules.tex b/Doku/Doxygen/latex/modules.tex deleted file mode 100644 index b6bf919..0000000 --- a/Doku/Doxygen/latex/modules.tex +++ /dev/null @@ -1,28 +0,0 @@ -\section{Modules} -Here is a list of all modules\+:\begin{DoxyCompactList} -\item \contentsline{section}{Higher level methods, setters and getters}{\pageref{group__higherlevel}}{} -\begin{DoxyCompactList} -\item \contentsline{section}{Methods}{\pageref{group__higherlevelmeths}}{} -\item \contentsline{section}{Getters and setters}{\pageref{group__higherlevelgetters}}{} -\end{DoxyCompactList} -\item \contentsline{section}{Lower level fun stuff methods}{\pageref{group__lowerlevelfun}}{} -\item \contentsline{section}{Lower level servo drive methods and getters}{\pageref{group__lowerlevelservo}}{} -\begin{DoxyCompactList} -\item \contentsline{section}{Methods}{\pageref{group__lowerlevelservomeths}}{} -\item \contentsline{section}{Getters}{\pageref{group__lowerlevelservogetters}}{} -\end{DoxyCompactList} -\item \contentsline{section}{Lower level ultra sonic methods and getters}{\pageref{group__lowerlevelus}}{} -\begin{DoxyCompactList} -\item \contentsline{section}{Methods}{\pageref{group__lowerlevelusmeths}}{} -\item \contentsline{section}{Setters and getters}{\pageref{group__lowerlevelusgetters}}{} -\end{DoxyCompactList} -\item \contentsline{section}{Lower level drives methods and getters}{\pageref{group__lowerleveldrives}}{} -\begin{DoxyCompactList} -\item \contentsline{section}{Methods}{\pageref{group__lowerleveldrivesmeths}}{} -\item \contentsline{section}{Getters}{\pageref{group__lowerleveldrivesgetters}}{} -\end{DoxyCompactList} -\item \contentsline{section}{Lower level L\+ED methods}{\pageref{group__lowerlevelled}}{} -\begin{DoxyCompactList} -\item \contentsline{section}{Methods}{\pageref{group__lowerlevelledmeths}}{} -\end{DoxyCompactList} -\end{DoxyCompactList} diff --git a/Doku/Doxygen/latex/refman.tex b/Doku/Doxygen/latex/refman.tex deleted file mode 100644 index 4030e12..0000000 --- a/Doku/Doxygen/latex/refman.tex +++ /dev/null @@ -1,169 +0,0 @@ -\documentclass[twoside]{book} - -% Packages required by doxygen -\usepackage{fixltx2e} -\usepackage{calc} -\usepackage{doxygen} -\usepackage[export]{adjustbox} % also loads graphicx -\usepackage{graphicx} -\usepackage[utf8]{inputenc} -\usepackage{makeidx} -\usepackage{multicol} -\usepackage{multirow} -\PassOptionsToPackage{warn}{textcomp} -\usepackage{textcomp} -\usepackage[nointegrals]{wasysym} -\usepackage[table]{xcolor} - -% Font selection -\usepackage[T1]{fontenc} -\usepackage[scaled=.90]{helvet} -\usepackage{courier} -\usepackage{amssymb} -\usepackage{sectsty} -\renewcommand{\familydefault}{\sfdefault} -\allsectionsfont{% - \fontseries{bc}\selectfont% - \color{darkgray}% -} -\renewcommand{\DoxyLabelFont}{% - \fontseries{bc}\selectfont% - \color{darkgray}% -} -\newcommand{\+}{\discretionary{\mbox{\scriptsize$\hookleftarrow$}}{}{}} - -% Page & text layout -\usepackage{geometry} -\geometry{% - a4paper,% - top=2.5cm,% - bottom=2.5cm,% - left=2.5cm,% - right=2.5cm% -} -\tolerance=750 -\hfuzz=15pt -\hbadness=750 -\setlength{\emergencystretch}{15pt} -\setlength{\parindent}{0cm} -\setlength{\parskip}{3ex plus 2ex minus 2ex} -\makeatletter -\renewcommand{\paragraph}{% - \@startsection{paragraph}{4}{0ex}{-1.0ex}{1.0ex}{% - \normalfont\normalsize\bfseries\SS@parafont% - }% -} -\renewcommand{\subparagraph}{% - \@startsection{subparagraph}{5}{0ex}{-1.0ex}{1.0ex}{% - \normalfont\normalsize\bfseries\SS@subparafont% - }% -} -\makeatother - -% Headers & footers -\usepackage{fancyhdr} -\pagestyle{fancyplain} -\fancyhead[LE]{\fancyplain{}{\bfseries\thepage}} -\fancyhead[CE]{\fancyplain{}{}} -\fancyhead[RE]{\fancyplain{}{\bfseries\leftmark}} -\fancyhead[LO]{\fancyplain{}{\bfseries\rightmark}} -\fancyhead[CO]{\fancyplain{}{}} -\fancyhead[RO]{\fancyplain{}{\bfseries\thepage}} -\fancyfoot[LE]{\fancyplain{}{}} -\fancyfoot[CE]{\fancyplain{}{}} -\fancyfoot[RE]{\fancyplain{}{\bfseries\scriptsize Generated by Doxygen }} -\fancyfoot[LO]{\fancyplain{}{\bfseries\scriptsize Generated by Doxygen }} -\fancyfoot[CO]{\fancyplain{}{}} -\fancyfoot[RO]{\fancyplain{}{}} -\renewcommand{\footrulewidth}{0.4pt} -\renewcommand{\chaptermark}[1]{% - \markboth{#1}{}% -} -\renewcommand{\sectionmark}[1]{% - \markright{\thesection\ #1}% -} - -% Indices & bibliography -\usepackage{natbib} -\usepackage[titles]{tocloft} -\setcounter{tocdepth}{3} -\setcounter{secnumdepth}{5} -\makeindex - -% Hyperlinks (required, but should be loaded last) -\usepackage{ifpdf} -\ifpdf - \usepackage[pdftex,pagebackref=true]{hyperref} -\else - \usepackage[ps2pdf,pagebackref=true]{hyperref} -\fi -\hypersetup{% - colorlinks=true,% - linkcolor=blue,% - citecolor=blue,% - unicode% -} - -% Custom commands -\newcommand{\clearemptydoublepage}{% - \newpage{\pagestyle{empty}\cleardoublepage}% -} - -\usepackage{caption} -\captionsetup{labelsep=space,justification=centering,font={bf},singlelinecheck=off,skip=4pt,position=top} - -%===== C O N T E N T S ===== - -\begin{document} - -% Titlepage & ToC -\hypersetup{pageanchor=false, - bookmarksnumbered=true, - pdfencoding=unicode - } -\pagenumbering{alph} -\begin{titlepage} -\vspace*{7cm} -\begin{center}% -{\Large Arduino \{code\}racer A\+PI }\\ -\vspace*{1cm} -{\large Generated by Doxygen 1.8.13}\\ -\end{center} -\end{titlepage} -\clearemptydoublepage -\pagenumbering{roman} -\tableofcontents -\clearemptydoublepage -\pagenumbering{arabic} -\hypersetup{pageanchor=true} - -%--- Begin generated contents --- -\chapter{Module Index} -\input{modules} -\chapter{Module Documentation} -\input{d9/d80/group__higherlevel} -\include{d2/d40/group__higherlevelmeths} -\include{d7/d45/group__higherlevelgetters} -\include{d8/d7a/group__lowerlevelfun} -\include{d3/d17/group__lowerlevelservo} -\include{db/dd5/group__lowerlevelservomeths} -\include{d4/df4/group__lowerlevelservogetters} -\include{da/daf/group__lowerlevelus} -\include{d6/dfc/group__lowerlevelusmeths} -\include{db/ddd/group__lowerlevelusgetters} -\include{d6/d98/group__lowerleveldrives} -\include{d1/d8a/group__lowerleveldrivesmeths} -\include{d0/d0a/group__lowerleveldrivesgetters} -\include{d7/d0f/group__lowerlevelled} -\include{dd/dff/group__lowerlevelledmeths} -%--- End generated contents --- - -% Index -\backmatter -\newpage -\phantomsection -\clearemptydoublepage -\addcontentsline{toc}{chapter}{Index} -\printindex - -\end{document}