Public Member Functions | Static Public Attributes | Private Types | Private Attributes | List of all members
robot_interaction::KinematicOptionsMap Class Reference

#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 (moveit::core::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, KinematicOptionsM_options
 

Private Attributes

KinematicOptions defaults_
 
boost::mutex lock_
 
M_options options_
 

Detailed Description

Definition at line 79 of file kinematic_options_map.h.

Member Typedef Documentation

◆ M_options

Definition at line 162 of file kinematic_options_map.h.

Constructor & Destructor Documentation

◆ KinematicOptionsMap()

robot_interaction::KinematicOptionsMap::KinematicOptionsMap ( )

Constructor - set all options to reasonable default values.

Definition at line 43 of file kinematic_options_map.cpp.

Member Function Documentation

◆ getOptions()

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 49 of file kinematic_options_map.cpp.

◆ merge()

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 109 of file kinematic_options_map.cpp.

◆ setOptions()

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.

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.

@fields which options to set for the key.

Definition at line 62 of file kinematic_options_map.cpp.

◆ setStateFromIK()

bool robot_interaction::KinematicOptionsMap::setStateFromIK ( moveit::core::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 132 of file kinematic_options_map.cpp.

Member Data Documentation

◆ ALL

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

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

Definition at line 121 of file kinematic_options_map.h.

◆ DEFAULT

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

When used as key this means the default value.

Definition at line 118 of file kinematic_options_map.h.

◆ defaults_

KinematicOptions robot_interaction::KinematicOptionsMap::defaults_
private

Definition at line 160 of file kinematic_options_map.h.

◆ lock_

boost::mutex robot_interaction::KinematicOptionsMap::lock_
mutableprivate

Definition at line 156 of file kinematic_options_map.h.

◆ options_

M_options robot_interaction::KinematicOptionsMap::options_
private

Definition at line 167 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 Sat Mar 15 2025 02:26:54