38#include <rclcpp/logging.hpp>
48 const std::string& tip,
49 const geometry_msgs::msg::Pose& pose)
const
54 RCLCPP_ERROR(
moveit::getLogger(
"moveit.ros.kinematic_options"),
"No getJointModelGroup('%s') found", group.c_str());
57 bool result = state.
setFromIK(jmg, pose, tip,
60 state_validity_callback_, options_);
75 F(double, timeout_seconds_, TIMEOUT) \
76 F(moveit::core::GroupStateValidityCallbackFn, state_validity_callback_, STATE_VALIDITY_CALLBACK)
81 F(bool, lock_redundant_joints, LOCK_REDUNDANT_JOINTS) \
82 F(bool, return_approximate_solution, RETURN_APPROXIMATE_SOLUTION) \
83 F(::kinematics::DiscretizationMethods::DiscretizationMethod, discretization_method, DISCRETIZATION_METHOD)
87 struct DummyKinematicsQueryOptions
89#define F(type, member, enumval) type member;
95 struct DummyKinematicOptions
97#define F(type, member, enumval) type member;
100 DummyKinematicsQueryOptions options_;
111#define F(type, member, enumval) \
112 if (fields & KinematicOptions::enumval) \
113 member = source.member;
119#define F(type, member, enumval) \
120 if (fields & KinematicOptions::enumval) \
121 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)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced 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.