35 #include <gtest/gtest.h> 75 TEST(TestRobotStatePubSubclass, robot_state_pub_subclass)
81 ROS_ERROR(
"Failed to extract kdl tree from xml robot description");
87 for(std::map< std::string, urdf::JointSharedPtr >::iterator i = model.joints_.begin(); i != model.joints_.end(); i++){
89 mimic.insert(make_pair(i->first, i->second->mimic));
95 EXPECT_EQ(model.name_, state_pub.
getModel().name_);
96 EXPECT_EQ(model.root_link_, state_pub.
getModel().root_link_);
99 EXPECT_TRUE(state_listener.usingTfStatic());
102 int main(
int argc,
char** argv)
105 testing::InitGoogleTest(&argc, argv);
107 int res = RUN_ALL_TESTS();
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool usingTfStatic() const
const urdf::Model & getModel() const
AccessibleJointStateListener(const KDL::Tree &tree, const MimicMap &m, const urdf::Model &model)
TEST(TestRobotStatePubSubclass, robot_state_pub_subclass)
JointStateListener(const KDL::Tree &tree, const MimicMap &m, const urdf::Model &model=urdf::Model())
URDF_EXPORT bool initParam(const std::string ¶m)
int main(int argc, char **argv)
std::map< std::string, urdf::JointMimicSharedPtr > MimicMap
AccessibleRobotStatePublisher(const KDL::Tree &tree, const urdf::Model &model)