38 #include <rclcpp/logging.hpp>
40 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros_robot_interaction.kinematic_options");
49 const std::string& tip,
50 const geometry_msgs::msg::Pose& pose)
const
55 RCLCPP_ERROR(LOGGER,
"No getJointModelGroup('%s') found",
group.c_str());
58 bool result = state.
setFromIK(jmg, pose, tip,
61 state_validity_callback_, options_);
76 F(double, timeout_seconds_, TIMEOUT) \
77 F(moveit::core::GroupStateValidityCallbackFn, state_validity_callback_, STATE_VALIDITY_CALLBACK)
81 #define QO_FIELDS(F) \
82 F(bool, lock_redundant_joints, LOCK_REDUNDANT_JOINTS) \
83 F(bool, return_approximate_solution, RETURN_APPROXIMATE_SOLUTION) \
84 F(::kinematics::DiscretizationMethods::DiscretizationMethod, discretization_method, DISCRETIZATION_METHOD)
88 struct DummyKinematicsQueryOptions
90 #define F(type, member, enumval) type member;
96 struct DummyKinematicOptions
98 #define F(type, member, enumval) type member;
101 DummyKinematicsQueryOptions options_;
112 #define F(type, member, enumval) \
113 if (fields & KinematicOptions::enumval) \
114 member = source.member;
120 #define F(type, member, enumval) \
121 if (fields & KinematicOptions::enumval) \
122 options_.member = source.options_.member;
double getDefaultIKTimeout() const
Get the default IK timeout.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
void update(bool force=false)
Update all transforms.
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
#define F(type, member, enumval)
const rclcpp::Logger LOGGER
A set of options for the kinematics solver.
void setOptions(const KinematicOptions &source, OptionBitmask fields=ALL)
bool setStateFromIK(moveit::core::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::msg::Pose &pose) const
KinematicOptions()
Constructor - set all options to reasonable default values.