|
23 | 23 | .option('-r, --run <n>', 'How many times to run') |
24 | 24 | .parse(process.argv); |
25 | 25 |
|
26 | | -rclnodejs.init().then(() => { |
27 | | - const time = process.hrtime(); |
28 | | - let node = rclnodejs.createNode('stress_publisher_rclnodejs'); |
29 | | - const publisher = node.createPublisher('std_msgs/msg/UInt8MultiArray', 'stress_topic'); |
30 | | - let sentTimes = 0; |
31 | | - let totalTimes = app.run || 1; |
32 | | - let size = app.size || 1; |
33 | | - const message = { |
34 | | - layout: { |
35 | | - dim: [ |
36 | | - {label: 'height', size: 10, stride: 600}, |
37 | | - {label: 'width', size: 20, stride: 60}, |
38 | | - {label: 'channel', size: 3, stride: 4}, |
39 | | - ], |
40 | | - data_offset: 0, |
41 | | - }, |
42 | | - data: Uint8Array.from({length: 1024 * size}, (v, k) => k) |
43 | | - }; |
44 | | - console.log(`The publisher will publish a UInt8MultiArray topic(contains a size of ${size}KB array)` + |
45 | | - ` ${totalTimes} times.`); |
| 26 | +rclnodejs |
| 27 | + .init() |
| 28 | + .then(() => { |
| 29 | + const time = process.hrtime(); |
| 30 | + let node = rclnodejs.createNode('stress_publisher_rclnodejs'); |
| 31 | + const publisher = node.createPublisher( |
| 32 | + 'std_msgs/msg/UInt8MultiArray', |
| 33 | + 'stress_topic' |
| 34 | + ); |
| 35 | + let sentTimes = 0; |
| 36 | + let totalTimes = app.run || 1; |
| 37 | + let size = app.size || 1; |
| 38 | + const message = { |
| 39 | + layout: { |
| 40 | + dim: [ |
| 41 | + { label: 'height', size: 10, stride: 600 }, |
| 42 | + { label: 'width', size: 20, stride: 60 }, |
| 43 | + { label: 'channel', size: 3, stride: 4 }, |
| 44 | + ], |
| 45 | + data_offset: 0, |
| 46 | + }, |
| 47 | + data: Uint8Array.from({ length: 1024 * size }, (v, k) => k), |
| 48 | + }; |
| 49 | + console.log( |
| 50 | + `The publisher will publish a UInt8MultiArray topic(contains a size of ${size}KB array)` + |
| 51 | + ` ${totalTimes} times.` |
| 52 | + ); |
46 | 53 |
|
47 | | - setImmediate(() => { |
48 | | - while (sentTimes++ < totalTimes) { |
49 | | - publisher.publish(message); |
50 | | - } |
51 | | - rclnodejs.shutdown(); |
52 | | - const diff = process.hrtime(time); |
53 | | - console.log(`Benchmark took ${diff[0]} seconds and ${Math.ceil(diff[1] / 1000000)} milliseconds.`); |
54 | | - }); |
| 54 | + setImmediate(() => { |
| 55 | + while (sentTimes++ < totalTimes) { |
| 56 | + publisher.publish(message); |
| 57 | + } |
| 58 | + rclnodejs.shutdown(); |
| 59 | + const diff = process.hrtime(time); |
| 60 | + console.log( |
| 61 | + `Benchmark took ${diff[0]} seconds and ${Math.ceil( |
| 62 | + diff[1] / 1000000 |
| 63 | + )} milliseconds.` |
| 64 | + ); |
| 65 | + }); |
55 | 66 |
|
56 | | - rclnodejs.spin(node); |
57 | | -}).catch((err) => { |
58 | | - console.log(err); |
59 | | -}); |
| 67 | + rclnodejs.spin(node); |
| 68 | + }) |
| 69 | + .catch((err) => { |
| 70 | + console.log(err); |
| 71 | + }); |
0 commit comments