Skip to content

Commit

Permalink
Pendulum teleop flakiness reduction (#232)
Browse files Browse the repository at this point in the history
* Sleep before exiting to get msgs out

* Avoid interrupting already exiting pendulum demo

* Use printf

* Subscribe to teleop msg with transient local

Makes test more robust to startup order

* Force flush for output sync
  • Loading branch information
dhood authored Apr 3, 2018
1 parent c3a9436 commit 7284573
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 2 deletions.
6 changes: 5 additions & 1 deletion pendulum_control/src/pendulum_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,8 +197,12 @@ int main(int argc, char * argv[])
pendulum_controller->on_pendulum_setpoint(msg);
};

// Receive the most recently published message from the teleop node publisher.
auto qos_profile_setpoint_sub(qos_profile);
qos_profile_setpoint_sub.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;

auto setpoint_sub = controller_node->create_subscription<pendulum_msgs::msg::JointCommand>(
"pendulum_setpoint", controller_command_callback, qos_profile, nullptr, false,
"pendulum_setpoint", controller_command_callback, qos_profile_setpoint_sub, nullptr, false,
setpoint_msg_strategy);

// Initialize the logger publisher.
Expand Down
4 changes: 3 additions & 1 deletion pendulum_control/src/pendulum_teleop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,9 @@ int main(int argc, char * argv[])
rclcpp::sleep_for(500ms);
pub->publish(msg);
rclcpp::spin_some(teleop_node);
std::cout << "Teleop node exited." << std::endl;
printf("Teleop message published.\n");
rclcpp::sleep_for(1s);
printf("Teleop node exited.\n");

rclcpp::shutdown();
}
4 changes: 4 additions & 0 deletions pendulum_control/test/test_pendulum_demo.py.in
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@ def setup():
os.environ['OSPL_VERBOSITY'] = '8' # 8 = OS_NONE
# bare minimum formatting for console output matching
os.environ['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '{message}'
# force flush of the stdout buffer.
# this ensures a correct sync of prints from processes executed within the launch file.
os.environ['RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED'] = '1'


def test_executable():
Expand Down Expand Up @@ -53,6 +56,7 @@ def test_executable():

pendulum_demo_handler = create_handler(
pendulum_demo_name, launch_descriptor, pendulum_demo_output_file,
exit_on_match=False, # the process will exit automatically after a set number of iterations
filtered_prefixes=filtered_prefixes,
filtered_rmw_implementation=rmw_implementation)
assert pendulum_demo_handler, \
Expand Down
3 changes: 3 additions & 0 deletions pendulum_control/test/test_pendulum_teleop.py.in
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@ def setup():
os.environ['OSPL_VERBOSITY'] = '8' # 8 = OS_NONE
# bare minimum formatting for console output matching
os.environ['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '{message}'
# force flush of the stdout buffer.
# this ensures a correct sync of prints from processes executed within the launch file.
os.environ['RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED'] = '1'


def test_executable():
Expand Down

0 comments on commit 7284573

Please sign in to comment.