51 std::scoped_lock lock(lock_);
56 M_options::const_iterator it = options_.find(key);
57 if (it == options_.end())
65 std::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 std::mutex* m1 = &lock_;
117 std::mutex* m2 = &other.lock_;
120 std::scoped_lock lock1(*m1);
121 std::scoped_lock lock2(*m2);
123 defaults_ = other.defaults_;
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::msg::Pose& pose)
const
138 return options.setStateFromIK(state, group, tip, pose);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
KinematicOptionsMap()
Constructor - set all options to reasonable default values.
void setOptions(const std::string &key, const KinematicOptions &options, KinematicOptions::OptionBitmask fields=KinematicOptions::ALL)
bool setStateFromIK(moveit::core::RobotState &state, const std::string &key, const std::string &group, const std::string &tip, const geometry_msgs::msg::Pose &pose) const
static const std::string DEFAULT
When used as key this means the default value.
static const std::string ALL
When used as key this means set ALL keys (including default)
void merge(const KinematicOptionsMap &other)
KinematicOptions getOptions(const std::string &key) const
void setOptions(const KinematicOptions &source, OptionBitmask fields=ALL)