Old working code

Dependencies:   mbed QEI ros_lib_melodic

Committer:
florine_van
Date:
Wed Oct 23 14:00:26 2019 +0000
Revision:
7:2cf57f28255d
Parent:
6:858a5116688e
Child:
8:57aa8a35d983
Not working code for ROS

Who changed what in which revision?

UserRevisionLine numberNew contents of line
florine_van 0:57855aafa907 1 #include "mbed.h"
florine_van 7:2cf57f28255d 2 #include <ros.h>
florine_van 7:2cf57f28255d 3 #include <std_msgs/Empty.h>
florine_van 7:2cf57f28255d 4 #include <std_msgs/Int32.h>
florine_van 5:8ef79eebbc97 5
florine_van 0:57855aafa907 6 #include "Sensor.h"
florine_van 5:8ef79eebbc97 7 #include "Motor.h"
florine_van 0:57855aafa907 8
florine_van 0:57855aafa907 9 // Set up serial to pc
florine_van 7:2cf57f28255d 10 //Serial pc(SERIAL_TX, SERIAL_RX);
florine_van 7:2cf57f28255d 11
florine_van 7:2cf57f28255d 12 // Set up ROS
florine_van 7:2cf57f28255d 13 ros::NodeHandle nh;
florine_van 0:57855aafa907 14
florine_van 0:57855aafa907 15 // Set up I²C on the STM32 NUCLEO-401RE
florine_van 0:57855aafa907 16 #define addr1 (0x29)
florine_van 0:57855aafa907 17 #define addr2 (0x2A)
florine_van 0:57855aafa907 18 #define addr3 (0x2B)
florine_van 0:57855aafa907 19 #define addr4 (0x2C)
florine_van 0:57855aafa907 20
florine_van 6:858a5116688e 21 #define S1 PC_8
florine_van 6:858a5116688e 22 #define S2 PC_9
florine_van 6:858a5116688e 23 #define S3 PC_10
florine_van 6:858a5116688e 24 #define S4 PC_11
florine_van 6:858a5116688e 25 #define S5 PC_12
florine_van 6:858a5116688e 26 #define S6 PD_2
florine_van 6:858a5116688e 27 #define S7 PG_2
florine_van 6:858a5116688e 28 #define S8 PG_3
florine_van 6:858a5116688e 29
florine_van 5:8ef79eebbc97 30 // VL6180x sensors
florine_van 7:2cf57f28255d 31 Sensor sensor_back(I2C_SDA, I2C_SCL, S1);
florine_van 7:2cf57f28255d 32 Sensor sensor_left(I2C_SDA, I2C_SCL, S3);
florine_van 7:2cf57f28255d 33 Sensor sensor_forward(I2C_SDA, I2C_SCL, S5);
florine_van 7:2cf57f28255d 34 Sensor sensor_right(I2C_SDA, I2C_SCL, S7);
florine_van 5:8ef79eebbc97 35
florine_van 5:8ef79eebbc97 36 // Motors
florine_van 6:858a5116688e 37 Motor motor_left(PC_6, PB_15, PB_13);
florine_van 6:858a5116688e 38 Motor motor_right(PA_15, PC_7, PB_4);
florine_van 7:2cf57f28255d 39
florine_van 7:2cf57f28255d 40 void avoidObstacle(const std_msgs::Empty& avoid_obstacle_msg)
florine_van 6:858a5116688e 41 {
florine_van 5:8ef79eebbc97 42 // When obstacle ahead
florine_van 6:858a5116688e 43 if (sensor_forward.getIsObstacle())
florine_van 5:8ef79eebbc97 44 {
florine_van 6:858a5116688e 45 if ( (sensor_right.getIsObstacle()) && (sensor_left.getIsObstacle()) )
florine_van 6:858a5116688e 46 {
florine_van 6:858a5116688e 47 //Turn backward
florine_van 6:858a5116688e 48 while(!sensor_back.getIsObstacle())
florine_van 6:858a5116688e 49 {
florine_van 6:858a5116688e 50 motor_left.moveForward();
florine_van 6:858a5116688e 51 motor_right.moveBackward();
florine_van 6:858a5116688e 52 }
florine_van 6:858a5116688e 53 }
florine_van 6:858a5116688e 54 if (sensor_left.getIsObstacle())
florine_van 6:858a5116688e 55 {
florine_van 6:858a5116688e 56 //Turn to the right
florine_van 6:858a5116688e 57 motor_left.moveForward();
florine_van 6:858a5116688e 58 motor_right.moveBackward();
florine_van 6:858a5116688e 59 }
florine_van 6:858a5116688e 60 else
florine_van 6:858a5116688e 61 {
florine_van 6:858a5116688e 62 // By default : turn to the left
florine_van 6:858a5116688e 63 motor_left.moveBackward();
florine_van 6:858a5116688e 64 motor_right.moveForward();
florine_van 6:858a5116688e 65 }
florine_van 5:8ef79eebbc97 66 }
florine_van 5:8ef79eebbc97 67 // No obstacle
florine_van 5:8ef79eebbc97 68 else
florine_van 5:8ef79eebbc97 69 {
florine_van 6:858a5116688e 70 motor_left.moveForward();
florine_van 6:858a5116688e 71 motor_right.moveForward();
florine_van 5:8ef79eebbc97 72 }
florine_van 5:8ef79eebbc97 73 }
florine_van 5:8ef79eebbc97 74
florine_van 7:2cf57f28255d 75 ros::Subscriber<std_msgs::Empty> avoid_obstacle_sub("avoid_obstacle", &avoidObstacle);
florine_van 7:2cf57f28255d 76
florine_van 5:8ef79eebbc97 77 int main()
florine_van 5:8ef79eebbc97 78 {
florine_van 7:2cf57f28255d 79 ros::NodeHandle nh;
florine_van 7:2cf57f28255d 80 nh.initNode();
florine_van 7:2cf57f28255d 81
florine_van 7:2cf57f28255d 82 std_msgs::Int32 int1_sensor_msg;
florine_van 7:2cf57f28255d 83 ros::Publisher range_forward_pub("sensor_forward", &int1_sensor_msg);
florine_van 7:2cf57f28255d 84 nh.advertise(range_forward_pub);
florine_van 7:2cf57f28255d 85
florine_van 7:2cf57f28255d 86 std_msgs::Int32 int2_sensor_msg;
florine_van 7:2cf57f28255d 87 ros::Publisher range_back_pub("sensor_back", &int2_sensor_msg);
florine_van 7:2cf57f28255d 88 nh.advertise(range_forward_pub);
florine_van 7:2cf57f28255d 89
florine_van 7:2cf57f28255d 90 std_msgs::Int32 int3_sensor_msg;
florine_van 7:2cf57f28255d 91 ros::Publisher range_left_pub("sensor_left", &int3_sensor_msg);
florine_van 7:2cf57f28255d 92 nh.advertise(range_forward_pub);
florine_van 7:2cf57f28255d 93
florine_van 7:2cf57f28255d 94 std_msgs::Int32 int4_sensor_msg;
florine_van 7:2cf57f28255d 95 ros::Publisher range_right_pub("sensor_right", &int4_sensor_msg);
florine_van 7:2cf57f28255d 96 nh.advertise(range_forward_pub);
florine_van 7:2cf57f28255d 97
florine_van 7:2cf57f28255d 98 nh.subscribe(avoid_obstacle_sub);
florine_van 7:2cf57f28255d 99
florine_van 0:57855aafa907 100 int range1;
florine_van 1:d5adc483bce0 101 int range2;
florine_van 2:c537f1ebad7b 102 int range3;
florine_van 2:c537f1ebad7b 103 int range4;
florine_van 3:a3144a45f44c 104
florine_van 3:a3144a45f44c 105 // load settings onto VL6180X sensors
florine_van 6:858a5116688e 106 sensor_forward.init();
florine_van 3:a3144a45f44c 107 // change default address of sensor 2
florine_van 6:858a5116688e 108 sensor_forward.changeAddress(addr2);
florine_van 2:c537f1ebad7b 109
florine_van 6:858a5116688e 110 sensor_right.init();
florine_van 3:a3144a45f44c 111 // change default address of sensor 3
florine_van 6:858a5116688e 112 sensor_right.changeAddress(addr3);
florine_van 2:c537f1ebad7b 113
florine_van 6:858a5116688e 114 sensor_back.init();
florine_van 3:a3144a45f44c 115 // change default address of sensor 4
florine_van 6:858a5116688e 116 sensor_back.changeAddress(addr4);
florine_van 6:858a5116688e 117
florine_van 6:858a5116688e 118 sensor_left.init();
florine_van 2:c537f1ebad7b 119
florine_van 6:858a5116688e 120 //Set Speeds
florine_van 6:858a5116688e 121 motor_left.setSpeed(0.5f);
florine_van 6:858a5116688e 122 motor_right.setSpeed(0.5f);
florine_van 0:57855aafa907 123
florine_van 0:57855aafa907 124 while (1)
florine_van 0:57855aafa907 125 {
florine_van 6:858a5116688e 126 range1 = sensor_forward.read();
florine_van 6:858a5116688e 127 range2 = sensor_right.read();
florine_van 6:858a5116688e 128 range3 = sensor_back.read();
florine_van 6:858a5116688e 129 range4 = sensor_left.read();
florine_van 0:57855aafa907 130
florine_van 7:2cf57f28255d 131 //pc.printf("Range forward = %d | range back = %d | range right = %d | range left = %d\r\n",range1, range3, range2, range4);
florine_van 7:2cf57f28255d 132
florine_van 7:2cf57f28255d 133 int1_sensor_msg.data = range1;
florine_van 7:2cf57f28255d 134 int2_sensor_msg.data = range3;
florine_van 7:2cf57f28255d 135 int3_sensor_msg.data = range4;
florine_van 7:2cf57f28255d 136 int4_sensor_msg.data = range2;
florine_van 7:2cf57f28255d 137 range_forward_pub.publish(&int1_sensor_msg);
florine_van 7:2cf57f28255d 138 range_back_pub.publish(&int2_sensor_msg);
florine_van 7:2cf57f28255d 139 range_left_pub.publish(&int3_sensor_msg);
florine_van 7:2cf57f28255d 140 range_right_pub.publish(&int4_sensor_msg);
florine_van 7:2cf57f28255d 141
florine_van 7:2cf57f28255d 142 nh.spinOnce();
florine_van 5:8ef79eebbc97 143
florine_van 7:2cf57f28255d 144 //avoidObstacle();
florine_van 5:8ef79eebbc97 145
florine_van 4:cb50c6fa340b 146 wait_ms(10);
florine_van 0:57855aafa907 147 }
florine_van 0:57855aafa907 148 }
florine_van 0:57855aafa907 149
florine_van 5:8ef79eebbc97 150
florine_van 5:8ef79eebbc97 151