38 #include <boost/static_assert.hpp> 42 : timeout_seconds_(0.0)
50 const std::string& tip,
const geometry_msgs::Pose& pose)
const 52 const robot_model::JointModelGroup* jmg = state.getJointModelGroup(group);
55 ROS_ERROR(
"No getJointModelGroup('%s') found", group.c_str());
73 F(double, timeout_seconds_, TIMEOUT) \ 74 F(unsigned int, max_attempts_, MAX_ATTEMPTS) \ 75 F(robot_state::GroupStateValidityCallbackFn, state_validity_callback_, STATE_VALIDITY_CALLBACK) 79 #define QO_FIELDS(F) \ 80 F(bool, lock_redundant_joints, LOCK_REDUNDANT_JOINTS) \ 81 F(bool, return_approximate_solution, RETURN_APPROXIMATE_SOLUTION) \ 82 F(::kinematics::DiscretizationMethods::DiscretizationMethod, discretization_method, DISCRETIZATION_METHOD) 86 struct DummyKinematicsQueryOptions
88 #define F(type, member, enumval) type member; 94 struct DummyKinematicOptions
96 #define F(type, member, enumval) type member; 99 DummyKinematicsQueryOptions
options_;
107 BOOST_STATIC_ASSERT(
sizeof(
KinematicOptions) ==
sizeof(DummyKinematicOptions));
110 #define F(type, member, enumval) \ 111 if (fields & KinematicOptions::enumval) \ 112 member = source.member; 118 #define F(type, member, enumval) \ 119 if (fields & KinematicOptions::enumval) \ 120 options_.member = source.options_.member;
robot_state::GroupStateValidityCallbackFn state_validity_callback_
This is called to determine if the state is valid.
#define F(type, member, enumval)
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