moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
kinematic_options_map.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
39// These strings have no content. They are compared by address.
42
46
47// Returns a copy of the KinematicOptions so that the caller does not need to
48// worry about locking.
50{
51 std::scoped_lock lock(lock_);
52
53 if (&key == &DEFAULT)
54 return defaults_;
55
56 M_options::const_iterator it = options_.find(key);
57 if (it == options_.end())
58 return defaults_;
59 return it->second;
60}
61
62void robot_interaction::KinematicOptionsMap::setOptions(const std::string& key, const KinematicOptions& options_delta,
64{
65 std::scoped_lock lock(lock_);
66
67 if (&key == &ALL)
68 {
69 if (fields == KinematicOptions::ALL)
70 {
71 // setting ALL fields for ALL keys
72 // so just clear all key-specific fields and set the defaults.
73 defaults_ = options_delta;
74 options_.clear();
75 return;
76 }
77
78 defaults_.setOptions(options_delta, fields);
79 for (std::pair<const std::string, KinematicOptions>& option : options_)
80 {
81 option.second.setOptions(options_delta, fields);
82 }
83 return;
84 }
85
86 if (&key == &DEFAULT)
87 {
88 defaults_.setOptions(options_delta, fields);
89 return;
90 }
91
92 M_options::iterator it = options_.find(key);
93 KinematicOptions* opts;
94 if (it == options_.end())
95 {
96 // create new entry for key and initialize to defaults_
97 opts = &options_[key];
98 *opts = defaults_;
99 }
100 else
101 {
102 opts = &it->second;
103 }
104
105 opts->setOptions(options_delta, fields);
106}
107
108// merge other into this. All options in other take precedence over this.
110{
111 if (&other == this)
112 return;
113
114 // need to lock in consistent order to avoid deadlock.
115 // Lock the one with lower address first.
116 std::mutex* m1 = &lock_;
117 std::mutex* m2 = &other.lock_;
118 if (m2 < m1)
119 std::swap(m1, m2);
120 std::scoped_lock lock1(*m1);
121 std::scoped_lock lock2(*m2);
122
123 defaults_ = other.defaults_;
124 for (const std::pair<const std::string, KinematicOptions>& option : other.options_)
125 {
126 options_[option.first] = option.second;
127 }
128}
129
130// This is intended to be called as a ModifyStateFunction to modify the state
131// maintained by a LockedRobotState in place.
133 const std::string& group, const std::string& tip,
134 const geometry_msgs::msg::Pose& pose) const
135{
136 // copy options so lock is not needed during IK solve.
137 KinematicOptions options = getOptions(key);
138 return options.setStateFromIK(state, group, tip, pose);
139}
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
KinematicOptionsMap()
Constructor - set all options to reasonable default values.
void setOptions(const std::string &key, const KinematicOptions &options, KinematicOptions::OptionBitmask fields=KinematicOptions::ALL)
bool setStateFromIK(moveit::core::RobotState &state, const std::string &key, const std::string &group, const std::string &tip, const geometry_msgs::msg::Pose &pose) const
static const std::string DEFAULT
When used as key this means the default value.
static const std::string ALL
When used as key this means set ALL keys (including default)
void merge(const KinematicOptionsMap &other)
KinematicOptions getOptions(const std::string &key) const
void setOptions(const KinematicOptions &source, OptionBitmask fields=ALL)