#include <kinematic_options_map.h>
|
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...
|
|
Definition at line 79 of file kinematic_options_map.h.
◆ M_options
◆ KinematicOptionsMap()
robot_interaction::KinematicOptionsMap::KinematicOptionsMap |
( |
| ) |
|
◆ getOptions()
◆ merge()
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()
Set some of the options to be used for a particular key.
- Parameters
-
@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
-
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 132 of file kinematic_options_map.cpp.
◆ ALL
const std::string robot_interaction::KinematicOptionsMap::ALL = "" |
|
static |
◆ DEFAULT
const std::string robot_interaction::KinematicOptionsMap::DEFAULT = "" |
|
static |
◆ defaults_
◆ lock_
boost::mutex robot_interaction::KinematicOptionsMap::lock_ |
|
mutableprivate |
◆ options_
M_options robot_interaction::KinematicOptionsMap::options_ |
|
private |
The documentation for this class was generated from the following files: