forked from moveit/moveit2
/
servo.cpp
502 lines (432 loc) · 18.9 KB
/
servo.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
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
/*******************************************************************************
* BSD 3-Clause License
*
* Copyright (c) 2019, Los Alamos National Security, LLC
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************/
/* Title : servo.cpp
* Project : moveit_servo
* Created : 05/17/2023
* Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim
*/
#include <moveit_servo/servo.hpp>
#include <moveit_servo/utils/command.hpp>
#include <moveit_servo/utils/common.hpp>
#include <rclcpp/rclcpp.hpp>
namespace
{
const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.servo");
constexpr double ROBOT_STATE_WAIT_TIME = 5.0; // seconds
constexpr double STOPPED_VELOCITY_EPS = 1e-4;
} // namespace
namespace moveit_servo
{
Servo::Servo(const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::ParamListener> servo_param_listener,
const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor)
: node_(node)
, servo_param_listener_{ servo_param_listener }
, planning_scene_monitor_{ planning_scene_monitor }
, transform_buffer_(node_->get_clock())
, transform_listener_(transform_buffer_)
{
servo_params_ = servo_param_listener_->get_params();
const bool params_valid = validateParams(servo_params_);
if (!params_valid)
{
RCLCPP_ERROR_STREAM(LOGGER, "Got invalid parameters, exiting.");
std::exit(EXIT_FAILURE);
}
if (!planning_scene_monitor_->getStateMonitor()->waitForCompleteState(servo_params_.move_group_name,
ROBOT_STATE_WAIT_TIME))
{
RCLCPP_ERROR(LOGGER, "Timeout waiting for current state");
std::exit(EXIT_FAILURE);
}
// Planning scene monitor is passed in.
if (servo_params_.is_primary_planning_scene_monitor)
{
planning_scene_monitor_->providePlanningSceneService();
}
else
{
planning_scene_monitor_->requestPlanningSceneState();
}
moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
// Check if the transforms to planning frame and end effector frame exist.
if (!robot_state->knowsFrameTransform(servo_params_.planning_frame))
{
servo_status_ = StatusCode::INVALID;
RCLCPP_ERROR_STREAM(LOGGER, "No transform available for planning frame " << servo_params_.planning_frame);
}
else if (!robot_state->knowsFrameTransform(servo_params_.ee_frame))
{
servo_status_ = StatusCode::INVALID;
RCLCPP_ERROR_STREAM(LOGGER, "No transform available for end effector frame " << servo_params_.ee_frame);
}
else
{
// Load the smoothing plugin
if (servo_params_.use_smoothing)
{
setSmoothingPlugin();
}
else
{
RCLCPP_WARN(LOGGER, "No smoothing plugin loaded");
}
// Create the collision checker and start collision checking.
collision_monitor_ =
std::make_unique<CollisionMonitor>(planning_scene_monitor_, servo_params_, std::ref(collision_velocity_scale_));
collision_monitor_->start();
servo_status_ = StatusCode::NO_WARNING;
RCLCPP_INFO_STREAM(LOGGER, "Servo initialized successfully");
}
}
Servo::~Servo()
{
setCollisionChecking(false);
}
void Servo::setSmoothingPlugin()
{
// Load the smoothing plugin
try
{
pluginlib::ClassLoader<online_signal_smoothing::SmoothingBaseClass> smoothing_loader(
"moveit_core", "online_signal_smoothing::SmoothingBaseClass");
smoother_ = smoothing_loader.createUniqueInstance(servo_params_.smoothing_filter_plugin_name);
}
catch (pluginlib::PluginlibException& ex)
{
RCLCPP_ERROR(LOGGER, "Exception while loading the smoothing plugin '%s': '%s'",
servo_params_.smoothing_filter_plugin_name.c_str(), ex.what());
std::exit(EXIT_FAILURE);
}
// Initialize the smoothing plugin
moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
const int num_joints =
robot_state->getJointModelGroup(servo_params_.move_group_name)->getActiveJointModelNames().size();
if (!smoother_->initialize(node_, planning_scene_monitor_->getRobotModel(), num_joints))
{
RCLCPP_ERROR(LOGGER, "Smoothing plugin could not be initialized");
std::exit(EXIT_FAILURE);
}
}
void Servo::setCollisionChecking(const bool check_collision)
{
check_collision ? collision_monitor_->start() : collision_monitor_->stop();
}
bool Servo::validateParams(const servo::Params& servo_params)
{
bool params_valid = true;
auto robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
auto joint_model_group = robot_state->getJointModelGroup(servo_params.move_group_name);
if (joint_model_group == nullptr)
{
RCLCPP_ERROR_STREAM(LOGGER, "Invalid move group name: `" << servo_params.move_group_name << '`');
params_valid = false;
}
if (servo_params.hard_stop_singularity_threshold <= servo_params.lower_singularity_threshold)
{
RCLCPP_ERROR(LOGGER, "Parameter 'hard_stop_singularity_threshold' "
"should be greater than 'lower_singularity_threshold.' "
"Check the parameters YAML file used to launch this node.");
params_valid = false;
}
if (!servo_params.publish_joint_positions && !servo_params.publish_joint_velocities &&
!servo_params.publish_joint_accelerations)
{
RCLCPP_ERROR(LOGGER, "At least one of publish_joint_positions / "
"publish_joint_velocities / "
"publish_joint_accelerations must be true. "
"Check the parameters YAML file used to launch this node.");
params_valid = false;
}
if ((servo_params.command_out_type == "std_msgs/Float64MultiArray") && servo_params.publish_joint_positions &&
servo_params.publish_joint_velocities)
{
RCLCPP_ERROR(LOGGER, "When publishing a std_msgs/Float64MultiArray, "
"you must select positions OR velocities."
"Check the parameters YAML file used to launch this node.");
params_valid = false;
}
if (servo_params.scene_collision_proximity_threshold < servo_params.self_collision_proximity_threshold)
{
RCLCPP_ERROR(LOGGER, "Parameter 'self_collision_proximity_threshold' should probably be less "
"than or equal to 'scene_collision_proximity_threshold'."
"Check the parameters YAML file used to launch this node.");
params_valid = false;
}
return params_valid;
}
bool Servo::updateParams()
{
bool params_updated = false;
if (servo_param_listener_->is_old(servo_params_))
{
auto params = servo_param_listener_->get_params();
const bool params_valid = validateParams(params);
if (params_valid)
{
if (params.override_velocity_scaling_factor != servo_params_.override_velocity_scaling_factor)
{
RCLCPP_INFO_STREAM(LOGGER, "override_velocity_scaling_factor changed to : "
<< std::to_string(params.override_velocity_scaling_factor));
}
if (params.move_group_name != servo_params_.move_group_name)
{
RCLCPP_INFO_STREAM(LOGGER, "Move group changed from " << servo_params_.move_group_name << " to "
<< params.move_group_name);
}
servo_params_ = params;
params_updated = true;
}
else
{
RCLCPP_WARN_STREAM(LOGGER, "Parameters will not be updated.");
}
}
return params_updated;
}
servo::Params& Servo::getParams()
{
return servo_params_;
}
StatusCode Servo::getStatus()
{
return servo_status_;
}
const std::string Servo::getStatusMessage()
{
return SERVO_STATUS_CODE_MAP.at(servo_status_);
}
CommandType Servo::getCommandType()
{
return expected_command_type_;
}
void Servo::setCommandType(const CommandType& command_type)
{
expected_command_type_ = command_type;
}
const Eigen::Isometry3d Servo::getEndEffectorPose()
{
// Robot base (panda_link0) to end effector frame (panda_link8)
return planning_scene_monitor_->getStateMonitor()->getCurrentState()->getGlobalLinkTransform(servo_params_.ee_frame);
}
KinematicState Servo::haltJoints(const std::vector<int>& joints_to_halt, const KinematicState& current_state,
const KinematicState& target_state)
{
KinematicState bounded_state(target_state.joint_names.size());
bounded_state.joint_names = target_state.joint_names;
std::stringstream halting_joint_names;
for (const int idx : joints_to_halt)
{
halting_joint_names << bounded_state.joint_names[idx] + " ";
}
RCLCPP_WARN_STREAM(LOGGER, "Joint position limit reached on joints: " << halting_joint_names.str());
const bool all_joint_halt =
(getCommandType() == CommandType::JOINT_JOG && servo_params_.halt_all_joints_in_joint_mode) ||
(getCommandType() == CommandType::TWIST && servo_params_.halt_all_joints_in_cartesian_mode);
if (all_joint_halt)
{
// The velocities are initialized to zero by default, so we dont need to set it here.
bounded_state.positions = current_state.positions;
}
else
{
// Halt only the joints that are out of bounds
bounded_state.positions = target_state.positions;
bounded_state.velocities = target_state.velocities;
for (const int idx : joints_to_halt)
{
bounded_state.positions[idx] = current_state.positions[idx];
bounded_state.velocities[idx] = 0.0;
}
}
return bounded_state;
}
Eigen::VectorXd Servo::jointDeltaFromCommand(const ServoInput& command, moveit::core::RobotStatePtr& robot_state)
{
const int num_joints =
robot_state->getJointModelGroup(servo_params_.move_group_name)->getActiveJointModelNames().size();
Eigen::VectorXd joint_position_deltas(num_joints);
joint_position_deltas.setZero();
JointDeltaResult delta_result;
const CommandType expected_type = getCommandType();
if (command.index() == static_cast<size_t>(expected_type))
{
if (expected_type == CommandType::JOINT_JOG)
{
delta_result = jointDeltaFromJointJog(std::get<JointJogCommand>(command), robot_state, servo_params_);
servo_status_ = delta_result.first;
}
else if (expected_type == CommandType::TWIST)
{
const TwistCommand command_in_planning_frame = toPlanningFrame(std::get<TwistCommand>(command));
delta_result = jointDeltaFromTwist(command_in_planning_frame, robot_state, servo_params_);
servo_status_ = delta_result.first;
}
else if (expected_type == CommandType::POSE)
{
const PoseCommand command_in_planning_frame = toPlanningFrame(std::get<PoseCommand>(command));
delta_result = jointDeltaFromPose(command_in_planning_frame, robot_state, servo_params_);
servo_status_ = delta_result.first;
}
if (servo_status_ != StatusCode::INVALID)
{
joint_position_deltas = delta_result.second;
}
}
else
{
servo_status_ = StatusCode::INVALID;
RCLCPP_WARN_STREAM(LOGGER, "SERVO : Incoming command type does not match expected command type.");
}
return joint_position_deltas;
}
KinematicState Servo::getNextJointState(const ServoInput& command)
{
// Set status to clear
servo_status_ = StatusCode::NO_WARNING;
// Update the parameters
updateParams();
// Get the robot state and joint model group info.
moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
const moveit::core::JointModelGroup* joint_model_group =
robot_state->getJointModelGroup(servo_params_.move_group_name);
// Get necessary information about joints
const std::vector<std::string> joint_names = joint_model_group->getActiveJointModelNames();
const moveit::core::JointBoundsVector joint_bounds = joint_model_group->getActiveJointModelsBounds();
const int num_joints = joint_names.size();
// State variables
KinematicState current_state(num_joints), target_state(num_joints);
target_state.joint_names = joint_names;
// Copy current kinematic data from RobotState.
robot_state->copyJointGroupPositions(joint_model_group, current_state.positions);
robot_state->copyJointGroupVelocities(joint_model_group, current_state.velocities);
// Create Eigen maps for cleaner operations.
Eigen::Map<Eigen::VectorXd> current_joint_positions(current_state.positions.data(), num_joints);
Eigen::Map<Eigen::VectorXd> target_joint_positions(target_state.positions.data(), num_joints);
Eigen::Map<Eigen::VectorXd> current_joint_velocities(current_state.velocities.data(), num_joints);
Eigen::Map<Eigen::VectorXd> target_joint_velocities(target_state.velocities.data(), num_joints);
// Compute the change in joint position due to the incoming command
Eigen::VectorXd joint_position_delta = jointDeltaFromCommand(command, robot_state);
if (collision_velocity_scale_ > 0 && collision_velocity_scale_ < 1)
{
servo_status_ = StatusCode::DECELERATE_FOR_COLLISION;
}
else if (collision_velocity_scale_ == 0)
{
servo_status_ = StatusCode::HALT_FOR_COLLISION;
}
// Continue rest of the computations only if the command is valid
// The computations can be skipped also in case we are halting.
if (servo_status_ != StatusCode::INVALID && servo_status_ != StatusCode::HALT_FOR_COLLISION)
{
// Apply collision scaling to the joint position delta
joint_position_delta *= collision_velocity_scale_;
// Compute the next joint positions based on the joint position deltas
target_joint_positions = current_joint_positions + joint_position_delta;
// TODO : apply filtering to the velocity instead of position
// Apply smoothing to the positions if a smoother was provided.
// Update filter state and apply filtering in position domain
if (smoother_)
{
smoother_->reset(current_state.positions);
smoother_->doSmoothing(target_state.positions);
}
// Compute velocities based on smoothed joint positions
target_joint_velocities = (target_joint_positions - current_joint_positions) / servo_params_.publish_period;
// Scale down the velocity based on joint velocity limit or user defined scaling if applicable.
const double joint_limit_scale = jointLimitVelocityScalingFactor(target_joint_velocities, joint_bounds,
servo_params_.override_velocity_scaling_factor);
if (joint_limit_scale < 1.0) // 1.0 means no scaling.
RCLCPP_WARN_STREAM(LOGGER, "Joint velocity limit scaling applied by a factor of " << joint_limit_scale);
target_joint_velocities *= joint_limit_scale;
// Adjust joint position based on scaled down velocity
target_joint_positions = current_joint_positions + (target_joint_velocities * servo_params_.publish_period);
// Check if any joints are going past joint position limits
const std::vector<int> joints_to_halt =
jointsToHalt(target_joint_positions, target_joint_velocities, joint_bounds, servo_params_.joint_limit_margin);
// Apply halting if any joints need to be halted.
if (!joints_to_halt.empty())
{
servo_status_ = StatusCode::JOINT_BOUND;
target_state = haltJoints(joints_to_halt, current_state, target_state);
}
}
return target_state;
}
const TwistCommand Servo::toPlanningFrame(const TwistCommand& command)
{
const auto command_to_planning_frame =
transform_buffer_.lookupTransform(servo_params_.planning_frame, command.frame_id, rclcpp::Time(0));
Eigen::VectorXd transformed_twist = command.velocities;
tf2::doTransform(transformed_twist, transformed_twist, command_to_planning_frame);
return TwistCommand{ servo_params_.planning_frame, transformed_twist };
}
const PoseCommand Servo::toPlanningFrame(const PoseCommand& command)
{
auto target_pose_msg = convertIsometryToTransform(command.pose, servo_params_.planning_frame, command.frame_id);
auto command_to_planning_frame = transform_buffer_.lookupTransform(
servo_params_.planning_frame, command.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(2));
tf2::doTransform(target_pose_msg, target_pose_msg, command_to_planning_frame);
return PoseCommand{ servo_params_.planning_frame, tf2::transformToEigen(target_pose_msg) };
}
KinematicState Servo::getCurrentRobotState()
{
moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
const moveit::core::JointModelGroup* joint_model_group =
robot_state->getJointModelGroup(servo_params_.move_group_name);
const auto joint_names = joint_model_group->getActiveJointModelNames();
KinematicState current_state(joint_names.size());
current_state.joint_names = joint_names;
robot_state->copyJointGroupPositions(joint_model_group, current_state.positions);
robot_state->copyJointGroupVelocities(joint_model_group, current_state.velocities);
robot_state->copyJointGroupAccelerations(joint_model_group, current_state.accelerations);
return current_state;
}
KinematicState Servo::smoothHalt(KinematicState halt_state)
{
const auto current_state = getCurrentRobotState();
const size_t num_joints = current_state.joint_names.size();
for (size_t i = 0; i < num_joints; i++)
{
const double vel = (halt_state.positions[i] - current_state.positions[i]) / servo_params_.publish_period;
halt_state.velocities[i] = (vel > STOPPED_VELOCITY_EPS) ? vel : 0.0;
halt_state.accelerations[i] =
(halt_state.velocities[i] - current_state.velocities[i]) / servo_params_.publish_period;
}
if (smoother_)
{
smoother_->reset(current_state.positions);
smoother_->doSmoothing(halt_state.positions);
}
return halt_state;
}
} // namespace moveit_servo