16 #include <gtest/gtest.h> 23 #include <recorder_msgs/DurationRecorderAction.h> 38 action_client_ = std::make_shared<DurationRecorderActionClient>(nh,
"RosbagDurationRecord");
39 duration_recorder_ = std::make_shared<Aws::Rosbag::DurationRecorder>();
50 bool message_received =
false;
52 ASSERT_TRUE(action_client_->waitForActionServerToStart(
ros::Duration(10, 0)));
54 EXPECT_EQ(goal_handle.getTerminalState().state_, actionlib::TerminalState::StateEnum::REJECTED);
55 message_received =
true;
57 recorder_msgs::DurationRecorderGoal goal;
58 auto gh = action_client_->sendGoal(goal, transition_call_back);
60 ASSERT_TRUE(message_received);
65 int main(
int argc,
char** argv)
67 ::testing::InitGoogleTest(&argc, argv);
68 ros::init(argc, argv,
"test_duration_recorder_node");
69 auto result = RUN_ALL_TESTS();
int main(int argc, char **argv)
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_