Skip to content

Commit

Permalink
Remove deprecated executor::FutureReturnCode APIs. (#1327)
Browse files Browse the repository at this point in the history
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>
  • Loading branch information
clalancette committed Sep 25, 2020
1 parent acf6971 commit 8c1d829
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 15 deletions.
14 changes: 0 additions & 14 deletions rclcpp/include/rclcpp/future_return_code.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,20 +42,6 @@ RCLCPP_PUBLIC
std::string
to_string(const FutureReturnCode & future_return_code);

namespace executor
{

using FutureReturnCode [[deprecated("use rclcpp::FutureReturnCode instead")]] = FutureReturnCode;

[[deprecated("use rclcpp::to_string(const rclcpp::FutureReturnCode &) instead")]]
inline
std::string
to_string(const rclcpp::FutureReturnCode & future_return_code)
{
return rclcpp::to_string(future_return_code);
}

} // namespace executor
} // namespace rclcpp

#endif // RCLCPP__FUTURE_RETURN_CODE_HPP_
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 8c1d829

Please sign in to comment.