Q

Dependencies:   SRF05 ros_lib_kinetic TinyGPSPlus

PROJ515.cpp

Committer:
Luka_Danilovic
Date:
2019-05-01
Revision:
1:ea2ee36038e7
Parent:
0:215bdd87b602
Child:
2:7288dd12186e

File content as of revision 1:ea2ee36038e7:

#include "PROJ515.hpp" // Contains all Libraries, Definitions & Function Prototypes

float cmDistance1;
float wPeriod = 50;


void setupRosMsg()
{/*CODE*/}

int main()
{
    nh.getHardware()->setBaud(921600);           // Set Baud Rate for ROS Serial
    nh.initNode();                                 // Initialise ROS Node Handler
    nh.advertise(ultrasound_pub);                    // Adverstise Odometry topic
       
    ultrasound_msg.header.frame_id = "uss_cb1";
    ultrasound_msg.radiation_type = 0x00;
    ultrasound_msg.field_of_view = ((80*3.14159)/180); //3.14159265358979323846
    ultrasound_msg.min_range = 0.02f;
    ultrasound_msg.max_range = 2.5;
    
    while(!nh.connected()) {                       // While node handler is not connected
        nh.spinOnce();                             // Attempt to connect and synchronise
    }
    
    while(true) {
        
        USS_CB4.start();
        cmDistance1 = USS_CB4.get_dist_cm();
        cmDistance1 = cmDistance1/100; // in meters
        ultrasound_msg.range = cmDistance1;// m
        nh.spinOnce();                             // Reccuring connect and synchronise
        ultrasound_msg.header.stamp = nh.now();      // Get current time
        ultrasound_pub.publish(&ultrasound_msg);
        //usbSer.printf("Distance (m) = %d\n\n", cmDistance);
        wait_ms(5);
    }
}