37 #ifndef MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_ 38 #define MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_ 75 bool setStateFromIK(robot_state::RobotState& state,
const std::string& group,
const std::string& tip,
76 const geometry_msgs::Pose& pose)
const;
robot_state::GroupStateValidityCallbackFn state_validity_callback_
This is called to determine if the state is valid.
void setOptions(const KinematicOptions &source, OptionBitmask fields=ALL)
double timeout_seconds_
max time an IK attempt can take before we give up.
KinematicOptions()
Constructor - set all options to reasonable default values.
kinematics::KinematicsQueryOptions options_
other options
unsigned int max_attempts_
how many attempts before we give up.
bool setStateFromIK(robot_state::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::Pose &pose) const