51 boost::mutex::scoped_lock lock(lock_);
56 M_options::const_iterator it = options_.find(key);
57 if (it == options_.end())
65 boost::mutex::scoped_lock lock(lock_);
73 defaults_ = options_delta;
79 for (std::pair<const std::string, KinematicOptions>& option : options_)
81 option.second.setOptions(options_delta, fields);
88 defaults_.setOptions(options_delta, fields);
92 M_options::iterator it = options_.find(key);
94 if (it == options_.end())
97 opts = &options_[key];
116 boost::mutex* m1 = &lock_;
117 boost::mutex* m2 = &other.
lock_;
120 boost::mutex::scoped_lock lock1(*m1);
121 boost::mutex::scoped_lock lock2(*m2);
124 for (
const std::pair<const std::string, KinematicOptions>& option : other.
options_)
126 options_[option.first] = option.second;
133 const std::string& group,
const std::string& tip,
134 const geometry_msgs::Pose& pose)
const