Zill Khan
/
ROS_HCSR04_test
Integration of HCSR04 with Nucleo board. ROS Enabled
Diff: main.cpp
- Revision:
- 1:ca82df4237eb
- Parent:
- 0:d94848220e71
- Child:
- 2:2bdc0f9b1a69
- Child:
- 4:13cda079f08d
--- a/main.cpp Thu Feb 02 11:01:07 2012 +0000 +++ b/main.cpp Fri Sep 10 09:24:48 2021 +0000 @@ -1,11 +1,33 @@ #include "mbed.h" +#include <ros.h> +#include <std_msgs/Float32.h> +#include <std_msgs/String.h> #include "SHARPIR.h" -SHARPIR Sensor(p10); //the output of the sharpIR sensor is connected to the MBEDs pin 10. + +ros::NodeHandle nh; + +std_msgs::Float32 data; +ros::Publisher sharpir("sharpir", &data); + +SHARPIR Sensor(A0); + + int main() { float DistanceCM; + + nh.initNode(); + nh.advertise(sharpir); + while (1) { //creates an eternal loop - DistanceCM=Sensor.cm(); - wait_ms(20); //wait 20 ms between each readout + + DistanceCM=Sensor.cm(); + //sprintf (buffer, "%f", DistanceCM); + + data.data = DistanceCM; + sharpir.publish( &data ); + + nh.spinOnce(); + wait_ms(1000); } }