Skip to content

Commit

Permalink
[PnP]Customize the period of a publisher to send a topic
Browse files Browse the repository at this point in the history
This patch implements that tester can input the period of a publish
which is used to send the topic when the test is launching.

Fix #308
  • Loading branch information
Minggang Wang committed Apr 9, 2018
1 parent b0123dc commit 4943d66
Show file tree
Hide file tree
Showing 6 changed files with 101 additions and 80 deletions.
11 changes: 8 additions & 3 deletions benchmark/rclcpp/publisher-endurance-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,19 +34,24 @@ int main(int argc, char* argv[]) {
msg->effort = std::vector<double>{4.0, 5.0, 6.0};

auto totalTimes = 0;
int ms = 0;
printf("How many times do you want to run?\n");
scanf("%d", &totalTimes);
printf("Please enter the period of publishing a topic in millisecond\n");
scanf("%d", &ms);

printf(
"The publisher will publish a JointState topic %d times every 100ms\n",
totalTimes);
"The publisher will publish a JointState topic %d times every %dms\n",
totalTimes, ms);
printf("Begin at %s\n", GetCurrentTime());

auto node = rclcpp::Node::make_shared("endurance_publisher_rclcpp");
auto publisher =
node->create_publisher<sensor_msgs::msg::JointState>("endurance_topic");
auto sentTimes = 0;

rclcpp::WallRate wall_rate(std::chrono::milliseconds(100));
auto period = std::chrono::milliseconds(ms);
rclcpp::WallRate wall_rate(period);
while (rclcpp::ok()) {
if (sentTimes > totalTimes) {
rclcpp::shutdown();
Expand Down
8 changes: 6 additions & 2 deletions benchmark/rclcpp/publisher-stress-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,19 +48,23 @@ int main(int argc, char* argv[]) {
msg->data = std::vector<uint8_t>(1024 * 1024 * 10, 255);

auto totalTimes = 0;
int ms = 0;
printf("How many times do you want to run?\n");
scanf("%d", &totalTimes);
printf("Please enter the period of publishing a topic in millisecond\n");
scanf("%d", &ms);
printf(
"The publisher will publish a UInt8MultiArray topic(contains a size of "
"10MB array) %d times every 100ms.\n", totalTimes);
"10MB array) %d times every %dms.\n", totalTimes, ms);
printf("Begin at %s\n", GetCurrentTime());

auto node = rclcpp::Node::make_shared("stress_publisher_rclcpp");
auto publisher =
node->create_publisher<std_msgs::msg::UInt8MultiArray>("stress_topic");
auto sentTimes = 0;

rclcpp::WallRate wall_rate(std::chrono::milliseconds(100));
auto period = std::chrono::milliseconds(ms);
rclcpp::WallRate wall_rate(period);
while (rclcpp::ok()) {
if (sentTimes > totalTimes) {
rclcpp::shutdown();
Expand Down
69 changes: 36 additions & 33 deletions benchmark/rclnodejs/publisher-endurance-test.js
Original file line number Diff line number Diff line change
Expand Up @@ -24,42 +24,45 @@ const rl = readline.createInterface({
});

rl.question('How many times do you want to run? ', (times) => {
rclnodejs.init().then(() => {
const JointState = 'sensor_msgs/msg/JointState';
const state = {
header: {
stamp: {
sec: 123456,
nanosec: 789,
rl.question('Please enter the period of publishing a topic in millisecond ', (ms) => {
rclnodejs.init().then(() => {
const JointState = 'sensor_msgs/msg/JointState';
const state = {
header: {
stamp: {
sec: 123456,
nanosec: 789,
},
frame_id: 'main_frame',
},
frame_id: 'main_frame',
},
name: ['Tom', 'Jerry'],
position: [1, 2],
velocity: [2, 3],
effort: [4, 5, 6],
};
name: ['Tom', 'Jerry'],
position: [1, 2],
velocity: [2, 3],
effort: [4, 5, 6],
};
let period = parseInt(ms, 10);

console.log(`The publisher will publish a JointState topic ${times} times every 100ms.`);
console.log(`Begin at ${new Date().toString()}.`);
console.log(`The publisher will publish a JointState topic ${times} times every ${period}ms.`);
console.log(`Begin at ${new Date().toString()}.`);

let node = rclnodejs.createNode('endurance_publisher_rclnodejs');
let publisher = node.createPublisher(JointState, 'endurance_topic');
let sentTimes = 0;
let totalTimes = parseInt(times, 10);
let node = rclnodejs.createNode('endurance_publisher_rclnodejs');
let publisher = node.createPublisher(JointState, 'endurance_topic');
let sentTimes = 0;
let totalTimes = parseInt(times, 10);

let timer = setInterval(() => {
if (sentTimes++ > totalTimes) {
clearInterval(timer);
rclnodejs.shutdown();
console.log(`End at ${new Date().toString()}`);
} else {
publisher.publish(state);
}}, 100);
rclnodejs.spin(node);
}).catch((err) => {
console.log(err);
});
let timer = setInterval(() => {
if (sentTimes++ > totalTimes) {
clearInterval(timer);
rclnodejs.shutdown();
console.log(`End at ${new Date().toString()}`);
} else {
publisher.publish(state);
}}, period);
rclnodejs.spin(node);
}).catch((err) => {
console.log(err);
});

rl.close();
rl.close();
});
});
74 changes: 39 additions & 35 deletions benchmark/rclnodejs/publisher-stress-test.js
Original file line number Diff line number Diff line change
Expand Up @@ -24,40 +24,44 @@ const rl = readline.createInterface({
});

rl.question('How many times do you want to run? ', (times) => {
const message = {
layout: {
dim: [
{label: 'height', size: 10, stride: 600},
{label: 'width', size: 20, stride: 60},
{label: 'channel', size: 3, stride: 4},
],
data_offset: 0,
},
data: Uint8Array.from({length: 1024 * 1024 * 10}, (v, k) => k)
};

rclnodejs.init().then(() => {
console.log(
`The publisher will publish a UInt8MultiArray topic(contains a size of 10MB array) ${times} times every 100ms.`);
console.log(`Begin at ${new Date().toString()}.`);

let node = rclnodejs.createNode('stress_publisher_rclnodejs');
const publisher = node.createPublisher('std_msgs/msg/UInt8MultiArray', 'stress_topic');
let sentTimes = 0;
let totalTimes = parseInt(times, 10);

let timer = setInterval(() => {
if (sentTimes++ > totalTimes) {
clearInterval(timer);
rclnodejs.shutdown();
console.log(`End at ${new Date().toString()}`);
} else {
publisher.publish(message);
}}, 100);
rclnodejs.spin(node);
}).catch((err) => {
console.log(err);
});
rl.question('Please enter the period of publishing a topic in millisecond ', (ms) => {
const message = {
layout: {
dim: [
{label: 'height', size: 10, stride: 600},
{label: 'width', size: 20, stride: 60},
{label: 'channel', size: 3, stride: 4},
],
data_offset: 0,
},
data: Uint8Array.from({length: 1024 * 1024 * 10}, (v, k) => k)
};

rclnodejs.init().then(() => {
let period = parseInt(ms, 10);

console.log('The publisher will publish a UInt8MultiArray topic(contains a size of 10MB array)' +
`${times} times every ${period}ms.`);
console.log(`Begin at ${new Date().toString()}.`);

rl.close();
let node = rclnodejs.createNode('stress_publisher_rclnodejs');
const publisher = node.createPublisher('std_msgs/msg/UInt8MultiArray', 'stress_topic');
let sentTimes = 0;
let totalTimes = parseInt(times, 10);

let timer = setInterval(() => {
if (sentTimes++ > totalTimes) {
clearInterval(timer);
rclnodejs.shutdown();
console.log(`End at ${new Date().toString()}`);
} else {
publisher.publish(message);
}}, period);
rclnodejs.spin(node);
}).catch((err) => {
console.log(err);
});

rl.close();
});
});
11 changes: 7 additions & 4 deletions benchmark/rclpy/publisher-endurance-test.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,11 @@ def main():
rclpy.init()

times = input('How many times do you want to run? ')
print('The publisher will publish a JointState topic % times every 100ms.' % times)
print('Begin at ' + str(datetime.now())
ms = input('Please enter the period of publishing a topic in millisecond ')
period = int(ms) / 100
print('The publisher will publish a JointState topic %s times every %sms.' % (times, ms))
print('Begin at ' + str(datetime.now()))

node = rclpy.create_node('endurance_publisher_rclpy')
publisher = node.create_publisher(JointState, 'endurance_topic')
time = Time()
Expand Down Expand Up @@ -56,10 +59,10 @@ def publish_topic():
else:
publisher.publish(msg)
sentTimes += 1
timer = threading.Timer(0.1, publish_topic)
timer = threading.Timer(period, publish_topic)
timer.start()

timer = threading.Timer(0.1, publish_topic)
timer = threading.Timer(period, publish_topic)
timer.start()

if __name__ == '__main__':
Expand Down
8 changes: 5 additions & 3 deletions benchmark/rclpy/publisher-stress-test.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,9 @@ def main():
multiArray.data = [x & 0xff for x in range(1024 * 1024 * 10)]

times = input('How many times do you want to run? ')
print('The publisher will publish a UInt8MultiArray topic(contains a size of 10MB array) %s times every 100ms.' % times)
ms = input('Please enter the period of publishing a topic in millisecond ')
period = int(ms) / 100
print('The publisher will publish a UInt8MultiArray topic(contains a size of 10MB array) %s times every %sms.' % (times, ms))
print('Begin at ' + str(datetime.now()))
node = rclpy.create_node('stress_publisher_rclpy')
publisher = node.create_publisher(UInt8MultiArray, 'stress_topic')
Expand All @@ -66,10 +68,10 @@ def publish_topic():
else:
publisher.publish(multiArray)
sentTimes += 1
timer = threading.Timer(0.1, publish_topic)
timer = threading.Timer(period, publish_topic)
timer.start()

timer = threading.Timer(0.1, publish_topic)
timer = threading.Timer(period, publish_topic)
timer.start()

if __name__ == '__main__':
Expand Down

0 comments on commit 4943d66

Please sign in to comment.