moveit2
The MoveIt Motion Planning Framework for ROS 2.
acceleration_filter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2024, PickNik Inc.
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 PickNik Inc. 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 
36 #include <rclcpp/logging.hpp>
37 
38 // Disable -Wold-style-cast because all _THROTTLE macros trigger this
39 #pragma GCC diagnostic ignored "-Wold-style-cast"
40 
42 {
43 rclcpp::Logger getLogger()
44 {
45  return moveit::getLogger("moveit.core.acceleration_limited_plugin");
46 }
47 
48 // The threshold below which any velocity or position difference is considered zero (rad and rad/s).
49 constexpr double COMMAND_DIFFERENCE_THRESHOLD = 1E-4;
50 // The scaling parameter alpha between the current point and commanded point must be less than 1.0
51 constexpr double ALPHA_UPPER_BOUND = 1.0;
52 // The scaling parameter alpha must also be greater than 0.0
53 constexpr double ALPHA_LOWER_BOUND = 0.0;
54 
56 struct CSCWrapper
57 {
59  std::vector<c_int> row_indices;
61  std::vector<c_int> column_pointers;
63  std::vector<double> elements;
66 
67  CSCWrapper(Eigen::SparseMatrix<double>& M)
68  {
69  M.makeCompressed();
70 
71  csc_sparse_matrix.n = M.cols();
72  csc_sparse_matrix.m = M.rows();
73  row_indices.assign(M.innerSize(), 0);
74  csc_sparse_matrix.i = row_indices.data();
75  column_pointers.assign(M.outerSize() + 1, 0);
77  csc_sparse_matrix.nzmax = M.nonZeros();
78  csc_sparse_matrix.nz = -1;
79  elements.assign(M.nonZeros(), 0.0);
80  csc_sparse_matrix.x = elements.data();
81 
82  update(M);
83  }
84 
86  void update(Eigen::SparseMatrix<double>& M)
87  {
88  for (size_t ind = 0; ind < row_indices.size(); ++ind)
89  {
90  row_indices[ind] = M.innerIndexPtr()[ind];
91  }
92 
93  for (size_t ind = 0; ind < column_pointers.size(); ++ind)
94  {
95  column_pointers[ind] = M.outerIndexPtr()[ind];
96  }
97  for (size_t ind = 0; ind < elements.size(); ++ind)
98  {
99  elements[ind] = M.data().at(ind);
100  }
101  }
102 };
103 
104 MOVEIT_STRUCT_FORWARD(OSQPDataWrapper);
105 
108 {
109  OSQPDataWrapper(Eigen::SparseMatrix<double>& objective_sparse, Eigen::SparseMatrix<double>& constraints_sparse)
110  : P{ objective_sparse }, A{ constraints_sparse }
111  {
112  data.n = objective_sparse.rows();
113  data.m = constraints_sparse.rows();
114  data.P = &P.csc_sparse_matrix;
115  q = Eigen::VectorXd::Zero(objective_sparse.rows());
116  data.q = q.data();
117  data.A = &A.csc_sparse_matrix;
118  l = Eigen::VectorXd::Zero(constraints_sparse.rows());
119  data.l = l.data();
120  u = Eigen::VectorXd::Zero(constraints_sparse.rows());
121  data.u = u.data();
122  }
123 
125  void updateA(OSQPWorkspace* work, Eigen::SparseMatrix<double>& constraints_sparse)
126  {
127  constraints_sparse.makeCompressed();
128  A.update(constraints_sparse);
129  osqp_update_A(work, A.elements.data(), OSQP_NULL, A.elements.size());
130  }
131 
134  Eigen::VectorXd q;
135  Eigen::VectorXd l;
136  Eigen::VectorXd u;
137  OSQPData data{};
138 };
139 
140 bool AccelerationLimitedPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
141  size_t num_joints)
142 {
143  // copy inputs into member variables
144  node_ = node;
145  num_joints_ = num_joints;
146  robot_model_ = robot_model;
147  cur_acceleration_ = Eigen::VectorXd::Zero(num_joints);
148 
149  // get node parameters and store in member variables
150  auto param_listener = online_signal_smoothing::ParamListener(node_);
151  params_ = param_listener.get_params();
152 
153  // get robot acceleration limits and store in member variables
154  auto joint_model_group = robot_model_->getJointModelGroup(params_.planning_group_name);
155  auto joint_bounds = joint_model_group->getActiveJointModelsBounds();
156  min_acceleration_limits_ = Eigen::VectorXd::Zero(num_joints);
157  max_acceleration_limits_ = Eigen::VectorXd::Zero(num_joints);
158  size_t ind = 0;
159  for (const auto& joint_bound : joint_bounds)
160  {
161  for (const auto& variable_bound : *joint_bound)
162  {
163  if (variable_bound.acceleration_bounded_)
164  {
165  min_acceleration_limits_[ind] = variable_bound.min_acceleration_;
166  max_acceleration_limits_[ind] = variable_bound.max_acceleration_;
167  }
168  else
169  {
170  RCLCPP_ERROR(getLogger(), "The robot must have acceleration joint limits specified for all joints to "
171  "use AccelerationLimitedPlugin.");
172  return false;
173  }
174  }
175  ind++;
176  }
177 
178  // setup osqp optimization problem
179  Eigen::SparseMatrix<double> objective_sparse(1, 1);
180  objective_sparse.insert(0, 0) = 1.0;
181  size_t num_constraints = num_joints + 1;
182  constraints_sparse_ = Eigen::SparseMatrix<double>(num_constraints, 1);
183  for (size_t i = 0; i < num_constraints - 1; ++i)
184  {
185  constraints_sparse_.insert(i, 0) = 0;
186  }
187  constraints_sparse_.insert(num_constraints - 1, 0) = 0;
188  osqp_set_default_settings(&osqp_settings_);
189  osqp_settings_.warm_start = 0;
190  osqp_settings_.verbose = 0;
191  osqp_data_ = std::make_shared<OSQPDataWrapper>(objective_sparse, constraints_sparse_);
192  osqp_data_->q[0] = 0;
193 
194  if (osqp_setup(&osqp_workspace_, &osqp_data_->data, &osqp_settings_) != 0)
195  {
196  osqp_settings_.verbose = 1;
197  // call setup again with verbose enables to trigger error message printing
198  osqp_setup(&osqp_workspace_, &osqp_data_->data, &osqp_settings_);
199  RCLCPP_ERROR(getLogger(), "Failed to initialize osqp problem.");
200  return false;
201  }
202 
203  return true;
204 }
205 
206 double jointLimitAccelerationScalingFactor(const Eigen::VectorXd& accelerations,
207  const moveit::core::JointBoundsVector& joint_bounds)
208 {
209  double min_scaling_factor = 1.0;
210 
211  // Now get the scaling factor from joint limits.
212  size_t idx = 0;
213  for (const auto& joint_bound : joint_bounds)
214  {
215  for (const auto& variable_bound : *joint_bound)
216  {
217  const auto& target_accel = accelerations(idx);
218  if (variable_bound.acceleration_bounded_ && target_accel != 0.0)
219  {
220  // Find the ratio of clamped acceleration to original acceleration
221  const auto bounded_vel =
222  std::clamp(target_accel, variable_bound.min_acceleration_, variable_bound.max_acceleration_);
223  double joint_scaling_factor = bounded_vel / target_accel;
224  min_scaling_factor = std::min(min_scaling_factor, joint_scaling_factor);
225  }
226  ++idx;
227  }
228  }
229 
230  return min_scaling_factor;
231 }
232 
233 inline bool updateData(const OSQPDataWrapperPtr& data, OSQPWorkspace* work,
234  Eigen::SparseMatrix<double>& constraints_sparse, const Eigen::VectorXd& lower_bound,
235  const Eigen::VectorXd& upper_bound)
236 {
237  data->updateA(work, constraints_sparse);
238  size_t num_constraints = constraints_sparse.rows();
239  data->u.block(0, 0, num_constraints - 1, 1) = upper_bound;
240  data->l.block(0, 0, num_constraints - 1, 1) = lower_bound;
241  data->u[num_constraints - 1] = ALPHA_UPPER_BOUND;
242  data->l[num_constraints - 1] = ALPHA_LOWER_BOUND;
243  return 0 == osqp_update_bounds(work, data->l.data(), data->u.data());
244 }
245 
246 bool AccelerationLimitedPlugin::doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities,
247  Eigen::VectorXd& /* unused */)
248 {
249  const size_t num_positions = velocities.size();
250  if (num_positions != num_joints_)
251  {
252  RCLCPP_ERROR_THROTTLE(
253  getLogger(), *node_->get_clock(), 1000,
254  "The length of the joint positions parameter is not equal to the number of joints, expected %zu got %zu.",
255  num_joints_, num_positions);
256  return false;
257  }
258  else if (last_positions_.size() != positions.size())
259  {
260  RCLCPP_ERROR_THROTTLE(getLogger(), *node_->get_clock(), 1000,
261  "The length of the last joint positions not equal to the current, expected %zu got %zu. Make "
262  "sure the reset was called.",
263  last_positions_.size(), positions.size());
264  return false;
265  }
266 
267  // formulate a quadratic program to find the best new reference point subject to the robot's acceleration limits
268  // p_c: robot's current position
269  // v_c: robot's current velocity
270  // p_t: robot's target position
271  // acc: acceleration to be applied
272  // p_n: next position
273  // dt: time step
274  // p_n_hat: parameterize solution to be along the line from p_c to p_t
275  // p_n_hat = p_t*alpha + p_c*(1-alpha)
276  // define constraints
277  // p_c + v_c*dt + acc_min*dt^2 < p_n_hat < p_c + v_c*dt + acc_max*dt^2
278  // p_c + v_c*dt -p_t + acc_min*dt^2 < (p_c-p_t)alpha < p_c + v_c*dt -p_t + acc_max*dt^2
279  // 0 < alpha < 1
280  // define optimization
281  // opt ||alpha||
282  // s.t. constraints
283  // p_n = p_t*alpha + p_c*(1-alpha)
284 
285  double& update_period = params_.update_period;
286  size_t num_constraints = num_joints_ + 1;
287  positions_offset_ = last_positions_ - positions;
288  velocities_offset_ = last_velocities_ - velocities;
289  for (size_t i = 0; i < num_constraints - 1; ++i)
290  {
291  constraints_sparse_.coeffRef(i, 0) = positions_offset_[i];
292  }
293  constraints_sparse_.coeffRef(num_constraints - 1, 0) = 1;
294  Eigen::VectorXd vel_point = last_positions_ + last_velocities_ * update_period;
295  Eigen::VectorXd upper_bound = vel_point - positions + max_acceleration_limits_ * (update_period * update_period);
296  Eigen::VectorXd lower_bound = vel_point - positions + min_acceleration_limits_ * (update_period * update_period);
297  if (!updateData(osqp_data_, osqp_workspace_, constraints_sparse_, lower_bound, upper_bound))
298  {
299  RCLCPP_ERROR_THROTTLE(getLogger(), *node_->get_clock(), 1000,
300  "failed to set osqp_update_bounds. Make sure the robot's acceleration limits are valid");
301  return false;
302  }
303 
304  if (positions_offset_.norm() < COMMAND_DIFFERENCE_THRESHOLD &&
305  velocities_offset_.norm() < COMMAND_DIFFERENCE_THRESHOLD)
306  {
307  positions = last_positions_;
308  velocities = last_velocities_;
309  }
310  else if (osqp_solve(osqp_workspace_) == 0 &&
311  osqp_workspace_->solution->x[0] >= ALPHA_LOWER_BOUND - osqp_settings_.eps_abs &&
312  osqp_workspace_->solution->x[0] <= ALPHA_UPPER_BOUND + osqp_settings_.eps_abs)
313  {
314  double alpha = osqp_workspace_->solution->x[0];
315  positions = alpha * last_positions_ + (1.0 - alpha) * positions.eval();
316  velocities = (positions - last_positions_) / update_period;
317  }
318  else
319  {
320  auto joint_model_group = robot_model_->getJointModelGroup(params_.planning_group_name);
321  auto joint_bounds = joint_model_group->getActiveJointModelsBounds();
322  cur_acceleration_ = -(last_velocities_) / update_period;
323  cur_acceleration_ *= jointLimitAccelerationScalingFactor(cur_acceleration_, joint_bounds);
324  velocities = last_velocities_ + cur_acceleration_ * update_period;
325  positions = last_positions_ + velocities * update_period;
326  }
327 
328  last_velocities_ = velocities;
329  last_positions_ = positions;
330 
331  return true;
332 }
333 
334 bool AccelerationLimitedPlugin::reset(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
335  const Eigen::VectorXd& /* unused */)
336 {
337  last_velocities_ = velocities;
338  last_positions_ = positions;
339  cur_acceleration_ = Eigen::VectorXd::Zero(num_joints_);
340 
341  return true;
342 }
343 
344 } // namespace online_signal_smoothing
345 
346 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model, size_t num_joints) override
bool reset(const Eigen::VectorXd &positions, const Eigen::VectorXd &velocities, const Eigen::VectorXd &accelerations) override
bool doSmoothing(Eigen::VectorXd &positions, Eigen::VectorXd &velocities, Eigen::VectorXd &accelerations) override
std::vector< const JointModel::Bounds * > JointBoundsVector
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
double jointLimitAccelerationScalingFactor(const Eigen::VectorXd &accelerations, const moveit::core::JointBoundsVector &joint_bounds)
MOVEIT_STRUCT_FORWARD(OSQPDataWrapper)
bool updateData(const OSQPDataWrapperPtr &data, OSQPWorkspace *work, Eigen::SparseMatrix< double > &constraints_sparse, const Eigen::VectorXd &lower_bound, const Eigen::VectorXd &upper_bound)
constexpr double ALPHA_LOWER_BOUND
constexpr double COMMAND_DIFFERENCE_THRESHOLD
constexpr double ALPHA_UPPER_BOUND
Wrapper struct to make memory management easier for using osqp's C sparse_matrix types.
std::vector< double > elements
holds the non-zero values in Compressed Sparse Column (CSC) form
csc csc_sparse_matrix
osqp C sparse_matrix type
std::vector< c_int > column_pointers
column pointers (size n+1); col indices (size nzmax)
void update(Eigen::SparseMatrix< double > &M)
Update the the data point to by sparse_matrix without reallocating memory.
std::vector< c_int > row_indices
row indices, size nzmax starting from 0
CSCWrapper(Eigen::SparseMatrix< double > &M)
Wrapper struct to make memory management easier for using osqp's C API.
void updateA(OSQPWorkspace *work, Eigen::SparseMatrix< double > &constraints_sparse)
Update the constraint matrix A without reallocating memory.
OSQPDataWrapper(Eigen::SparseMatrix< double > &objective_sparse, Eigen::SparseMatrix< double > &constraints_sparse)