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
51 TEST(NeonavigationCompat, CompatMode)
89 std_msgs::Bool::ConstPtr
msg_;
93 void cb(
const std_msgs::Bool::ConstPtr& msg)
97 void cbConst(
const std_msgs::Bool::ConstPtr& msg)
const
102 bool cbSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res)
115 TEST(NeonavigationCompat, Subscribe)
129 pub_new.publish(msg);
135 cls.
pnh_,
"test_old",
140 ASSERT_TRUE(
static_cast<bool>(cls.
msg_));
141 ASSERT_EQ(
false,
static_cast<bool>(cls.
msg_->data));
149 cls.
pnh_,
"test_old",
154 ASSERT_TRUE(
static_cast<bool>(cls.
msg_));
155 ASSERT_EQ(
true,
static_cast<bool>(cls.
msg_->data));
163 cls.
pnh_,
"test_old",
168 ASSERT_TRUE(
static_cast<bool>(cls.
msg_const_));
169 ASSERT_EQ(
false,
static_cast<bool>(cls.
msg_const_->data));
177 cls.
pnh_,
"test_old",
182 ASSERT_TRUE(
static_cast<bool>(cls.
msg_const_));
183 ASSERT_EQ(
true,
static_cast<bool>(cls.
msg_const_->data));
187 TEST(NeonavigationCompat, AdvertiseService)
208 std_srvs::Empty empty;
209 ASSERT_TRUE(cli_old.call(empty.request, empty.response));
220 std_srvs::Empty empty;
221 ASSERT_TRUE(cli_new.
call(empty.request, empty.response));
227 int main(
int argc,
char** argv)
229 testing::InitGoogleTest(&argc, argv);
232 return RUN_ALL_TESTS();
NeonavigationCompatCallbacks()
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void spinOnce()
void cb(const std_msgs::Bool::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) 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(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
Publisher advertise(AdvertiseOptions &ops)
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)
std_msgs::Bool::ConstPtr msg_const_
bool cbSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
TEST(NeonavigationCompat, CompatMode)
const int supported_level
std_msgs::Bool::ConstPtr msg_
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
void cbConst(const std_msgs::Bool::ConstPtr &msg) const