Go to the documentation of this file.
37 #include <gtest/gtest.h>
39 #include <actionlib/TestAction.h>
44 TEST(SimpleClientCancelCrash, uninitialized_crash) {
46 Client client(
"test_client",
true);
51 ROS_INFO_NAMED(
"actionlib",
"Successfully done with test. Exiting");
54 int main(
int argc,
char ** argv)
56 testing::InitGoogleTest(&argc, argv);
58 ros::init(argc, argv,
"test_cpp_simple_client_cancel_crash");
60 return RUN_ALL_TESTS();
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TEST(SimpleClientCancelCrash, uninitialized_crash)
actionlib::SimpleActionClient< actionlib::TestAction > Client
int main(int argc, char **argv)
A Simple client implementation of the ActionInterface which supports only one goal at a time.
#define ROS_INFO_NAMED(name,...)
void cancelGoal()
Cancel the goal that we are currently pursuing.
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55