Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/robot_interaction/kinematic_options_map.h>
00038 #include <ros/console.h>
00039 #include <algorithm>
00040
00041
00042 const std::string robot_interaction::KinematicOptionsMap::DEFAULT = "";
00043 const std::string robot_interaction::KinematicOptionsMap::ALL = "";
00044
00045 robot_interaction::KinematicOptionsMap::KinematicOptionsMap()
00046 {
00047 }
00048
00049
00050
00051 robot_interaction::KinematicOptions robot_interaction::KinematicOptionsMap::getOptions(const std::string& key) const
00052 {
00053 boost::mutex::scoped_lock lock(lock_);
00054
00055 if (&key == &DEFAULT)
00056 return defaults_;
00057
00058 M_options::const_iterator it = options_.find(key);
00059 if (it == options_.end())
00060 return defaults_;
00061 return it->second;
00062 }
00063
00064 void robot_interaction::KinematicOptionsMap::setOptions(const std::string& key, const KinematicOptions& options_delta,
00065 KinematicOptions::OptionBitmask fields)
00066 {
00067 boost::mutex::scoped_lock lock(lock_);
00068
00069 if (&key == &ALL)
00070 {
00071 if (fields == KinematicOptions::ALL)
00072 {
00073
00074
00075 defaults_ = options_delta;
00076 options_.clear();
00077 return;
00078 }
00079
00080 defaults_.setOptions(options_delta, fields);
00081 for (M_options::iterator it = options_.begin(); it != options_.end(); ++it)
00082 {
00083 it->second.setOptions(options_delta, fields);
00084 }
00085 return;
00086 }
00087
00088 if (&key == &DEFAULT)
00089 {
00090 defaults_.setOptions(options_delta, fields);
00091 return;
00092 }
00093
00094 M_options::iterator it = options_.find(key);
00095 KinematicOptions* opts;
00096 if (it == options_.end())
00097 {
00098
00099 opts = &options_[key];
00100 *opts = defaults_;
00101 }
00102 else
00103 {
00104 opts = &it->second;
00105 }
00106
00107 opts->setOptions(options_delta, fields);
00108 }
00109
00110
00111 void robot_interaction::KinematicOptionsMap::merge(const KinematicOptionsMap& other)
00112 {
00113 if (&other == this)
00114 return;
00115
00116
00117
00118 boost::mutex* m1 = &lock_;
00119 boost::mutex* m2 = &other.lock_;
00120 if (m2 < m1)
00121 std::swap(m1, m2);
00122 boost::mutex::scoped_lock lock1(*m1);
00123 boost::mutex::scoped_lock lock2(*m2);
00124
00125 defaults_ = other.defaults_;
00126 for (M_options::const_iterator it = other.options_.begin(); it != other.options_.end(); ++it)
00127 {
00128 options_[it->first] = it->second;
00129 }
00130 }
00131
00132
00133
00134 bool robot_interaction::KinematicOptionsMap::setStateFromIK(robot_state::RobotState& state, const std::string& key,
00135 const std::string& group, const std::string& tip,
00136 const geometry_msgs::Pose& pose) const
00137 {
00138
00139 KinematicOptions options = getOptions(key);
00140 return options.setStateFromIK(state, group, tip, pose);
00141 }