duration_recorder_test.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License").
5  * You may not use this file except in compliance with the License.
6  * A copy of the License is located at
7  *
8  * http://aws.amazon.com/apache2.0
9  *
10  * or in the "license" file accompanying this file. This file is distributed
11  * on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either
12  * express or implied. See the License for the specific language governing
13  * permissions and limitations under the License.
14  */
15 
16 #include <gtest/gtest.h>
17 #include <fstream>
20 #include <ros/ros.h>
21 #include <ros/console.h>
22 
23 #include <recorder_msgs/DurationRecorderAction.h>
26 
27 using namespace Aws::Rosbag;
28 
29 
31 
32 class DurationRecorderNodeTest : public ::testing::Test
33 {
34 protected:
35  void SetUp() override
36  {
37  ros::NodeHandle nh("~");
38  action_client_ = std::make_shared<DurationRecorderActionClient>(nh, "RosbagDurationRecord");
39  duration_recorder_ = std::make_shared<Aws::Rosbag::DurationRecorder>();
40  }
41 
42  std::shared_ptr<DurationRecorderActionClient> action_client_;
43  std::shared_ptr<Aws::Rosbag::DurationRecorder> duration_recorder_;
44 };
45 
46 TEST_F(DurationRecorderNodeTest, TestActionReceivedbyActionServer)
47 {
48  ros::AsyncSpinner executor(0);
49  executor.start();
50  bool message_received = false;
51  // Wait 10 seconds for server to start
52  ASSERT_TRUE(action_client_->waitForActionServerToStart(ros::Duration(10, 0)));
53  auto transition_call_back = [&message_received](DurationRecorderActionClient::GoalHandle goal_handle){
54  EXPECT_EQ(goal_handle.getTerminalState().state_, actionlib::TerminalState::StateEnum::REJECTED);
55  message_received = true;
56  };
57  recorder_msgs::DurationRecorderGoal goal;
58  auto gh = action_client_->sendGoal(goal, transition_call_back);
59  ros::Duration(1,0).sleep();
60  ASSERT_TRUE(message_received);
61  gh.cancel();
62  executor.stop();
63 }
64 
65 int main(int argc, char** argv)
66 {
67  ::testing::InitGoogleTest(&argc, argv);
68  ros::init(argc, argv, "test_duration_recorder_node");
69  auto result = RUN_ALL_TESTS();
70  ros::shutdown();
71  return result;
72 }
int main(int argc, char **argv)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::shared_ptr< DurationRecorderActionClient > action_client_
ROSCPP_DECL void shutdown()
TEST_F(DurationRecorderNodeTest, TestActionReceivedbyActionServer)
std::shared_ptr< Aws::Rosbag::DurationRecorder > duration_recorder_


rosbag_cloud_recorders
Author(s): AWS RoboMaker
autogenerated on Tue Jun 1 2021 02:51:27