|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <kinematic_options.hpp>

Public Types | |
| enum | OptionBitmask { TIMEOUT = 0x00000001 , STATE_VALIDITY_CALLBACK = 0x00000002 , LOCK_REDUNDANT_JOINTS = 0x00000004 , RETURN_APPROXIMATE_SOLUTION = 0x00000008 , DISCRETIZATION_METHOD = 0x00000010 , 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. | |
| bool | setStateFromIK (moveit::core::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::msg::Pose &pose) const |
| void | setOptions (const KinematicOptions &source, OptionBitmask fields=ALL) |
Public Attributes | |
| double | timeout_seconds_ |
| max time an IK attempt can take before we give up. | |
| moveit::core::GroupStateValidityCallbackFn | state_validity_callback_ |
| This is called to determine if the state is valid. | |
| kinematics::KinematicsQueryOptions | options_ |
| other options | |
Definition at line 48 of file kinematic_options.hpp.
Bits corresponding to each member. NOTE: when adding fields to this structure also add the field to this enum and to the setOptions() method.
| Enumerator | |
|---|---|
| TIMEOUT | |
| STATE_VALIDITY_CALLBACK | |
| LOCK_REDUNDANT_JOINTS | |
| RETURN_APPROXIMATE_SOLUTION | |
| DISCRETIZATION_METHOD | |
| ALL_QUERY_OPTIONS | |
| ALL | |
Definition at line 56 of file kinematic_options.hpp.
| robot_interaction::KinematicOptions::KinematicOptions | ( | ) |
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 65 of file kinematic_options.cpp.

| bool robot_interaction::KinematicOptions::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
| 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 47 of file kinematic_options.cpp.

| kinematics::KinematicsQueryOptions robot_interaction::KinematicOptions::options_ |
other options
Definition at line 88 of file kinematic_options.hpp.
| moveit::core::GroupStateValidityCallbackFn robot_interaction::KinematicOptions::state_validity_callback_ |
This is called to determine if the state is valid.
Definition at line 85 of file kinematic_options.hpp.
| double robot_interaction::KinematicOptions::timeout_seconds_ |
max time an IK attempt can take before we give up.
Definition at line 82 of file kinematic_options.hpp.