Skip to content

Commit

Permalink
[foxy backport] Add ostream test for FutureReturnCode (#1327) (#1393)
Browse files Browse the repository at this point in the history
* Remove deprecated executor::FutureReturnCode APIs. (#1327)

While we are here, add in another test for the stream operator for future_return_code.cpp

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Revert removing deprecated API

Signed-off-by: Stephen Brawner <brawner@gmail.com>

Co-authored-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
brawner and clalancette authored Oct 9, 2020
1 parent bad0460 commit 9aed2ec
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion rclcpp/test/rclcpp/test_future_return_code.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
// Copyright 2020 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -14,6 +14,7 @@

#include <gtest/gtest.h>

#include <sstream>
#include <string>

#include "rclcpp/future_return_code.hpp"
Expand All @@ -32,3 +33,10 @@ TEST(TestFutureReturnCode, to_string) {
EXPECT_EQ(
"Unknown enum value (100)", rclcpp::to_string(rclcpp::FutureReturnCode(100)));
}

TEST(FutureReturnCode, ostream) {
std::ostringstream ostream;

ostream << rclcpp::FutureReturnCode::SUCCESS;
ASSERT_EQ("SUCCESS (0)", ostream.str());
}

0 comments on commit 9aed2ec

Please sign in to comment.