Testing sensor

Committer:
zillkhan
Date:
Tue Sep 28 12:38:25 2021 +0000
Revision:
3:1be742e63b57
Parent:
2:13cda079f08d
final code

Who changed what in which revision?

UserRevisionLine numberNew contents of line
zillkhan 1:ca82df4237eb 1 #include <ros.h>
zillkhan 1:ca82df4237eb 2 #include <std_msgs/Float32.h>
zillkhan 1:ca82df4237eb 3 #include <std_msgs/String.h>
Tomas 0:d94848220e71 4 #include "SHARPIR.h"
Tomas 0:d94848220e71 5
zillkhan 1:ca82df4237eb 6
zillkhan 1:ca82df4237eb 7 ros::NodeHandle nh;
zillkhan 1:ca82df4237eb 8
zillkhan 1:ca82df4237eb 9 std_msgs::Float32 data;
zillkhan 1:ca82df4237eb 10 ros::Publisher sharpir("sharpir", &data);
zillkhan 1:ca82df4237eb 11
zillkhan 1:ca82df4237eb 12 SHARPIR Sensor(A0);
zillkhan 1:ca82df4237eb 13
zillkhan 1:ca82df4237eb 14
Tomas 0:d94848220e71 15 int main() {
Tomas 0:d94848220e71 16 float DistanceCM;
zillkhan 1:ca82df4237eb 17
zillkhan 1:ca82df4237eb 18 nh.initNode();
zillkhan 1:ca82df4237eb 19 nh.advertise(sharpir);
zillkhan 1:ca82df4237eb 20
Tomas 0:d94848220e71 21 while (1) { //creates an eternal loop
zillkhan 1:ca82df4237eb 22
zillkhan 1:ca82df4237eb 23 DistanceCM=Sensor.cm();
zillkhan 1:ca82df4237eb 24 //sprintf (buffer, "%f", DistanceCM);
zillkhan 1:ca82df4237eb 25
zillkhan 1:ca82df4237eb 26 data.data = DistanceCM;
zillkhan 1:ca82df4237eb 27 sharpir.publish( &data );
zillkhan 1:ca82df4237eb 28
zillkhan 1:ca82df4237eb 29 nh.spinOnce();
zillkhan 1:ca82df4237eb 30 wait_ms(1000);
Tomas 0:d94848220e71 31 }
Tomas 0:d94848220e71 32 }