-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathsent.cpp
41 lines (36 loc) · 1.04 KB
/
sent.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
#include <ros/ros.h>
#include <std_msgs/Float32MultiArray.h>
#include <string>
#include <vector>
#include "simple_udp.h"
std::vector<float> send_data_array;
std::string send_data;
std::string separator = ",";
void callback(const std_msgs::Float32MultiArray& array)
{
send_data_array = array.data;
send_data = std::to_string(send_data_array[0]);
//combine string data
for(int i=1; i<send_data_array.size(); i++){
send_data.append(separator + std::to_string(send_data_array[i]));
}
//ROS_INFO("subscribe: %f", send_data_array.data);
}
int main(int argc, char **argv){
std::string IPadress = "192.168.0.200";
int portNumber = 9070;
ros::init(argc, argv, "sentUDP");
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
pnh.getParam("clientIP", IPadress);
pnh.getParam("clientPort", portNumber);
simple_udp udp0(IPadress, portNumber);
ros::Subscriber sub = nh.subscribe("sentUDP", 10, callback);
ros::Rate loop_rate(10);
while(ros::ok()){
udp0.udp_send(send_data);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}