#include <kinematic_options.h>
| Public Types | |
| enum | OptionBitmask { TIMEOUT = 0x00000001, MAX_ATTEMPTS = 0x00000002, STATE_VALIDITY_CALLBACK = 0x00000004, LOCK_REDUNDANT_JOINTS = 0x00000008, RETURN_APPROXIMATE_SOLUTION = 0x00000010, DISCRETIZATION_METHOD = 0x00000020, ALL_QUERY_OPTIONS = LOCK_REDUNDANT_JOINTS | RETURN_APPROXIMATE_SOLUTION | DISCRETIZATION_METHOD, ALL = 0x7fffffff } | 
| Public Member Functions | |
| KinematicOptions () | |
| Constructor - set all options to reasonable default values. | |
| void | setOptions (const KinematicOptions &source, OptionBitmask fields=ALL) | 
| bool | setStateFromIK (robot_state::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::Pose &pose) const | 
| Public Attributes | |
| unsigned int | max_attempts_ | 
| how many attempts before we give up. | |
| kinematics::KinematicsQueryOptions | options_ | 
| other options | |
| robot_state::GroupStateValidityCallbackFn | state_validity_callback_ | 
| This is called to determine if the state is valid. | |
| double | timeout_seconds_ | 
| max time an IK attempt can take before we give up. | |
Definition at line 49 of file kinematic_options.h.
Bits corresponding to each member. NOTE: when adding fields to this structure also add the field to this enum and to the setOptions() method.
| TIMEOUT | |
| MAX_ATTEMPTS | |
| STATE_VALIDITY_CALLBACK | |
| LOCK_REDUNDANT_JOINTS | |
| RETURN_APPROXIMATE_SOLUTION | |
| DISCRETIZATION_METHOD | |
| ALL_QUERY_OPTIONS | |
| ALL | 
Definition at line 57 of file kinematic_options.h.
Constructor - set all options to reasonable default values.
Definition at line 41 of file kinematic_options.cpp.
| void robot_interaction::KinematicOptions::setOptions | ( | const KinematicOptions & | source, | 
| OptionBitmask | fields = ALL | ||
| ) | 
Copy a subset of source to this. For each bit set in fields the corresponding member is copied from source to this.
Definition at line 63 of file kinematic_options.cpp.
| bool robot_interaction::KinematicOptions::setStateFromIK | ( | robot_state::RobotState & | state, | 
| const std::string & | group, | ||
| const std::string & | tip, | ||
| const geometry_msgs::Pose & | pose | ||
| ) | const | 
Set state using inverse kinematics
| state | the state to set | 
| 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 49 of file kinematic_options.cpp.
| unsigned int robot_interaction::KinematicOptions::max_attempts_ | 
how many attempts before we give up.
Definition at line 87 of file kinematic_options.h.
other options
Definition at line 93 of file kinematic_options.h.
| robot_state::GroupStateValidityCallbackFn robot_interaction::KinematicOptions::state_validity_callback_ | 
This is called to determine if the state is valid.
Definition at line 90 of file kinematic_options.h.
max time an IK attempt can take before we give up.
Definition at line 84 of file kinematic_options.h.