Robot team project

Dependencies:   QEI Motordriver ros_lib_melodic

Committer:
florine_van
Date:
Fri Nov 15 17:38:04 2019 +0000
Revision:
12:817da876ae2f
Parent:
11:35809512ec11
Child:
13:d41144f89195
Latest code to use with 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 12:817da876ae2f 3 #include <cstdlib>
florine_van 7:2cf57f28255d 4 #include <std_msgs/Empty.h>
florine_van 7:2cf57f28255d 5 #include <std_msgs/Int32.h>
florine_van 10:be9de79cf6b0 6 #include <std_msgs/String.h>
florine_van 8:57aa8a35d983 7 #include <mbed_custom_msgs/lidar_msg.h>
florine_van 5:8ef79eebbc97 8
florine_van 0:57855aafa907 9 #include "Sensor.h"
florine_van 5:8ef79eebbc97 10 #include "Motor.h"
florine_van 12:817da876ae2f 11 #include "QEI.h"
florine_van 7:2cf57f28255d 12
florine_van 0:57855aafa907 13 // Set up I²C on the STM32 NUCLEO-401RE
florine_van 0:57855aafa907 14 #define addr1 (0x29)
florine_van 0:57855aafa907 15 #define addr2 (0x2A)
florine_van 0:57855aafa907 16 #define addr3 (0x2B)
florine_van 0:57855aafa907 17 #define addr4 (0x2C)
florine_van 0:57855aafa907 18
florine_van 6:858a5116688e 19 #define S1 PC_8
florine_van 6:858a5116688e 20 #define S2 PC_9
florine_van 6:858a5116688e 21 #define S3 PC_10
florine_van 6:858a5116688e 22 #define S4 PC_11
florine_van 6:858a5116688e 23 #define S5 PC_12
florine_van 6:858a5116688e 24 #define S6 PD_2
florine_van 6:858a5116688e 25 #define S7 PG_2
florine_van 6:858a5116688e 26 #define S8 PG_3
florine_van 6:858a5116688e 27
florine_van 5:8ef79eebbc97 28 // VL6180x sensors
florine_van 7:2cf57f28255d 29 Sensor sensor_back(I2C_SDA, I2C_SCL, S1);
florine_van 7:2cf57f28255d 30 Sensor sensor_left(I2C_SDA, I2C_SCL, S3);
florine_van 7:2cf57f28255d 31 Sensor sensor_forward(I2C_SDA, I2C_SCL, S5);
florine_van 7:2cf57f28255d 32 Sensor sensor_right(I2C_SDA, I2C_SCL, S7);
florine_van 5:8ef79eebbc97 33
florine_van 5:8ef79eebbc97 34 // Motors
florine_van 11:35809512ec11 35 QEI wheel_A (PB_12, PA_4, NC, 3576, QEI::X4_ENCODING); //counts per rev = 12 * 298:1, use quadrature encoding
florine_van 11:35809512ec11 36 QEI wheel_B (PB_5, PB_3, NC, 3576, QEI::X4_ENCODING); //counts per rev = 12 * 298:1, use quadrature encoding
florine_van 12:817da876ae2f 37 Motor motor_left(PC_6, PB_15, PB_13);
florine_van 12:817da876ae2f 38 Motor motor_right(PA_15, PC_7, PB_4);
florine_van 12:817da876ae2f 39
florine_van 12:817da876ae2f 40
florine_van 12:817da876ae2f 41 void pulse(int distance)
florine_van 12:817da876ae2f 42 {
florine_van 12:817da876ae2f 43 // Variable to allow for any pulse reading
florine_van 12:817da876ae2f 44 float current_pulse_reading = wheel_B.getPulses();
florine_van 12:817da876ae2f 45
florine_van 12:817da876ae2f 46 while(abs(current_pulse_reading) <= distance)
florine_van 12:817da876ae2f 47 {
florine_van 12:817da876ae2f 48 current_pulse_reading = wheel_A.getPulses();
florine_van 12:817da876ae2f 49 }
florine_van 12:817da876ae2f 50
florine_van 12:817da876ae2f 51 motor_left.stop();
florine_van 12:817da876ae2f 52 motor_right.stop();
florine_van 12:817da876ae2f 53
florine_van 12:817da876ae2f 54 wheel_A.reset();
florine_van 12:817da876ae2f 55 wheel_B.reset();
florine_van 12:817da876ae2f 56 }
florine_van 5:8ef79eebbc97 57
florine_van 10:be9de79cf6b0 58 void controlMotor(const std_msgs::Int32& motor_dir)
florine_van 10:be9de79cf6b0 59 {
florine_van 11:35809512ec11 60 switch(motor_dir.data) {
florine_van 12:817da876ae2f 61 // Stop motors
florine_van 11:35809512ec11 62 case 0:
florine_van 12:817da876ae2f 63 motor_left.stop();
florine_van 12:817da876ae2f 64 motor_right.stop();
florine_van 11:35809512ec11 65 break;
florine_van 11:35809512ec11 66
florine_van 10:be9de79cf6b0 67 // Move forward
florine_van 10:be9de79cf6b0 68 case 1:
florine_van 12:817da876ae2f 69 motor_left.moveForward();
florine_van 12:817da876ae2f 70 motor_right.moveForward();
florine_van 12:817da876ae2f 71 pulse(5691);
florine_van 10:be9de79cf6b0 72 break;
florine_van 10:be9de79cf6b0 73
florine_van 10:be9de79cf6b0 74 // Move left
florine_van 10:be9de79cf6b0 75 case 2:
florine_van 12:817da876ae2f 76 motor_left.moveBackward();
florine_van 12:817da876ae2f 77 motor_right.moveForward();
florine_van 12:817da876ae2f 78 pulse(3000);
florine_van 10:be9de79cf6b0 79 break;
florine_van 10:be9de79cf6b0 80
florine_van 10:be9de79cf6b0 81 // Move right
florine_van 10:be9de79cf6b0 82 case 3:
florine_van 12:817da876ae2f 83 motor_left.moveForward();
florine_van 12:817da876ae2f 84 motor_right.moveBackward();
florine_van 12:817da876ae2f 85 pulse(3000);
florine_van 12:817da876ae2f 86 break;
florine_van 12:817da876ae2f 87
florine_van 12:817da876ae2f 88 // Reverse
florine_van 12:817da876ae2f 89 case 4:
florine_van 12:817da876ae2f 90 motor_left.moveBackward();
florine_van 12:817da876ae2f 91 motor_right.moveBackward();
florine_van 12:817da876ae2f 92 pulse(5691);
florine_van 10:be9de79cf6b0 93 break;
florine_van 10:be9de79cf6b0 94 }
florine_van 10:be9de79cf6b0 95 }
florine_van 10:be9de79cf6b0 96
florine_van 5:8ef79eebbc97 97 int main()
florine_van 5:8ef79eebbc97 98 {
florine_van 7:2cf57f28255d 99 ros::NodeHandle nh;
florine_van 7:2cf57f28255d 100 nh.initNode();
florine_van 8:57aa8a35d983 101
florine_van 10:be9de79cf6b0 102 // ROS publisher for sensor readings
florine_van 12:817da876ae2f 103 mbed_custom_msgs::lidar_msg lidar_msg;
florine_van 12:817da876ae2f 104 ros::Publisher lidar_pub("lidar_reading", &lidar_msg);
florine_van 12:817da876ae2f 105
florine_van 12:817da876ae2f 106 // ROS subscriber for motors control
florine_van 12:817da876ae2f 107 ros::Subscriber<std_msgs::Int32> motor_sub("motor_control", &controlMotor);
florine_van 11:35809512ec11 108
florine_van 8:57aa8a35d983 109 nh.advertise(lidar_pub);
florine_van 10:be9de79cf6b0 110 nh.subscribe(motor_sub);
florine_van 3:a3144a45f44c 111
florine_van 3:a3144a45f44c 112 // load settings onto VL6180X sensors
florine_van 6:858a5116688e 113 sensor_forward.init();
florine_van 3:a3144a45f44c 114 // change default address of sensor 2
florine_van 6:858a5116688e 115 sensor_forward.changeAddress(addr2);
florine_van 12:817da876ae2f 116
florine_van 6:858a5116688e 117 sensor_right.init();
florine_van 3:a3144a45f44c 118 // change default address of sensor 3
florine_van 6:858a5116688e 119 sensor_right.changeAddress(addr3);
florine_van 2:c537f1ebad7b 120
florine_van 6:858a5116688e 121 sensor_back.init();
florine_van 3:a3144a45f44c 122 // change default address of sensor 4
florine_van 6:858a5116688e 123 sensor_back.changeAddress(addr4);
florine_van 6:858a5116688e 124
florine_van 6:858a5116688e 125 sensor_left.init();
florine_van 2:c537f1ebad7b 126
florine_van 6:858a5116688e 127 //Set Speeds
florine_van 6:858a5116688e 128 motor_left.setSpeed(0.5f);
florine_van 6:858a5116688e 129 motor_right.setSpeed(0.5f);
florine_van 0:57855aafa907 130
florine_van 0:57855aafa907 131 while (1)
florine_van 12:817da876ae2f 132 {
florine_van 12:817da876ae2f 133 lidar_msg.sensor_forward = sensor_forward.read();
florine_van 12:817da876ae2f 134 lidar_msg.sensor_back = sensor_back.read();
florine_van 12:817da876ae2f 135 lidar_msg.sensor_left = sensor_left.read();
florine_van 12:817da876ae2f 136 lidar_msg.sensor_right = sensor_right.read();
florine_van 12:817da876ae2f 137 lidar_pub.publish(&lidar_msg);
florine_van 12:817da876ae2f 138
florine_van 7:2cf57f28255d 139 nh.spinOnce();
florine_van 5:8ef79eebbc97 140
florine_van 4:cb50c6fa340b 141 wait_ms(10);
florine_van 0:57855aafa907 142 }
florine_van 0:57855aafa907 143 }
florine_van 0:57855aafa907 144
florine_van 5:8ef79eebbc97 145
florine_van 5:8ef79eebbc97 146