38 #include <boost/static_assert.hpp>
48 const std::string& tip,
const geometry_msgs::Pose& pose)
const
53 ROS_ERROR(
"No getJointModelGroup('%s') found", group.c_str());
56 bool result = state.
setFromIK(jmg, pose, tip,
59 state_validity_callback_, options_);
74 F(double, timeout_seconds_, TIMEOUT) \
75 F(moveit::core::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;