New MKII update with comments on changes made in the library
This commit is contained in:
parent
68c939e973
commit
03ac5a1d44
3 changed files with 257 additions and 63 deletions
|
@ -13,6 +13,8 @@ CodeRacerMKII::CodeRacerMKII()
|
||||||
_servo_pin = H_SERVO_PIN;
|
_servo_pin = H_SERVO_PIN;
|
||||||
_barrier_pin_left = H_LEFT_BARRIER_PIN;
|
_barrier_pin_left = H_LEFT_BARRIER_PIN;
|
||||||
_barrier_pin_right = H_RIGHT_BARRIER_PIN;
|
_barrier_pin_right = H_RIGHT_BARRIER_PIN;
|
||||||
|
_infrared_sensor_left = H_INFRARED_SENSOR_LEFT;
|
||||||
|
_infrared_sensor_right = H_INFRARED_SENSOR_RIGHT;
|
||||||
_us_trigger_pin = H_US_TRIG_PIN;
|
_us_trigger_pin = H_US_TRIG_PIN;
|
||||||
_us_echo_pin = H_US_ECHO_PIN;
|
_us_echo_pin = H_US_ECHO_PIN;
|
||||||
_drive_left_frwd_bkwrd_pin = H_DRIVE_LEFT_FWRD_BKWRD_PIN;
|
_drive_left_frwd_bkwrd_pin = H_DRIVE_LEFT_FWRD_BKWRD_PIN;
|
||||||
|
@ -28,10 +30,13 @@ CodeRacerMKII::CodeRacerMKII()
|
||||||
}
|
}
|
||||||
|
|
||||||
/** @brief CodeRace constructor with pins.This will overwrite the default settings taken from the header file.
|
/** @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 button_pin_left Pin the left button is connected at
|
||||||
|
* @param button_pin_right Pin the right button is connected at
|
||||||
* @param servo_pin Pin the servo drive is connected at
|
* @param servo_pin Pin the servo drive is connected at
|
||||||
* @param left_barrier_pin Pin the left photoelectric barrier is connected at
|
* @param left_barrier_pin Pin the left photoelectric barrier is connected at
|
||||||
* @param right_barrier_pin Pin the right photoelectric barrier is connected at
|
* @param right_barrier_pin Pin the right photoelectric barrier is connected at
|
||||||
|
* @param infrared_sensor_left Pin the left infrared sensor is connected at
|
||||||
|
* @param infrared_sensor_right Pin the right infrared sensor is connected at
|
||||||
* @param us_trigger_pin Pin the trigger signal of the ultrasonic sensor 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 us_echo_pin Pin the echo signal of the ultrasonic sensor is connected at
|
||||||
* @param drive_left_frwd_bkwrd_pin Pin the forward/ backward pin of the left side drive device driver is connected at
|
* @param drive_left_frwd_bkwrd_pin Pin the forward/ backward pin of the left side drive device driver is connected at
|
||||||
|
@ -47,7 +52,7 @@ CodeRacerMKII::CodeRacerMKII()
|
||||||
* @return nothing
|
* @return nothing
|
||||||
*/
|
*/
|
||||||
CodeRacerMKII::CodeRacerMKII(uint8_t button_pin_left , uint8_t button_pin_right, uint8_t servo_pin,
|
CodeRacerMKII::CodeRacerMKII(uint8_t button_pin_left , uint8_t button_pin_right, uint8_t servo_pin,
|
||||||
uint8_t left_barrier_pin, uint8_t right_barrier_pin,
|
uint8_t left_barrier_pin, uint8_t right_barrier_pin, uint8_t infrared_sensor_left, uint8_t infrared_sensor_right,
|
||||||
uint8_t us_trigger_pin, uint8_t us_echo_pin,
|
uint8_t us_trigger_pin, uint8_t us_echo_pin,
|
||||||
uint8_t drive_left_frwd_bkwrd_pin, uint8_t drive_left_enable_pin,
|
uint8_t drive_left_frwd_bkwrd_pin, uint8_t drive_left_enable_pin,
|
||||||
uint8_t drive_right_frwd_bkwrd_pin, uint8_t drive_right_enable_pin,
|
uint8_t drive_right_frwd_bkwrd_pin, uint8_t drive_right_enable_pin,
|
||||||
|
@ -59,6 +64,8 @@ CodeRacerMKII::CodeRacerMKII(uint8_t button_pin_left , uint8_t button_pin_right,
|
||||||
_servo_pin = servo_pin;
|
_servo_pin = servo_pin;
|
||||||
_barrier_pin_left = left_barrier_pin;
|
_barrier_pin_left = left_barrier_pin;
|
||||||
_barrier_pin_right = right_barrier_pin;
|
_barrier_pin_right = right_barrier_pin;
|
||||||
|
_infrared_sensor_left = infrared_sensor_left;
|
||||||
|
_infrared_sensor_right = infrared_sensor_right;
|
||||||
_us_trigger_pin = us_trigger_pin;
|
_us_trigger_pin = us_trigger_pin;
|
||||||
_us_echo_pin = us_echo_pin;
|
_us_echo_pin = us_echo_pin;
|
||||||
_drive_left_frwd_bkwrd_pin = drive_left_frwd_bkwrd_pin;
|
_drive_left_frwd_bkwrd_pin = drive_left_frwd_bkwrd_pin;
|
||||||
|
@ -132,6 +139,14 @@ void CodeRacerMKII::begin() {
|
||||||
pinMode(_barrier_pin_right, INPUT_PULLUP);
|
pinMode(_barrier_pin_right, INPUT_PULLUP);
|
||||||
attachInterrupt(digitalPinToInterrupt(_barrier_pin_right), _count_steps_right, FALLING);
|
attachInterrupt(digitalPinToInterrupt(_barrier_pin_right), _count_steps_right, FALLING);
|
||||||
|
|
||||||
|
// Infrared sensors
|
||||||
|
pinMode(_infrared_sensor_left, INPUT);
|
||||||
|
pinMode(_infrared_sensor_right, INPUT);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(_infrared_sensor_left), _stop_obstacle_left, CHANGE);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(_infrared_sensor_right), _stop_obstacle_right, CHANGE);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Left drive
|
// Left drive
|
||||||
pinMode(_drive_left_frwd_bkwrd_pin, OUTPUT);
|
pinMode(_drive_left_frwd_bkwrd_pin, OUTPUT);
|
||||||
set_drive_left_state(DRIVESTOP);
|
set_drive_left_state(DRIVESTOP);
|
||||||
|
@ -184,8 +199,9 @@ void CodeRacerMKII::begin() {
|
||||||
void CodeRacerMKII::stop_driving() {
|
void CodeRacerMKII::stop_driving() {
|
||||||
_servo_sweep = false;
|
_servo_sweep = false;
|
||||||
_drive = false;
|
_drive = false;
|
||||||
set_drives_stop_left_right();
|
global_stop_driving();
|
||||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF);
|
//set_drives_stop_left_right();
|
||||||
|
//set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF);
|
||||||
}
|
}
|
||||||
|
|
||||||
/** @brief Sets the speed and the directions of both drives so that it will move forward.
|
/** @brief Sets the speed and the directions of both drives so that it will move forward.
|
||||||
|
@ -446,24 +462,52 @@ bool CodeRacerMKII::is_active() {
|
||||||
return(coderracer_activ);
|
return(coderracer_activ);
|
||||||
}
|
}
|
||||||
/** @brief returns the right button's current state
|
/** @brief returns the right button's current state
|
||||||
* _right_button_state is toggled each time the right button is pressed. Is set false by default.
|
* _right_button_state is toggled each time the right button is pressed. It is set false by default.
|
||||||
* @return true if _right_button_pressed is set- False if not.
|
* @return true if right_button_pressed is set- False if not.
|
||||||
*/
|
*/
|
||||||
bool CodeRacerMKII::right_button_state() {
|
bool CodeRacerMKII::right_button_state() {
|
||||||
return(right_button_pressed);
|
return(right_button_pressed);
|
||||||
}
|
}
|
||||||
|
/** @brief returns the variable set if an obstacle is identified by the left infrared sensor
|
||||||
|
* @return true if an obstacle is seen by the sensor, false if not
|
||||||
|
*/
|
||||||
|
bool CodeRacerMKII::is_obstacle_on_the_left(){
|
||||||
|
return(obstacle_left_side);
|
||||||
|
}
|
||||||
|
/** @brief returns the variable set if an obstacle is identified by the right infrared sensor
|
||||||
|
* @return true if an obstacle is seen by the sensor, false if not
|
||||||
|
*/
|
||||||
|
bool CodeRacerMKII::is_obstacle_on_the_right(){
|
||||||
|
return(obstacle_right_side);
|
||||||
|
}
|
||||||
|
/** @brief returns current value of the variable right_button_count
|
||||||
|
* right_button_count is set 0 by default and increments every time the right button is pressed
|
||||||
|
* @return right_button_count (an integer starting at 0)
|
||||||
|
*/
|
||||||
unsigned int CodeRacerMKII::button_count() {
|
unsigned int CodeRacerMKII::button_count() {
|
||||||
return(right_button_count);
|
return(right_button_count);
|
||||||
}
|
}
|
||||||
|
/** @brief returns the current distance driven by the Coderacer in mm
|
||||||
|
* distance is calculated with the step counter of the left wheel and a constant defined in the header file
|
||||||
|
* @return driven_distance
|
||||||
|
*/
|
||||||
unsigned int CodeRacerMKII::show_distance_mm(){
|
unsigned int CodeRacerMKII::show_distance_mm(){
|
||||||
int driven_distance;
|
int driven_distance;
|
||||||
driven_distance= left_step_counter*DISTANCE_PER_TICK_MM;
|
driven_distance= left_step_counter*DISTANCE_PER_TICK_MM;
|
||||||
return driven_distance;
|
return driven_distance;
|
||||||
}
|
}
|
||||||
|
/** @brief returns the current stepcount of the PE barrier of the left wheel
|
||||||
|
* @return left_step_counter
|
||||||
|
*/
|
||||||
|
unsigned int CodeRacerMKII::show_left_stepcounter(){
|
||||||
|
return left_step_counter;
|
||||||
|
}
|
||||||
|
/** @brief returns the current stepcount of the PE barrier of the right wheel
|
||||||
|
* @return right_step_counter
|
||||||
|
*/
|
||||||
|
unsigned int CodeRacerMKII::show_right_stepcounter(){
|
||||||
|
return right_step_counter;
|
||||||
|
}
|
||||||
|
|
||||||
/** @} */ // end of group higherlevelgetters
|
/** @} */ // end of group higherlevelgetters
|
||||||
/** @} */ // end of group higherlevel
|
/** @} */ // end of group higherlevel
|
||||||
|
@ -1048,7 +1092,7 @@ unsigned long CodeRacerMKII::usonic_distance_cm() {
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @brief Overwrites some drive settings. This will replace the defaults set by the values in the header file.
|
/** @brief Overwrites the values for the speed of the race. 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_left_speed Speed of the left side drive
|
||||||
* @param drive_right_speed Speed of the right side drive
|
* @param drive_right_speed Speed of the right side drive
|
||||||
* @return nothing
|
* @return nothing
|
||||||
|
@ -1109,10 +1153,10 @@ void CodeRacerMKII::set_drive_right_state(drivestate state) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/** @brief Sets the specified drivestate for the drive connected to the sepecified pins (DRIVESTOP, DRIVEFRWD, DRIVEBACK)
|
/** @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 state drivestate to set for the connected drive
|
||||||
* @param frwdpin Pin the forward signal of the drive device driver is connected at
|
* @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
|
* @param backpin Pin the backward signal of the drive device driver is connected at
|
||||||
* @return nothing
|
* @return nothing
|
||||||
*/
|
*/
|
||||||
void CodeRacerMKII::set_drive_state(drivestate state, uint8_t frwdbackpin, uint8_t enable_pin ) {
|
void CodeRacerMKII::set_drive_state(drivestate state, uint8_t frwdbackpin, uint8_t enable_pin ) {
|
||||||
switch (state) {
|
switch (state) {
|
||||||
|
@ -1127,7 +1171,10 @@ void CodeRacerMKII::set_drive_state(drivestate state, uint8_t frwdbackpin, uint8
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/** @brief enables or disables a syncronized halting if the method global_stop_driving() is used. if disabled, the left engine will continue running.
|
||||||
|
* @param state a boolean expression to enable or disable syncstop. this variable is set false by default.
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::set_syncstop(bool state){
|
void CodeRacerMKII::set_syncstop(bool state){
|
||||||
if (1== state)
|
if (1== state)
|
||||||
{
|
{
|
||||||
|
@ -1135,6 +1182,17 @@ void CodeRacerMKII::set_syncstop(bool state){
|
||||||
}
|
}
|
||||||
else syncstop=0;
|
else syncstop=0;
|
||||||
}
|
}
|
||||||
|
/** @brief enables or disables obstacle_stop and by that, enables or disables halting if an obstacle is identified by either of the infrared sensors
|
||||||
|
* @param state a boolean expression to enable or disable obstacle_stop. this variable is set false by default.
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
|
void CodeRacerMKII::set_obstacle_stop(bool state){
|
||||||
|
if (1== state)
|
||||||
|
{
|
||||||
|
obstacle_stop= 1;
|
||||||
|
}
|
||||||
|
else obstacle_stop=0;
|
||||||
|
}
|
||||||
|
|
||||||
/** @brief Sets the speed for both of the drives.
|
/** @brief Sets the speed for both of the drives.
|
||||||
*
|
*
|
||||||
|
@ -1206,18 +1264,31 @@ void CodeRacerMKII::_analog_write(uint8_t pin, uint8_t speed) {
|
||||||
ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed);
|
ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to drive a specified number of wheel turns forward. requires a positive integer.
|
||||||
|
* @param turnsleft sets the number of turns for the left wheel
|
||||||
|
* @param turnsright sets the number of turns for the right wheel
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::drive_turns(unsigned int turnsleft, unsigned int turnsright){
|
void CodeRacerMKII::drive_turns(unsigned int turnsleft, unsigned int turnsright){
|
||||||
drive_ticks(turnsleft*TURN, turnsright*TURN);
|
drive_ticks(turnsleft*TURN, turnsright*TURN);
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to drive a specified number of ticks of the PE barriers. requires a positive integer.
|
||||||
|
* @param tickleft sets the number of ticks for the left wheel
|
||||||
|
* @param tickright sets the number of ticks for the right wheel
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::drive_ticks(unsigned int tickleft, unsigned int tickright){
|
void CodeRacerMKII::drive_ticks(unsigned int tickleft, unsigned int tickright){
|
||||||
drive_ticks_left(tickleft, false);
|
drive_ticks_left(tickleft, false);
|
||||||
drive_ticks_right(tickright, false);
|
drive_ticks_right(tickright, false);
|
||||||
drive_forward();
|
drive_forward();
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to turn by a specified number of degrees to the left or to the right. if the value is positive, turn clockwise, if negative turn counter- clockwise.
|
||||||
|
* the speed of the turn is defined by the normal driving speed.
|
||||||
|
* @param degree tells the coderacer how many degrees it has to turn.
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::turn_degree(int degree){
|
void CodeRacerMKII::turn_degree(int degree){
|
||||||
|
// sets thhe drive states for both wheels and by that the direction the racer will turn.
|
||||||
if(degree>0)
|
if(degree>0)
|
||||||
{
|
{
|
||||||
set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
|
set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
|
||||||
|
@ -1228,13 +1299,18 @@ void CodeRacerMKII::turn_degree(int degree){
|
||||||
degree= abs(degree);
|
degree= abs(degree);
|
||||||
}
|
}
|
||||||
else set_drives_states_left_right(DRIVESTOP, DRIVESTOP);
|
else set_drives_states_left_right(DRIVESTOP, DRIVESTOP);
|
||||||
|
// calculates the number of ticks for both wheels and tells the racer to drive with the internally stored driving speed
|
||||||
int Ticks= degree*TICKS_OF_ONE_DEGREE;
|
int Ticks= degree*TICKS_OF_ONE_DEGREE;
|
||||||
drive_ticks_left(Ticks, false);
|
drive_ticks_left(Ticks, false);
|
||||||
drive_ticks_right(Ticks, false);
|
drive_ticks_right(Ticks, false);
|
||||||
set_drives_speed_left_right(_drive_left_speed, _drive_right_speed);
|
set_drives_speed_left_right(_drive_left_speed, _drive_right_speed);
|
||||||
|
_drive= true;
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to drive a specified number of ticks for the left wheel.
|
||||||
|
* @param Ticks number of ticks
|
||||||
|
* @param drive can be told to be false- if that is the case, the racer won't start driving but will only set the new stopcount for the left wheel
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::drive_ticks_left(unsigned int Ticks, bool drive = true ){
|
void CodeRacerMKII::drive_ticks_left(unsigned int Ticks, bool drive = true ){
|
||||||
if(left_step_stopcount<=left_step_counter)
|
if(left_step_stopcount<=left_step_counter)
|
||||||
{
|
{
|
||||||
|
@ -1242,7 +1318,11 @@ void CodeRacerMKII::drive_ticks_left(unsigned int Ticks, bool drive = true ){
|
||||||
if(true == drive){drive_forward();}
|
if(true == drive){drive_forward();}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to drive a specified number of ticks for the right wheel.
|
||||||
|
* @param Ticks number of ticks
|
||||||
|
* @param drive can be told to be false- if that is the case, the racer won't start driving but will only set the new stopcount for the right wheel
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::drive_ticks_right(unsigned int Ticks, bool drive = true){
|
void CodeRacerMKII::drive_ticks_right(unsigned int Ticks, bool drive = true){
|
||||||
if(right_step_stopcount<=right_step_counter)
|
if(right_step_stopcount<=right_step_counter)
|
||||||
{
|
{
|
||||||
|
@ -1250,20 +1330,64 @@ void CodeRacerMKII::drive_ticks_right(unsigned int Ticks, bool drive = true){
|
||||||
if(true == drive){drive_forward();}
|
if(true == drive){drive_forward();}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to drive a specified distance in mm. requires two values for both the left and the right wheel.
|
||||||
|
* @param leftdistance the distance to be driven by the left wheel
|
||||||
|
* @param rightdistance the distance to be driven by the right wheel
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::drive_distance_mm(unsigned int leftdistance, unsigned int rightdistance){
|
void CodeRacerMKII::drive_distance_mm(unsigned int leftdistance, unsigned int rightdistance){
|
||||||
|
// calls two subroutines for both sides
|
||||||
drive_distance_left_mm(leftdistance);
|
drive_distance_left_mm(leftdistance);
|
||||||
drive_distance_right_mm(rightdistance);
|
drive_distance_right_mm(rightdistance);
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to drive a specified distance in mm for the left wheel.
|
||||||
|
* @param distance_mm a distance in mm
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::drive_distance_left_mm(int distance_mm){
|
void CodeRacerMKII::drive_distance_left_mm(int distance_mm){
|
||||||
distance_mm/=DISTANCE_PER_TICK_MM;
|
distance_mm/=DISTANCE_PER_TICK_MM;
|
||||||
drive_ticks_left(distance_mm);
|
drive_ticks_left(distance_mm);
|
||||||
}
|
}
|
||||||
|
/** @brief tells the coderacer to drive a specified distance in mm for the right wheel.
|
||||||
|
* @param distance_mm a distance in mm
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
void CodeRacerMKII::drive_distance_right_mm(int distance_mm){
|
void CodeRacerMKII::drive_distance_right_mm(int distance_mm){
|
||||||
distance_mm/=DISTANCE_PER_TICK_MM;
|
distance_mm/=DISTANCE_PER_TICK_MM;
|
||||||
drive_ticks_right(distance_mm);
|
drive_ticks_right(distance_mm);
|
||||||
}
|
}
|
||||||
|
/** @brief checks if an obstacle is identified by either of the infrared sensors. returns true if that is the case for AT LEAST one of them
|
||||||
|
* @return true or false if an obstacle has been identified
|
||||||
|
*/
|
||||||
|
bool CodeRacerMKII::obstacle_check_left_right(){
|
||||||
|
if((true== obstacle_check_left()) || (true== obstacle_check_right()))
|
||||||
|
{
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
else {return false;}
|
||||||
|
}
|
||||||
|
/** @brief subroutine called by obstacle_check_left_right(). can be used seperately to check if an obstacle has been identified by the left infrared sensor.
|
||||||
|
* @return true or false if an obstacle has been identified
|
||||||
|
*/
|
||||||
|
bool CodeRacerMKII::obstacle_check_left(){
|
||||||
|
return obstacle_check(_infrared_sensor_left);
|
||||||
|
}
|
||||||
|
/** @brief subroutine called by obstacle_check_left_right(). can be used seperately to check if an obstacle has been identified by the left infrared sensor.
|
||||||
|
* @return true or false if an obstacle has been identified
|
||||||
|
*/
|
||||||
|
bool CodeRacerMKII::obstacle_check_right(){
|
||||||
|
return obstacle_check(_infrared_sensor_right);
|
||||||
|
}
|
||||||
|
/** @brief universal routine called by all obstacle_check routines. reads the pin the infrared sensor is connected at.
|
||||||
|
* @return true if voltage is present, false if not
|
||||||
|
*/
|
||||||
|
bool CodeRacerMKII::obstacle_check(uint8_t sensorpin) {
|
||||||
|
if (true== digitalRead(sensorpin)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
else {return false;}
|
||||||
|
}
|
||||||
|
|
||||||
/** @} */ // end of group lowerleveldrivesgetters
|
/** @} */ // end of group lowerleveldrivesgetters
|
||||||
/** @} */ // end of group lowerleveldrives
|
/** @} */ // end of group lowerleveldrives
|
||||||
|
|
||||||
|
@ -1280,9 +1404,9 @@ void CodeRacerMKII::drive_distance_right_mm(int distance_mm){
|
||||||
|
|
||||||
/** @brief Sets all of the 4 LEDs to a ledstate (LEDON, LEDOFF)
|
/** @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 leftled set state of status left LED (most left yellow led)
|
||||||
* @param stopled set state of status stop LED (red led)
|
* @param rightled set state of status stop LED (red led)
|
||||||
* @param frwdled set state of status forward LED (green or blue led)
|
* @param stopled set state of status forward LED (green or blue led)
|
||||||
* @param rightled set state of status right LED (most right yellow led)
|
* @param frwrdled set state of status right LED (most right yellow led)
|
||||||
* @param blueled set state of blue LED
|
* @param blueled set state of blue LED
|
||||||
* @param whiteled set state of white LED
|
* @param whiteled set state of white LED
|
||||||
* @return nothing
|
* @return nothing
|
||||||
|
@ -1345,31 +1469,10 @@ void IRAM_ATTR CodeRacerMKII::_set_button_state_right() {
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
/** @brief basically the same as stop_driving(), but is required for all routines attached to an interrupt which can't call stop_driving()
|
||||||
void IRAM_ATTR CodeRacerMKII::_count_steps_left() {
|
* @return nothing
|
||||||
left_step_counter++;
|
*/
|
||||||
if (left_step_counter==left_step_stopcount)
|
void global_stop_driving(){
|
||||||
{
|
|
||||||
//TODO: use stop_driving();
|
|
||||||
ledcWrite(DRIVE_PWM_LEFT_CHANNEL, 0);
|
|
||||||
if(true == syncstop)
|
|
||||||
{
|
|
||||||
ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, 0);
|
|
||||||
}
|
|
||||||
digitalWrite(H_LED_RIGHT_PIN, LOW);
|
|
||||||
digitalWrite(H_LED_LEFT_PIN, LOW);
|
|
||||||
digitalWrite(H_LED_STOP_PIN, HIGH);
|
|
||||||
digitalWrite(H_LED_FRWD_PIN, LOW);
|
|
||||||
digitalWrite(H_LED_BLUE_PIN, LOW);
|
|
||||||
digitalWrite(H_LED_WHITE_PIN, LOW);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void IRAM_ATTR CodeRacerMKII::_count_steps_right() {
|
|
||||||
right_step_counter++;
|
|
||||||
if (right_step_counter==right_step_stopcount)
|
|
||||||
{
|
|
||||||
//TODO: use stop_driving();
|
|
||||||
ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, 0);
|
ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, 0);
|
||||||
if(true == syncstop)
|
if(true == syncstop)
|
||||||
{
|
{
|
||||||
|
@ -1381,8 +1484,55 @@ void IRAM_ATTR CodeRacerMKII::_count_steps_right() {
|
||||||
digitalWrite(H_LED_FRWD_PIN, LOW);
|
digitalWrite(H_LED_FRWD_PIN, LOW);
|
||||||
digitalWrite(H_LED_BLUE_PIN, LOW);
|
digitalWrite(H_LED_BLUE_PIN, LOW);
|
||||||
digitalWrite(H_LED_WHITE_PIN, LOW);
|
digitalWrite(H_LED_WHITE_PIN, LOW);
|
||||||
|
_drive= false;
|
||||||
|
}
|
||||||
|
/** @brief this routine is called each time the left PE barrier changes its state. it increments (and by that counts) the ticks driven by the left wheel and is also instructed to stop the racer if the stopcount set by drive_ticks() is reached using the global_stop_driving() routine
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
|
void IRAM_ATTR CodeRacerMKII::_count_steps_left() {
|
||||||
|
left_step_counter++;
|
||||||
|
if (left_step_counter==left_step_stopcount)
|
||||||
|
{
|
||||||
|
//TODO: use stop_driving();
|
||||||
|
global_stop_driving();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/** @brief this routine is called each time the left PE barrier changes its state. it increments (and by that counts) the ticks driven by the right wheel and is also instructed to stop the racer if the stopcount set by drive_ticks() is reached using the global_stop_driving() routine
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
|
void IRAM_ATTR CodeRacerMKII::_count_steps_right() {
|
||||||
|
right_step_counter++;
|
||||||
|
if (right_step_counter==right_step_stopcount)
|
||||||
|
{
|
||||||
|
//TODO: use stop_driving();
|
||||||
|
global_stop_driving();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/** @brief this routine is called each time the left infrared sensor changes its state. it sets the boolean variable obstacle_left_side to true/false and, if obstacle_stop is enabled, also stops the racer using global_stop_driving()
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
|
void IRAM_ATTR CodeRacerMKII::_stop_obstacle_left(){
|
||||||
|
if(HIGH== digitalRead(H_INFRARED_SENSOR_LEFT)){
|
||||||
|
if(1==obstacle_stop){
|
||||||
|
global_stop_driving();
|
||||||
|
}
|
||||||
|
obstacle_left_side=true;
|
||||||
|
}
|
||||||
|
else obstacle_left_side= false;
|
||||||
|
}
|
||||||
|
/** @brief this routine is called each time the left infrared sensor changes its state. it sets the boolean variable obstacle_left_side to true/false and, if obstacle_stop is enabled, also stops the racer using global_stop_driving()
|
||||||
|
* @return nothing
|
||||||
|
*/
|
||||||
|
void IRAM_ATTR CodeRacerMKII::_stop_obstacle_right(){
|
||||||
|
if(HIGH== digitalRead(H_INFRARED_SENSOR_RIGHT)){
|
||||||
|
if(1==obstacle_stop){
|
||||||
|
global_stop_driving();
|
||||||
|
}
|
||||||
|
obstacle_right_side=true;
|
||||||
|
}
|
||||||
|
else obstacle_right_side= false;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#define SERVO_MIN_POSITION 10 // minimum 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_SET_1TICK_POSITION_DELAY_MS 3 // minimum duration of time between two servo steps
|
||||||
|
|
||||||
//----- PE- Barrier -----
|
//----- PE- barrier -----
|
||||||
#define H_LEFT_BARRIER_PIN 34
|
#define H_LEFT_BARRIER_PIN 34
|
||||||
#define H_RIGHT_BARRIER_PIN 35
|
#define H_RIGHT_BARRIER_PIN 35
|
||||||
#define TURN 20
|
#define TURN 20
|
||||||
|
@ -47,7 +47,11 @@
|
||||||
#define DISTANCE_BETWEEN_WHEELS_MM 112
|
#define DISTANCE_BETWEEN_WHEELS_MM 112
|
||||||
#define SCOPE_OF_ONE_TURN_MM PI*DISTANCE_BETWEEN_WHEELS_MM
|
#define SCOPE_OF_ONE_TURN_MM PI*DISTANCE_BETWEEN_WHEELS_MM
|
||||||
#define TICKS_OF_ONE_TURN SCOPE_OF_ONE_TURN_MM/DISTANCE_PER_TICK_MM
|
#define TICKS_OF_ONE_TURN SCOPE_OF_ONE_TURN_MM/DISTANCE_PER_TICK_MM
|
||||||
#define TICKS_OF_ONE_DEGREE TICKS_OF_ONE_TURN/360
|
#define TICKS_OF_ONE_DEGREE 0.0889 //TICKS_OF_ONE_TURN/360
|
||||||
|
|
||||||
|
//----- Infrared sensor -----
|
||||||
|
#define H_INFRARED_SENSOR_LEFT 36
|
||||||
|
#define H_INFRARED_SENSOR_RIGHT 39
|
||||||
|
|
||||||
//----- Ultrasonic sensor -----
|
//----- Ultrasonic sensor -----
|
||||||
#define H_US_TRIG_PIN 21
|
#define H_US_TRIG_PIN 21
|
||||||
|
@ -84,11 +88,16 @@ static volatile unsigned int left_step_stopcount=0;
|
||||||
static volatile unsigned int right_step_counter=0;
|
static volatile unsigned int right_step_counter=0;
|
||||||
static volatile unsigned int right_step_stopcount=0;
|
static volatile unsigned int right_step_stopcount=0;
|
||||||
static volatile bool syncstop= 0;
|
static volatile bool syncstop= 0;
|
||||||
|
static volatile bool _drive;
|
||||||
|
static volatile bool obstacle_stop= false;
|
||||||
|
static volatile bool obstacle_left_side= false;
|
||||||
|
static volatile bool obstacle_right_side= false;
|
||||||
static volatile bool coderracer_activ = false;
|
static volatile bool coderracer_activ = false;
|
||||||
static volatile bool right_button_pressed =false;
|
static volatile bool right_button_pressed =false;
|
||||||
static volatile unsigned int right_button_count=0;
|
static volatile unsigned int right_button_count=0;
|
||||||
static volatile unsigned long left_button_last_pressed_at_ms = millis();
|
static volatile unsigned long left_button_last_pressed_at_ms = millis();
|
||||||
static volatile unsigned long right_button_last_pressed_at_ms = millis();
|
static volatile unsigned long right_button_last_pressed_at_ms = millis();
|
||||||
|
void global_stop_driving();
|
||||||
|
|
||||||
enum ledstate {
|
enum ledstate {
|
||||||
LEDOFF,
|
LEDOFF,
|
||||||
|
@ -120,6 +129,8 @@ class CodeRacerMKII {
|
||||||
uint8_t _servo_pin;
|
uint8_t _servo_pin;
|
||||||
uint8_t _barrier_pin_left;
|
uint8_t _barrier_pin_left;
|
||||||
uint8_t _barrier_pin_right;
|
uint8_t _barrier_pin_right;
|
||||||
|
uint8_t _infrared_sensor_left;
|
||||||
|
uint8_t _infrared_sensor_right;
|
||||||
uint8_t _us_trigger_pin;
|
uint8_t _us_trigger_pin;
|
||||||
uint8_t _us_echo_pin;
|
uint8_t _us_echo_pin;
|
||||||
uint8_t _drive_left_frwd_bkwrd_pin;
|
uint8_t _drive_left_frwd_bkwrd_pin;
|
||||||
|
@ -160,7 +171,7 @@ class CodeRacerMKII {
|
||||||
unsigned long _servo_look_around_at_ms;
|
unsigned long _servo_look_around_at_ms;
|
||||||
|
|
||||||
unsigned long _min_distance_cm;
|
unsigned long _min_distance_cm;
|
||||||
bool _drive;
|
|
||||||
unsigned long _drive_set_at_ms;
|
unsigned long _drive_set_at_ms;
|
||||||
bool _servo_sweep;
|
bool _servo_sweep;
|
||||||
bool _coderracer_activ;
|
bool _coderracer_activ;
|
||||||
|
@ -172,6 +183,8 @@ class CodeRacerMKII {
|
||||||
static void _count_steps_right();
|
static void _count_steps_right();
|
||||||
static void _set_button_state_left();
|
static void _set_button_state_left();
|
||||||
static void _set_button_state_right();
|
static void _set_button_state_right();
|
||||||
|
static void _stop_obstacle_left();
|
||||||
|
static void _stop_obstacle_right();
|
||||||
void _analog_write(uint8_t pin, uint8_t speed);
|
void _analog_write(uint8_t pin, uint8_t speed);
|
||||||
unsigned long _servo_set_position(uint8_t position);
|
unsigned long _servo_set_position(uint8_t position);
|
||||||
|
|
||||||
|
@ -189,7 +202,7 @@ class CodeRacerMKII {
|
||||||
CodeRacerMKII();
|
CodeRacerMKII();
|
||||||
|
|
||||||
CodeRacerMKII(uint8_t button_pin_left, uint8_t button_pin_right, uint8_t servo_pin,
|
CodeRacerMKII(uint8_t button_pin_left, uint8_t button_pin_right, uint8_t servo_pin,
|
||||||
uint8_t barrier_pin_left, uint8_t barrier_pin_right,
|
uint8_t barrier_pin_left, uint8_t barrier_pin_right, uint8_t infrared_sensor_left, uint8_t infrared_sensor_right,
|
||||||
uint8_t us_trigger_pin, uint8_t us_echo_pin,
|
uint8_t us_trigger_pin, uint8_t us_echo_pin,
|
||||||
uint8_t drive_left_frwd_bkwrd_pin, uint8_t drive_left_enable_pin,
|
uint8_t drive_left_frwd_bkwrd_pin, uint8_t drive_left_enable_pin,
|
||||||
uint8_t drive_right_frwd_bkwrd_pin, uint8_t drive_right_enable_pin,
|
uint8_t drive_right_frwd_bkwrd_pin, uint8_t drive_right_enable_pin,
|
||||||
|
@ -214,8 +227,12 @@ class CodeRacerMKII {
|
||||||
unsigned long turn_left_for_ms();
|
unsigned long turn_left_for_ms();
|
||||||
unsigned long turn_right_for_ms();
|
unsigned long turn_right_for_ms();
|
||||||
bool right_button_state();
|
bool right_button_state();
|
||||||
|
bool is_obstacle_on_the_left();
|
||||||
|
bool is_obstacle_on_the_right();
|
||||||
unsigned int button_count();
|
unsigned int button_count();
|
||||||
unsigned int show_distance_mm();
|
unsigned int show_distance_mm();
|
||||||
|
unsigned int show_left_stepcounter();
|
||||||
|
unsigned int show_right_stepcounter();
|
||||||
|
|
||||||
|
|
||||||
// higher level {code}racer services
|
// higher level {code}racer services
|
||||||
|
@ -262,6 +279,7 @@ class CodeRacerMKII {
|
||||||
void set_drive_left_state(drivestate state);
|
void set_drive_left_state(drivestate state);
|
||||||
void set_drive_right_state(drivestate state);
|
void set_drive_right_state(drivestate state);
|
||||||
void set_syncstop(bool state);
|
void set_syncstop(bool state);
|
||||||
|
void set_obstacle_stop(bool state);
|
||||||
void set_drive_state(drivestate state, uint8_t fwrdbackpin, uint8_t enable_pin);
|
void set_drive_state(drivestate state, uint8_t fwrdbackpin, uint8_t enable_pin);
|
||||||
void set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright);
|
void set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright);
|
||||||
void set_drive_left_speed(uint8_t speed);
|
void set_drive_left_speed(uint8_t speed);
|
||||||
|
@ -276,6 +294,10 @@ class CodeRacerMKII {
|
||||||
void drive_distance_mm(unsigned int leftdistance, unsigned int rightdistance);
|
void drive_distance_mm(unsigned int leftdistance, unsigned int rightdistance);
|
||||||
void drive_distance_left_mm(int distance_mm);
|
void drive_distance_left_mm(int distance_mm);
|
||||||
void drive_distance_right_mm(int distance_mm);
|
void drive_distance_right_mm(int distance_mm);
|
||||||
|
bool obstacle_check_left_right();
|
||||||
|
bool obstacle_check_right();
|
||||||
|
bool obstacle_check_left();
|
||||||
|
bool obstacle_check (uint8_t sensorpin);
|
||||||
|
|
||||||
// Ultrasonic sensor
|
// Ultrasonic sensor
|
||||||
unsigned long usonic_measure_cm();
|
unsigned long usonic_measure_cm();
|
||||||
|
|
|
@ -15,6 +15,10 @@ drehrichtung drehung = links;
|
||||||
unsigned int anzahl_drehung = 0;
|
unsigned int anzahl_drehung = 0;
|
||||||
CodeRacerMKII coderacer;
|
CodeRacerMKII coderacer;
|
||||||
|
|
||||||
|
int aabstand[160];
|
||||||
|
void filladistance();
|
||||||
|
int adegree[160];
|
||||||
|
int ispeed=1;
|
||||||
//---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ----
|
//---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ----
|
||||||
void setup() {
|
void setup() {
|
||||||
// Monitor
|
// Monitor
|
||||||
|
@ -32,21 +36,39 @@ void setup() {
|
||||||
anzahl_drehung = 0;
|
anzahl_drehung = 0;
|
||||||
drehung = links;
|
drehung = links;
|
||||||
coderacer.set_syncstop(true);
|
coderacer.set_syncstop(true);
|
||||||
|
coderacer.set_obstacle_stop(false);
|
||||||
|
coderacer.speed_settings(135, 135);
|
||||||
}
|
}
|
||||||
|
|
||||||
//---- 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
|
//---- 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
|
||||||
void loop() {
|
void loop()
|
||||||
|
{
|
||||||
|
bool started = false;
|
||||||
while(coderacer.start_stop()== 1)
|
while(coderacer.start_stop()== 1)
|
||||||
{
|
{
|
||||||
delay(2000);
|
if(false == started)
|
||||||
coderacer.speed_settings(130, 130);
|
{
|
||||||
coderacer.turn_degree(180);
|
started = true;
|
||||||
while(true== coderacer.is_driving())
|
delay(1000);
|
||||||
{};
|
}
|
||||||
coderacer.turn_degree(-180);
|
|
||||||
delay(5000);
|
unsigned int stepsprevl, stepsprevr ;
|
||||||
|
for(unsigned int v= 80;v<=255;v=v+10)
|
||||||
|
{
|
||||||
|
coderacer.speed_settings(v, v);
|
||||||
|
stepsprevl = coderacer.show_left_stepcounter();
|
||||||
|
stepsprevr = coderacer.show_right_stepcounter();
|
||||||
|
coderacer.drive_ticks_left(2000, true);
|
||||||
|
while (1== coderacer.is_driving()){}
|
||||||
|
Serial.printf("v=%i links*(2000)=%i rechts=%i\n",v, coderacer.show_left_stepcounter() - stepsprevl , coderacer.show_right_stepcounter() - stepsprevr);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
//Serial.printf("links %i\n", coderacer.show_left_stepcounter());
|
||||||
|
//Serial.printf("rechts %i\n", coderacer.show_right_stepcounter());
|
||||||
|
//Serial.printf("%i\n", coderacer.show_distance_mm());
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in a new issue