moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
kinematic_options.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, SRI International
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Acorn Pooley */
36
38#include <rclcpp/logging.hpp>
40
41robot_interaction::KinematicOptions::KinematicOptions() : timeout_seconds_(0.0) // 0.0 = use default timeout
42{
43}
44
45// This is intended to be called as a ModifyStateFunction to modify the state
46// maintained by a LockedRobotState in place.
48 const std::string& tip,
49 const geometry_msgs::msg::Pose& pose) const
50{
51 const moveit::core::JointModelGroup* jmg = state.getJointModelGroup(group);
52 if (!jmg)
53 {
54 RCLCPP_ERROR(moveit::getLogger("moveit.ros.kinematic_options"), "No getJointModelGroup('%s') found", group.c_str());
55 return false;
56 }
57 bool result = state.setFromIK(jmg, pose, tip,
58 // limit timeout to 0.1s if set from JMG's default, i.e. when timeout_seconds_ == 0
59 timeout_seconds_ > 0.0 ? timeout_seconds_ : std::min(0.1, jmg->getDefaultIKTimeout()),
60 state_validity_callback_, options_);
61 state.update();
62 return result;
63}
64
66{
67// This function is implemented with the O_FIELDS and QO_FIELDS macros to
68// ensure that any fields added to robot_interaction::KinematicOptions or
69// kinematics::KinematicsQueryOptions are also added here and to the
70// KinematicOptions::OptionBitmask enum.
71
72// This needs to represent all the fields in
73// robot_interaction::KinematicOptions except options_
74#define O_FIELDS(F) \
75 F(double, timeout_seconds_, TIMEOUT) \
76 F(moveit::core::GroupStateValidityCallbackFn, state_validity_callback_, STATE_VALIDITY_CALLBACK)
77
78// This needs to represent all the fields in
79// kinematics::KinematicsQueryOptions
80#define QO_FIELDS(F) \
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)
84
85 // This structure should be identical to kinematics::KinematicsQueryOptions
86 // This is only used in the static_assert below.
87 struct DummyKinematicsQueryOptions
88 {
89#define F(type, member, enumval) type member;
91#undef F
92 };
93 // This structure should be identical to robot_interaction::KinematicOptions
94 // This is only used in the static_assert below.
95 struct DummyKinematicOptions
96 {
97#define F(type, member, enumval) type member;
98 O_FIELDS(F)
99#undef F
100 DummyKinematicsQueryOptions options_;
101 };
102
103 // If these asserts fails it means that fields were added to
104 // kinematics::KinematicsQueryOptions or robot_interaction::KinematicOptions
105 // and not added to the O_FIELDS and QO_FIELDS definitions above. To fix add
106 // any new fields to the definitions above.
107 static_assert(sizeof(kinematics::KinematicsQueryOptions) == sizeof(DummyKinematicsQueryOptions));
108 static_assert(sizeof(KinematicOptions) == sizeof(DummyKinematicOptions));
109
110// copy fields from other to this if its bit is set in fields
111#define F(type, member, enumval) \
112 if (fields & KinematicOptions::enumval) \
113 member = source.member;
114 O_FIELDS(F)
115#undef F
116
117// copy fields from other.options_ to this.options_ if its bit is set in
118// fields
119#define F(type, member, enumval) \
120 if (fields & KinematicOptions::enumval) \
121 options_.member = source.options_.member;
122 QO_FIELDS(F)
123#undef F
124}
double getDefaultIKTimeout() const
Get the default IK timeout.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
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 QO_FIELDS(F)
#define O_FIELDS(F)
#define F(type, member, enumval)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
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.