-
Notifications
You must be signed in to change notification settings - Fork 20
/
vadd_publisher.cpp
102 lines (89 loc) · 2.89 KB
/
vadd_publisher.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
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
/*
____ ____
/ /\/ /
/___/ \ / Copyright (c) 2021, Xilinx®.
\ \ \/ Author: Víctor Mayoral Vilches <[email protected]>
\ \
/ /
/___/ /\
\ \ / \
\___\/\___\
Inspired by the Vector-Add example.
See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis
*/
#include <chrono> // NOLINT
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "vadd.hpp"
#include "tracetools/tracetools.h"
#include "tracetools_acceleration/tracetools.h"
#define DATA_SIZE 4096 // 2**12
// #define DATA_SIZE 16384 // 2**14
// #define DATA_SIZE 65536 // 2**16
// #define DATA_SIZE 262144 // 2**18
using namespace std::chrono_literals; // NOLINT
bool check_vadd(
const unsigned int *in1, // Read-Only Vector 1
const unsigned int *in2, // Read-Only Vector 2
const unsigned int *out // Read-Only Result
) {
bool match = true;
// no need to iterate twice through the loop, math's the same
for (int i = 0 ; i < DATA_SIZE ; i++) {
unsigned int expected = in1[i]+in2[i];
if (out[i] != expected) {
std::cout << "Error: Result mismatch" << std::endl;
std::cout << "i = " << i << " CPU result = "
<< expected << " Device result = " << out[i] << std::endl;
match = false;
break;
}
}
return match;
}
int main(int argc, char * argv[]) {
// ROS 2 abstractions
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("vadd_publisher");
auto publisher = node->create_publisher<std_msgs::msg::String>("vector", 10);
auto publish_count = 0;
std_msgs::msg::String message;
rclcpp::WallRate loop_rate(100ms);
// Application variables
unsigned int in1[DATA_SIZE];
unsigned int in2[DATA_SIZE];
unsigned int out[DATA_SIZE];
while (rclcpp::ok()) {
// randomize the vectors used
for (int i = 0 ; i < DATA_SIZE ; i++) {
in1[i] = rand() % DATA_SIZE; // NOLINT
in2[i] = rand() % DATA_SIZE; // NOLINT
out[i] = 0;
}
TRACEPOINT(vadd_pre, ("iteration: " + std::to_string(publish_count)).c_str());
// Add vectors
vadd(in1, in2, out, DATA_SIZE); // function subject to be accelerated
TRACEPOINT(vadd_post, ("iteration: " + std::to_string(publish_count)).c_str());
// Validate operation
check_vadd(in1, in2, out);
// Publish publish result
message.data = "vadd finished, iteration: " +
std::to_string(publish_count++);
RCLCPP_INFO(node->get_logger(), "Publishing: '%s'", message.data.c_str());
try {
publisher->publish(message);
rclcpp::spin_some(node);
} catch (const rclcpp::exceptions::RCLError & e) {
RCLCPP_ERROR(
node->get_logger(),
"unexpectedly failed with %s",
e.what());
}
loop_rate.sleep();
}
rclcpp::shutdown();
return 0;
}