Robot team project

Dependencies:   QEI Motordriver ros_lib_melodic

main.cpp

Committer:
florine_van
Date:
2019-11-13
Revision:
11:35809512ec11
Parent:
10:be9de79cf6b0
Child:
12:817da876ae2f
Child:
14:08047fde54f6

File content as of revision 11:35809512ec11:

#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
QEI wheel_A (PB_12, PA_4, NC, 3576, QEI::X4_ENCODING); //counts per rev = 12 * 298:1, use quadrature encoding
QEI wheel_B (PB_5, PB_3, NC, 3576, QEI::X4_ENCODING); //counts per rev = 12 * 298:1, use quadrature encoding
Motor motor_left(PC_6, PB_15, PB_13, wheel_A);
Motor motor_right(PA_15, PC_7, PB_4, wheel_B);

void controlMotor(const std_msgs::Int32& motor_dir)
{
    switch(motor_dir.data) {
        // Stop motor
        case 0:
            motor_left.moveForward(0);
            motor_right.moveForward(0);
            break;
            
        // Move forward
        case 1:
            motor_left.moveForward(5691);
            motor_right.moveForward(5691);
            break;
    
        // Move left
        case 2:
            motor_left.moveLeft(0.5);
            motor_right.moveLeft(-0.5);      
            break;
            
        // Move right
        case 3:
            motor_left.moveRight(-0.5);
            motor_right.moveBackward(0.5);
            break;
    }
}

// ROS subscriber for motors control
ros::Subscriber<std_msgs::Int32> motor_sub("motor_control", &controlMotor);


int main() 
{
    ros::NodeHandle  nh;
    nh.initNode();
    
    // ROS publisher for sensor readings
    mbed_custom_msgs::lidar_msg int_lidar_msg;
    ros::Publisher lidar_pub("lidar_reading", &int_lidar_msg);

    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)
    {        
        int_lidar_msg.sensor_forward  = sensor_forward.read();
        int_lidar_msg.sensor_right  = sensor_right.read();
        int_lidar_msg.sensor_back  = sensor_back.read();
        int_lidar_msg.sensor_left  = sensor_left.read();         

        lidar_pub.publish(&int_lidar_msg);
        
        /*
        int range;
        range = sensor_forward.read();
        pc.printf("Range = %d\r\n", range);
        */
        
        nh.spinOnce();
              
        wait_ms(10); 
    } 
}