37 #ifndef MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_MAP_ 38 #define MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_MAP_ 41 #include <boost/thread.hpp> 42 #include <boost/function.hpp> 58 static const std::string
ALL;
67 bool setStateFromIK(robot_state::RobotState& state,
const std::string& key,
const std::string& group,
68 const std::string& tip,
const geometry_msgs::Pose& pose)
const;
99 typedef std::map<std::string, KinematicOptions>
M_options;
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 merge(const KinematicOptionsMap &other)
void setOptions(const std::string &key, const KinematicOptions &options, KinematicOptions::OptionBitmask fields=KinematicOptions::ALL)
std::map< std::string, KinematicOptions > M_options
static const std::string ALL
When used as key this means set ALL keys (including default)