Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <gtest/gtest.h>
00031
00032 #include <ros/ros.h>
00033
00034 #include <test_roscpp/TestEmpty.h>
00035
00036 #define ASSERT_THROWS(expr) \
00037 try \
00038 { \
00039 expr; \
00040 FAIL(); \
00041 } \
00042 catch (std::exception& e) \
00043 { \
00044 ROS_INFO("Caught exception: %s", e.what());\
00045 }
00046
00047 void callback(const test_roscpp::TestEmptyConstPtr&)
00048 {
00049
00050 }
00051
00052 TEST(ParameterValidation, subscribeEmptyMD5Sum)
00053 {
00054 ros::NodeHandle nh;
00055 ros::SubscribeOptions ops;
00056 ops.init<test_roscpp::TestEmpty>("blah", 0, callback);
00057 ops.md5sum.clear();
00058 ASSERT_THROWS(nh.subscribe(ops));
00059 }
00060
00061 TEST(ParameterValidation, subscribeEmptyDataType)
00062 {
00063 ros::NodeHandle nh;
00064 ros::SubscribeOptions ops;
00065 ops.init<test_roscpp::TestEmpty>("blah", 0, callback);
00066 ops.datatype.clear();
00067 ASSERT_THROWS(nh.subscribe(ops));
00068 }
00069
00070 TEST(ParameterValidation, subscribeNoCallback)
00071 {
00072 ros::NodeHandle nh;
00073 ros::SubscribeOptions ops("blah", 0, "blah", "blah");
00074 ASSERT_THROWS(nh.subscribe(ops));
00075 }
00076
00077 TEST(ParameterValidation, advertiseEmptyMD5Sum)
00078 {
00079 ros::NodeHandle nh;
00080 ros::AdvertiseOptions ops("blah", 0, "", "blah", "blah");
00081 ASSERT_THROWS(nh.advertise(ops));
00082 }
00083
00084 TEST(ParameterValidation, advertiseEmptyDataType)
00085 {
00086 ros::NodeHandle nh;
00087 ros::AdvertiseOptions ops("blah", 0, "blah", "", "blah");
00088 ASSERT_THROWS(nh.advertise(ops));
00089 }
00090
00091 TEST(ParameterValidation, advertiseStarMD5Sum)
00092 {
00093 ros::NodeHandle nh;
00094 ros::AdvertiseOptions ops("blah", 0, "*", "blah", "blah");
00095 ASSERT_THROWS(nh.advertise(ops));
00096 }
00097
00098 TEST(ParameterValidation, advertiseStarDataType)
00099 {
00100 ros::NodeHandle nh;
00101 ros::AdvertiseOptions ops("blah", 0, "blah", "*", "blah");
00102 ASSERT_THROWS(nh.advertise(ops));
00103 }
00104
00105 int main(int argc, char** argv)
00106 {
00107 testing::InitGoogleTest(&argc, argv);
00108 ros::init(argc, argv, "parameter_validation");
00109
00110 ros::NodeHandle nh;
00111
00112 return RUN_ALL_TESTS();
00113 }