Go to the documentation of this file.
33 #include <std_msgs/Bool.h>
34 #include <std_srvs/Empty.h>
36 #include <gtest/gtest.h>
38 #define UNDEF_COMPATIBILITY_LEVEL
48 TEST(Mcl3DlCompat, ParamRename)
57 mcl_3dl_compat::paramRename<double>(nh,
"param1_new",
"param1");
58 mcl_3dl_compat::paramRename<double>(nh,
"param2_new",
"param2");
60 ASSERT_TRUE(nh.
hasParam(
"param1_new"));
61 ASSERT_TRUE(nh.
hasParam(
"param2_new"));
62 ASSERT_TRUE(nh.
hasParam(
"param3_new"));
72 ASSERT_EQ(param1, 1.0);
74 ASSERT_EQ(param2, 3.0);
76 ASSERT_EQ(param3, 4.0);
79 TEST(Mcl3DlCompat, CompatMode)
121 void cb(
const std_msgs::Bool::ConstPtr& msg)
125 void cbConst(
const std_msgs::Bool::ConstPtr& msg)
const
130 bool cbSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res)
157 pub_new.publish(
msg);
163 cls.
pnh_,
"test_old",
168 ASSERT_TRUE(
static_cast<bool>(cls.
msg_));
169 ASSERT_EQ(
false,
static_cast<bool>(cls.
msg_->data));
177 cls.
pnh_,
"test_old",
182 ASSERT_TRUE(
static_cast<bool>(cls.
msg_));
183 ASSERT_EQ(
true,
static_cast<bool>(cls.
msg_->data));
191 cls.
pnh_,
"test_old",
196 ASSERT_TRUE(
static_cast<bool>(cls.
msg_const_));
197 ASSERT_EQ(
false,
static_cast<bool>(cls.
msg_const_->data));
205 cls.
pnh_,
"test_old",
210 ASSERT_TRUE(
static_cast<bool>(cls.
msg_const_));
211 ASSERT_EQ(
true,
static_cast<bool>(cls.
msg_const_->data));
215 TEST(Mcl3DlCompat, AdvertiseService)
236 std_srvs::Empty empty;
237 ASSERT_TRUE(cli_old.call(empty.request, empty.response));
248 std_srvs::Empty empty;
249 ASSERT_TRUE(cli_new.
call(empty.request, empty.response));
255 int main(
int argc,
char** argv)
257 testing::InitGoogleTest(&argc, argv);
258 ros::init(argc, argv,
"test_mcl_3dl_compat");
260 return RUN_ALL_TESTS();
void cb(const std_msgs::Bool::ConstPtr &msg)
void setParam(const std::string &key, bool b) const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints())
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void spinOnce()
void publish(const boost::shared_ptr< M > &message) const
bool cbSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Publisher advertise(AdvertiseOptions &ops)
void cbConst(const std_msgs::Bool::ConstPtr &msg) const
TEST(Mcl3DlCompat, ParamRename)
std_msgs::Bool::ConstPtr msg_const_
ros::ServiceServer advertiseService(ros::NodeHandle &nh_new, const std::string &service_new, ros::NodeHandle &nh_old, const std::string &service_old, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int main(int argc, char **argv)
bool hasParam(const std::string &key) const
std_msgs::Bool::ConstPtr msg_
const int supported_level
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04