Struct KinematicOptions
Defined in File kinematic_options.hpp
Struct Documentation
-
struct KinematicOptions
Public Types
-
enum OptionBitmask
Bits corresponding to each member. NOTE: when adding fields to this structure also add the field to this enum and to the setOptions() method.
Values:
-
enumerator TIMEOUT
-
enumerator STATE_VALIDITY_CALLBACK
-
enumerator LOCK_REDUNDANT_JOINTS
-
enumerator RETURN_APPROXIMATE_SOLUTION
-
enumerator DISCRETIZATION_METHOD
-
enumerator ALL_QUERY_OPTIONS
-
enumerator ALL
-
enumerator TIMEOUT
Public Functions
-
KinematicOptions()
Constructor - set all options to reasonable default values.
-
bool setStateFromIK(moveit::core::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::msg::Pose &pose) const
Set state using inverse kinematics
- Parameters:
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.
-
void 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.
-
enum OptionBitmask