39 bool isSimilar(std::vector<std::string> lhs, std::vector<std::string> rhs)
43 if (lhs.size() != rhs.size())
49 std::sort(lhs.begin(), lhs.end());
50 std::sort(rhs.begin(), rhs.end());
57 bool isSame(
const std::vector<std::string> & lhs,
const std::vector<std::string> & rhs)
61 if (lhs.size() != rhs.size())
67 rtn = std::equal(lhs.begin(), lhs.end(), rhs.begin());
73 std::vector<std::string> &joint_names)
75 typedef std::vector<urdf::JointSharedPtr > joint_list;
76 typedef std::vector<urdf::LinkSharedPtr > link_list;
77 std::string found_joint, found_link;
80 const joint_list &joints = link->child_joints;
81 ROS_DEBUG(
"Found %lu child joints:", joints.size());
82 for (joint_list::const_iterator it=joints.begin(); it!=joints.end(); ++it)
85 if (ignore_fixed && (*it)->type == urdf::Joint::FIXED)
88 if (found_joint.empty())
90 found_joint = (*it)->name;
91 joint_names.push_back(found_joint);
95 ROS_WARN_STREAM(
"Unable to find chain in URDF. Branching joints: " << found_joint <<
" and " << (*it)->name);
101 const link_list &links = link->child_links;
102 std::vector<std::string> sub_joints;
103 ROS_DEBUG(
"Found %lu child links:", links.size());
104 for (link_list::const_iterator it=links.begin(); it!=links.end(); ++it)
110 if (sub_joints.empty())
113 if (found_link.empty())
115 found_link = (*it)->name;
116 joint_names.insert(joint_names.end(), sub_joints.begin(), sub_joints.end());
120 ROS_WARN_STREAM(
"Unable to find chain in URDF. Branching links: " << found_link <<
" and " << (*it)->name);
bool findChainJointNames(const urdf::LinkConstSharedPtr &link, bool ignore_fixed, std::vector< std::string > &joint_names)
bool isSame(const std::vector< std::string > &lhs, const std::vector< std::string > &rhs)
Checks to see if sets are the same(same members, same order) Wraps std::equal method.
bool isSimilar(std::vector< std::string > lhs, std::vector< std::string > rhs)
Checks to see if sets are similar(same members, any order) NOTE: Vectors are passed by copy because t...
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)