forked from PickNikRobotics/pick_ik
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgoal.cpp
238 lines (209 loc) · 9.21 KB
/
goal.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
#include <pick_ik/fk_moveit.hpp>
#include <pick_ik/goal.hpp>
#include <pick_ik/robot.hpp>
#include <algorithm>
#include <cmath>
#include <limits>
#include <moveit/kinematics_base/kinematics_base.h>
#include <moveit/robot_model/joint_model_group.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
#include <optional>
#include <vector>
namespace pick_ik {
double linear_distance(Eigen::Isometry3d const& frame_1, Eigen::Isometry3d const& frame_2) {
return (frame_1.translation() - frame_2.translation()).norm();
}
double angular_distance(Eigen::Isometry3d const& frame_1, Eigen::Isometry3d const& frame_2) {
auto const q_1 = Eigen::Quaterniond(frame_1.rotation());
auto const q_2 = Eigen::Quaterniond(frame_2.rotation());
return q_2.angularDistance(q_1);
}
auto make_frame_test_fn(Eigen::Isometry3d goal_frame,
std::optional<double> position_threshold = std::nullopt,
std::optional<double> orientation_threshold = std::nullopt) -> FrameTestFn {
return [=](Eigen::Isometry3d const& tip_frame) -> bool {
return (!position_threshold.has_value() ||
linear_distance(goal_frame, tip_frame) <= position_threshold) &&
(!orientation_threshold.has_value() ||
std::abs(angular_distance(goal_frame, tip_frame)) <= orientation_threshold.value());
};
}
auto make_frame_tests(std::vector<Eigen::Isometry3d> goal_frames,
std::optional<double> position_threshold,
std::optional<double> orientation_threshold) -> std::vector<FrameTestFn> {
auto tests = std::vector<FrameTestFn>{};
std::transform(goal_frames.cbegin(),
goal_frames.cend(),
std::back_inserter(tests),
[&](auto const& frame) {
return make_frame_test_fn(frame, position_threshold, orientation_threshold);
});
return tests;
}
auto make_pose_cost_fn(Eigen::Isometry3d goal,
size_t goal_link_index,
double position_scale,
double rotation_scale) -> PoseCostFn {
if (position_scale > 0.0) {
if (rotation_scale > 0.0) {
return [=](std::vector<Eigen::Isometry3d> const& tip_frames) -> double {
auto const& frame = tip_frames[goal_link_index];
return std::pow(linear_distance(goal, frame) * position_scale, 2) +
std::pow(angular_distance(goal, frame) * rotation_scale, 2);
};
} else {
return [=](std::vector<Eigen::Isometry3d> const& tip_frames) -> double {
auto const& frame = tip_frames[goal_link_index];
return std::pow(linear_distance(goal, frame) * position_scale, 2);
};
}
} else {
if (rotation_scale > 0.0) {
return [=](std::vector<Eigen::Isometry3d> const& tip_frames) -> double {
auto const& frame = tip_frames[goal_link_index];
return std::pow(angular_distance(goal, frame) * rotation_scale, 2);
};
} else {
return [=](std::vector<Eigen::Isometry3d> const&) -> double { return 0.0; };
}
}
}
auto make_pose_cost_functions(std::vector<Eigen::Isometry3d> goal_frames,
double position_scale,
double rotation_scale) -> std::vector<PoseCostFn> {
auto cost_functions = std::vector<PoseCostFn>{};
for (size_t i = 0; i < goal_frames.size(); ++i) {
cost_functions.push_back(
make_pose_cost_fn(goal_frames[i], i, position_scale, rotation_scale));
}
return cost_functions;
}
auto make_center_joints_cost_fn(Robot robot) -> CostFn {
return [=](std::vector<double> const& active_positions) -> double {
double sum = 0;
assert(robot.variables.size() == active_positions.size());
for (size_t i = 0; i < active_positions.size(); ++i) {
auto const& variable = robot.variables[i];
if (!variable.bounded) {
continue;
}
auto const position = active_positions[i];
auto const mid = (variable.min + variable.max) * 0.5;
sum += std::pow(position - mid, 2);
}
return sum;
};
}
auto make_avoid_joint_limits_cost_fn(Robot robot) -> CostFn {
return [=](std::vector<double> const& active_positions) -> double {
double sum = 0;
assert(robot.variables.size() == active_positions.size());
for (size_t i = 0; i < active_positions.size(); ++i) {
auto const& variable = robot.variables[i];
if (!variable.bounded) {
continue;
}
auto const position = active_positions[i];
sum += std::pow(
std::fmax(0.0, std::fabs(position - variable.mid) * 2.0 - variable.half_span),
2);
}
return sum;
};
}
auto make_minimal_displacement_cost_fn(Robot robot, std::vector<double> initial_guess) -> CostFn {
return [=](std::vector<double> const& active_positions) -> double {
double sum = 0;
assert(active_positions.size() == robot.variables.size() &&
active_positions.size() == initial_guess.size());
for (size_t i = 0; i < active_positions.size(); ++i) {
auto const guess = initial_guess[i];
auto const position = active_positions[i];
sum += std::pow(position - guess, 2);
}
return sum;
};
}
auto make_minimal_velocity_cost_fn(Robot robot_,
std::vector<double> initial_guess,
long joint_index,
double time_step) -> CostFn {
return [=](std::vector<double> const& active_positions) -> double {
double sum = 0;
assert(active_positions.size() == robot_.variables.size() &&
active_positions.size() == initial_guess.size());
auto const guess = initial_guess[joint_index];
auto const position = active_positions[joint_index];
sum += std::pow(position - guess, 2) / time_step;
return sum;
};
}
auto make_hard_joint_limits_cost_fn(Robot robot,
long joint_index,
double lower_limit,
double upper_limit) -> CostFn {
return [=](std::vector<double> const& active_positions) -> double {
assert(active_positions.size() == robot.variables.size());
double joint_value = active_positions[joint_index];
double value = std::fabs(joint_value - (upper_limit + lower_limit) / 2.0) * 2.0 -
(upper_limit - lower_limit) / 2.0;
double cost = std::pow(std::fmax(0.0, value), 2);
return cost;
};
}
auto make_ik_cost_fn(geometry_msgs::msg::Pose pose,
kinematics::KinematicsBase::IKCostFn cost_fn,
std::shared_ptr<moveit::core::RobotModel const> robot_model,
moveit::core::JointModelGroup const* jmg,
std::vector<double> initial_guess) -> CostFn {
auto robot_state = moveit::core::RobotState(robot_model);
robot_state.setToDefaultValues();
robot_state.setJointGroupPositions(jmg, initial_guess);
robot_state.update();
return [=](std::vector<double> const& active_positions) mutable {
robot_state.setJointGroupPositions(jmg, active_positions);
robot_state.update();
return cost_fn(pose, robot_state, jmg, initial_guess);
};
}
auto make_is_solution_test_fn(std::vector<FrameTestFn> frame_tests,
std::vector<Goal> goals,
double cost_threshold,
FkFn fk) -> SolutionTestFn {
return [=](std::vector<double> const& active_positions) {
auto tip_frames = fk(active_positions);
assert(frame_tests.size() == tip_frames.size());
for (size_t i = 0; i < frame_tests.size(); ++i) {
if (!frame_tests[i](tip_frames[i])) {
return false;
}
}
auto const cost_threshold_sq = std::pow(cost_threshold, 2);
for (auto const& goal : goals) {
auto const cost = goal.eval(active_positions) * goal.weight;
if (cost >= cost_threshold_sq) {
return false;
}
}
return true;
};
}
auto make_cost_fn(std::vector<PoseCostFn> pose_cost_functions,
std::vector<Goal> goals,
FkFn fk) -> CostFn {
return [=](std::vector<double> const& active_positions) {
auto tip_frames = fk(active_positions);
auto const pose_cost =
std::accumulate(pose_cost_functions.cbegin(),
pose_cost_functions.cend(),
0.0,
[&](auto sum, auto const& fn) { return sum + fn(tip_frames); });
auto const goal_cost =
std::accumulate(goals.cbegin(), goals.cend(), 0.0, [&](auto sum, auto const& goal) {
return sum + goal.eval(active_positions) * goal.weight;
});
return pose_cost + goal_cost;
};
}
} // namespace pick_ik