UNPKG

rclnodejs

Version:
87 lines (71 loc) 2.2 kB
// Reprocer for https://github.com/RobotWebTools/rclnodejs/issues/1394 // Tests subscription throughput at ~10Hz publishing rate 'use strict'; const rclnodejs = require('./index.js'); const PUBLISH_HZ = 10; const TEST_DURATION_SEC = 10; async function main() { await rclnodejs.init(); const pubNode = new rclnodejs.Node('test_pub_node'); const subNode = new rclnodejs.Node('test_sub_node'); const publisher = pubNode.createPublisher( 'std_msgs/msg/Float64MultiArray', '/test_hz_topic' ); let msgCount = 0; let lastTs = null; const hzSamples = []; subNode.createSubscription( 'std_msgs/msg/Float64MultiArray', '/test_hz_topic', (msg) => { const now = Date.now(); msgCount++; if (lastTs) { const hz = 1000 / (now - lastTs); hzSamples.push(hz); } lastTs = now; } ); pubNode.spin(); subNode.spin(); // Publish at target Hz let pubCount = 0; const pubInterval = setInterval(() => { publisher.publish({ data: [1.0, 2.0, 3.0] }); pubCount++; }, 1000 / PUBLISH_HZ); // Wait for test duration then report setTimeout(() => { clearInterval(pubInterval); if (hzSamples.length > 0) { const avgHz = hzSamples.reduce((a, b) => a + b, 0) / hzSamples.length; const minHz = Math.min(...hzSamples); const maxHz = Math.max(...hzSamples); console.log(`Published: ${pubCount} messages`); console.log(`Received: ${msgCount} messages`); console.log(`Avg Hz: ${avgHz.toFixed(2)}`); console.log(`Min Hz: ${minHz.toFixed(2)}`); console.log(`Max Hz: ${maxHz.toFixed(2)}`); console.log( `Expected: ~${PUBLISH_HZ} Hz` ); if (avgHz < PUBLISH_HZ * 0.5) { console.log( `\n*** REGRESSION DETECTED: Average Hz (${avgHz.toFixed(2)}) is less than 50% of expected (${PUBLISH_HZ}) ***` ); } else { console.log('\nPerformance looks OK.'); } } else { console.log('No messages received!'); } pubNode.stop(); subNode.stop(); rclnodejs.shutdown(); process.exit(0); }, TEST_DURATION_SEC * 1000); } main().catch(console.error);