Public Member Functions | Static Public Attributes | Private Types | Private Attributes
robot_interaction::KinematicOptionsMap Class Reference

#include <kinematic_options_map.h>

List of all members.

Public Member Functions

KinematicOptions getOptions (const std::string &key) const
 KinematicOptionsMap ()
 Constructor - set all options to reasonable default values.
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)
static const std::string DEFAULT = ""
 When used as key this means the default value.

Private Types

typedef std::map< std::string,
KinematicOptions
M_options

Private Attributes

KinematicOptions defaults_
boost::mutex lock_
M_options options_

Detailed Description

Definition at line 48 of file kinematic_options_map.h.


Member Typedef Documentation

typedef std::map<std::string, KinematicOptions> robot_interaction::KinematicOptionsMap::M_options [private]

Definition at line 99 of file kinematic_options_map.h.


Constructor & Destructor Documentation

Constructor - set all options to reasonable default values.

Definition at line 45 of file kinematic_options_map.cpp.


Member Function Documentation

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.

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.

Set some of the options to be used for a particular key.

Parameters:
keyset the options for this key. To set the default options use key = KinematicOptionsMap::DEFAULT To set ALL options use key = KinematicOptionsMap::ALL
optionsthe 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.

Parameters:
statethe state to set
keyused to lookup the options to use
groupname of group whose joints can move
tiplink that will be posed
posedesired pose of tip link
resulttrue if IK succeeded.

Definition at line 134 of file kinematic_options_map.cpp.


Member Data Documentation

const std::string robot_interaction::KinematicOptionsMap::ALL = "" [static]

When used as key this means set ALL keys (including default)

Definition at line 58 of file kinematic_options_map.h.

const std::string robot_interaction::KinematicOptionsMap::DEFAULT = "" [static]

When used as key this means the default value.

Definition at line 55 of file kinematic_options_map.h.

Definition at line 97 of file kinematic_options_map.h.

boost::mutex robot_interaction::KinematicOptionsMap::lock_ [mutable, private]

Definition at line 93 of file kinematic_options_map.h.

Definition at line 104 of file kinematic_options_map.h.


The documentation for this class was generated from the following files:


robot_interaction
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:44