53 boost::mutex::scoped_lock lock(
lock_);
58 M_options::const_iterator it =
options_.find(key);
67 boost::mutex::scoped_lock lock(
lock_);
83 it->second.setOptions(options_delta, fields);
94 M_options::iterator it =
options_.find(key);
118 boost::mutex* m1 = &
lock_;
119 boost::mutex* m2 = &other.
lock_;
122 boost::mutex::scoped_lock lock1(*m1);
123 boost::mutex::scoped_lock lock2(*m2);
126 for (M_options::const_iterator it = other.
options_.begin(); it != other.
options_.end(); ++it)
135 const std::string& group,
const std::string& tip,
136 const geometry_msgs::Pose& pose)
const bool setStateFromIK(robot_state::RobotState &state, const std::string &key, const std::string &group, const std::string &tip, const geometry_msgs::Pose &pose) const
KinematicOptionsMap()
Constructor - set all options to reasonable default values.
KinematicOptions defaults_
static const std::string DEFAULT
When used as key this means the default value.
KinematicOptions getOptions(const std::string &key) const
void setOptions(const KinematicOptions &source, OptionBitmask fields=ALL)
void merge(const KinematicOptionsMap &other)
void setOptions(const std::string &key, const KinematicOptions &options, KinematicOptions::OptionBitmask fields=KinematicOptions::ALL)
static const std::string ALL
When used as key this means set ALL keys (including default)
bool setStateFromIK(robot_state::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::Pose &pose) const