74 const geometry_msgs::msg::Pose& pose)
const;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
A set of options for the kinematics solver.
void setOptions(const KinematicOptions &source, OptionBitmask fields=ALL)
kinematics::KinematicsQueryOptions options_
other options
@ RETURN_APPROXIMATE_SOLUTION
@ STATE_VALIDITY_CALLBACK
bool setStateFromIK(moveit::core::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::msg::Pose &pose) const
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.
KinematicOptions()
Constructor - set all options to reasonable default values.