Robot team project
Dependencies: QEI Motordriver ros_lib_melodic
main.cpp
- Committer:
- florine_van
- Date:
- 2019-10-23
- Revision:
- 6:858a5116688e
- Parent:
- 5:8ef79eebbc97
- Child:
- 7:2cf57f28255d
File content as of revision 6:858a5116688e:
#include "mbed.h" #include "Sensor.h" #include "Motor.h" // Set up serial to pc Serial pc(SERIAL_TX, SERIAL_RX); // Set up I²C on the STM32 NUCLEO-401RE #define addr1 (0x29) #define addr2 (0x2A) #define addr3 (0x2B) #define addr4 (0x2C) #define S1 PC_8 #define S2 PC_9 #define S3 PC_10 #define S4 PC_11 #define S5 PC_12 #define S6 PD_2 #define S7 PG_2 #define S8 PG_3 // VL6180x sensors Sensor sensor_forward(I2C_SDA, I2C_SCL, S1); Sensor sensor_right(I2C_SDA, I2C_SCL, S3); Sensor sensor_back(I2C_SDA, I2C_SCL, S5); Sensor sensor_left(I2C_SDA, I2C_SCL, S7); // Motors Motor motor_left(PC_6, PB_15, PB_13); Motor motor_right(PA_15, PC_7, PB_4); void CheckObstacle() { // When obstacle ahead if (sensor_forward.getIsObstacle()) { if ( (sensor_right.getIsObstacle()) && (sensor_left.getIsObstacle()) ) { //Turn backward while(!sensor_back.getIsObstacle()) { motor_left.moveForward(); motor_right.moveBackward(); } } if (sensor_left.getIsObstacle()) { //Turn to the right motor_left.moveForward(); motor_right.moveBackward(); } else { // By default : turn to the left motor_left.moveBackward(); motor_right.moveForward(); } } // No obstacle else { motor_left.moveForward(); motor_right.moveForward(); } } int main() { int range1; int range2; int range3; int range4; // load settings onto VL6180X sensors sensor_forward.init(); // change default address of sensor 2 sensor_forward.changeAddress(addr2); sensor_right.init(); // change default address of sensor 3 sensor_right.changeAddress(addr3); sensor_back.init(); // change default address of sensor 4 sensor_back.changeAddress(addr4); sensor_left.init(); //Set Speeds motor_left.setSpeed(0.5f); motor_right.setSpeed(0.5f); while (1) { range1 = sensor_forward.read(); range2 = sensor_right.read(); range3 = sensor_back.read(); range4 = sensor_left.read(); pc.printf("Range forward = %d | range back = %d | range right = %d | range left = %d\r\n",range1, range3, range2, range4); // TODO : better name for this method ?? CheckObstacle(); wait_ms(10); } }