Old working code
Dependencies: mbed QEI ros_lib_melodic
main.cpp
- Committer:
- florine_van
- Date:
- 2019-11-15
- Revision:
- 12:0fa4c5a86c75
- Parent:
- 11:35809512ec11
- Child:
- 13:0be39d0abac7
File content as of revision 12:0fa4c5a86c75:
#include "mbed.h" #include <ros.h> #include <std_msgs/Empty.h> #include <std_msgs/Int32.h> #include <std_msgs/String.h> #include <mbed_custom_msgs/lidar_msg.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_back(I2C_SDA, I2C_SCL, S1); Sensor sensor_left(I2C_SDA, I2C_SCL, S3); Sensor sensor_forward(I2C_SDA, I2C_SCL, S5); Sensor sensor_right(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 controlMotor(const std_msgs::Int32& motor_dir) { switch(motor_dir.data) { case 0: motor_left.stop(); motor_right.stop(); break; // Move forward case 1: motor_left.moveForward(); motor_right.moveForward(); break; // Move left case 2: motor_left.moveBackward(); motor_right.moveForward(); break; // Move right case 3: motor_left.moveForward(); motor_right.moveBackward(); break; } } int main() { ros::NodeHandle nh; nh.initNode(); // ROS publisher for sensor readings mbed_custom_msgs::lidar_msg lidar_msg; ros::Publisher lidar_pub("lidar_reading", &lidar_msg); // ROS subscriber for motors control ros::Subscriber<std_msgs::Int32> motor_sub("motor_control", &controlMotor); nh.advertise(lidar_pub); nh.subscribe(motor_sub); // 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) { lidar_msg.sensor_forward = sensor_forward.read(); lidar_msg.sensor_back = sensor_back.read(); lidar_msg.sensor_left = sensor_left.read(); lidar_msg.sensor_right = sensor_right.read(); lidar_pub.publish(&lidar_msg); /* int range; range = sensor_forward.read(); pc.printf("Range = %d\r\n", range); */ nh.spinOnce(); wait_ms(10); } }