Tobis Programm forked to not destroy your golden files
Fork of Robocode by
Diff: source/Mapping.cpp
- Revision:
- 51:4a18b47fd659
- Parent:
- 50:2e2bf0815fd9
- Child:
- 52:56399c2f13cd
--- a/source/Mapping.cpp Sat Apr 15 00:11:16 2017 +0000 +++ b/source/Mapping.cpp Sat Apr 15 00:18:50 2017 +0000 @@ -5,11 +5,15 @@ #include "Mapping.h" +#define list_time_value 60 +#define list_target_value 1 +#define list_boundry_value 255 +#define servo_angle 50 + + uint8_t obstacle_list[row][col] = { 0 }; uint8_t target_list[row][col] = {0}; -uint8_t list_time_value = 60; -uint8_t list_target_value = 1; -uint8_t list_boundry_value = 255; + uint8_t a = list_time_value; //Substitution um Matrix übersichtlich zu halten uint8_t superpos[7][7] = {{0,0,a,a,a,0,0}, {0,a,a,a,a,a,0}, @@ -32,7 +36,7 @@ //check_sensor(left); float distance0 = getDistanceIR(0); if(distance0 < 0.75f && distance0 > 0.1f) { - set_servo_position(0, 50); + set_servo_position(0, servo_angle); float distance = getDistanceIR(1); int object = 0; if(distance < 0.75f && distance > 0.1f && distance -0.05f < distance0 && distance + 0.05f > distance0) { @@ -40,26 +44,27 @@ } else { object = 1; } - position mapping_pos = position_calculation(distance0, 50, 0.12, 0.12, current_heading, current_pos); + position mapping_pos = position_calculation(distance0, servo_angle, 0.12, 0.12, current_heading, current_pos); draw_to_map(mapping_pos, object); } //check_sensor(right); - float distance4 = getDistanceIR(0); + float distance4 = getDistanceIR(4); if(distance4 < 0.75f && distance4 > 0.1f) { - float distance = getDistanceIR(1); + set_servo_position(1, -servo_angle); + float distance = getDistanceIR(5); int object = 0; if(distance < 0.75f && distance > 0.1f && distance -0.05f < distance4 && distance + 0.05f > distance4) { object = 0; } else { object = 1; } - position mapping_pos = position_calculation(distance4, -50, -0.12, 0.12, current_heading, current_pos); + position mapping_pos = position_calculation(distance4, -servo_angle, -0.12, 0.12, current_heading, current_pos); draw_to_map(mapping_pos, object); } //check_sensor(center); - float distance2 = getDistanceIR(0); + float distance2 = getDistanceIR(2); if(distance2 < 0.75f && distance2 > 0.1f) { - float distance = getDistanceIR(1); + float distance = getDistanceIR(3); int object = 0; if(distance < 0.75f && distance > 0.1f && distance -0.05f < distance2 && distance + 0.05f > distance2) { object = 0;