#include <kinematic_options_map.h>
Public Member Functions | |
KinematicOptions | getOptions (const std::string &key) const |
KinematicOptionsMap () | |
Constructor - set all options to reasonable default values. More... | |
void | merge (const KinematicOptionsMap &other) |
void | setOptions (const std::string &key, const KinematicOptions &options, KinematicOptions::OptionBitmask fields=KinematicOptions::ALL) |
bool | setStateFromIK (robot_state::RobotState &state, const std::string &key, const std::string &group, const std::string &tip, const geometry_msgs::Pose &pose) const |
Static Public Attributes | |
static const std::string | ALL = "" |
When used as key this means set ALL keys (including default) More... | |
static const std::string | DEFAULT = "" |
When used as key this means the default value. More... | |
Private Types | |
typedef std::map< std::string, KinematicOptions > | M_options |
Private Attributes | |
KinematicOptions | defaults_ |
boost::mutex | lock_ |
M_options | options_ |
Definition at line 48 of file kinematic_options_map.h.
|
private |
Definition at line 99 of file kinematic_options_map.h.
robot_interaction::KinematicOptionsMap::KinematicOptionsMap | ( | ) |
Constructor - set all options to reasonable default values.
Definition at line 45 of file kinematic_options_map.cpp.
robot_interaction::KinematicOptions robot_interaction::KinematicOptionsMap::getOptions | ( | const std::string & | key | ) | const |
Get the options to use for a particular key. To get the default values pass key = KinematicOptionsMap::DEFAULT
Definition at line 51 of file kinematic_options_map.cpp.
void robot_interaction::KinematicOptionsMap::merge | ( | const KinematicOptionsMap & | other | ) |
Merge all options from other into this. Values in other (including defaults_) take precedence over values in this.
Definition at line 111 of file kinematic_options_map.cpp.
void robot_interaction::KinematicOptionsMap::setOptions | ( | const std::string & | key, |
const KinematicOptions & | options, | ||
KinematicOptions::OptionBitmask | fields = KinematicOptions::ALL |
||
) |
Set some of the options to be used for a particular key.
key | set the options for this key. To set the default options use key = KinematicOptionsMap::DEFAULT To set ALL options use key = KinematicOptionsMap::ALL |
options | the new value for the options. |
which options to set for the key.
Definition at line 64 of file kinematic_options_map.cpp.
bool robot_interaction::KinematicOptionsMap::setStateFromIK | ( | robot_state::RobotState & | state, |
const std::string & | key, | ||
const std::string & | group, | ||
const std::string & | tip, | ||
const geometry_msgs::Pose & | pose | ||
) | const |
Set state using inverse kinematics.
state | the state to set |
key | used to lookup the options to use |
group | name of group whose joints can move |
tip | link that will be posed |
pose | desired pose of tip link |
result | true if IK succeeded. |
Definition at line 134 of file kinematic_options_map.cpp.
|
static |
When used as key this means set ALL keys (including default)
Definition at line 58 of file kinematic_options_map.h.
|
static |
When used as key this means the default value.
Definition at line 55 of file kinematic_options_map.h.
|
private |
Definition at line 97 of file kinematic_options_map.h.
|
mutableprivate |
Definition at line 93 of file kinematic_options_map.h.
|
private |
Definition at line 104 of file kinematic_options_map.h.