moveit2
The MoveIt Motion Planning Framework for ROS 2.
ruckig_filter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2024, Andrew Zelenak
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/clock.hpp>
37 #include <rclcpp/logging.hpp>
38 
39 // Disable -Wold-style-cast because all _THROTTLE macros trigger this
40 #pragma GCC diagnostic ignored "-Wold-style-cast"
41 
43 {
44 namespace
45 {
46 rclcpp::Logger getLogger()
47 {
48  return moveit::getLogger("moveit.core.ruckig_filter_plugin");
49 }
50 } // namespace
51 
52 bool RuckigFilterPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
53  size_t num_joints)
54 {
55  robot_model_ = robot_model;
56 
57  // get node parameters and store in member variables
58  auto param_listener = online_signal_smoothing::ParamListener(node);
59  params_ = param_listener.get_params();
60 
61  // Ruckig needs the joint vel/accel bounds
62  // TODO: Ruckig says the jerk bounds can be optional. We require them, for now.
63  ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input(num_joints);
64  if (!getVelAccelJerkBounds(ruckig_input.max_velocity, ruckig_input.max_acceleration, ruckig_input.max_jerk))
65  {
66  return false;
67  }
68  ruckig_input.current_position = std::vector<double>(num_joints, 0.0);
69  ruckig_input.current_velocity = std::vector<double>(num_joints, 0.0);
70  ruckig_input.current_acceleration = std::vector<double>(num_joints, 0.0);
71  ruckig_input.synchronization = ruckig::Synchronization::Phase;
72 
73  ruckig_input_ = ruckig_input;
74 
75  ruckig_output_.emplace(ruckig::OutputParameter<ruckig::DynamicDOFs>(num_joints));
76 
77  ruckig_.emplace(ruckig::Ruckig<ruckig::DynamicDOFs>(num_joints, params_.update_period));
78 
79  return true;
80 }
81 
82 bool RuckigFilterPlugin::doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities,
83  Eigen::VectorXd& accelerations)
84 {
85  if (!ruckig_input_ || !ruckig_output_ || !ruckig_)
86  {
87  RCLCPP_ERROR_STREAM(getLogger(), "The Ruckig smoother was not initialized");
88  return false;
89  }
90 
91  if (have_initial_ruckig_output_)
92  {
93  ruckig_output_->pass_to_input(*ruckig_input_);
94  }
95 
96  // Update Ruckig target state
97  ruckig_input_->target_position = std::vector<double>(positions.data(), positions.data() + positions.size());
98  // We don't know what the next command will be. Assume velocity continues forward based on current state,
99  // target_acceleration is zero.
100  const size_t num_joints = ruckig_input_->current_acceleration.size();
101  for (size_t i = 0; i < num_joints; ++i)
102  {
103  ruckig_input_->target_velocity.at(i) =
104  ruckig_input_->current_velocity.at(i) + ruckig_input_->current_acceleration.at(i) * params_.update_period;
105  }
106  // target_acceleration remains a vector of zeroes
107 
108  // Call the Ruckig algorithm
109  ruckig::Result ruckig_result = ruckig_->update(*ruckig_input_, *ruckig_output_);
110 
111  // Finished means the target state can be reached in this timestep.
112  // Working means the target state can be reached but not in this timestep.
113  // ErrorSynchronizationCalculation means smoothing was successful but the robot will deviate a bit from the desired
114  // path.
115  // See https://github.com/pantor/ruckig/blob/master/include/ruckig/input_parameter.hpp
116  if (ruckig_result != ruckig::Result::Finished && ruckig_result != ruckig::Result::Working &&
117  ruckig_result != ruckig::Result::ErrorSynchronizationCalculation)
118 
119  {
120  RCLCPP_ERROR_STREAM(getLogger(), "Ruckig jerk-limited smoothing failed with code: " << ruckig_result);
121  printRuckigState();
122  // Return without modifying the position/vel/accel
123  have_initial_ruckig_output_ = false;
124  return true;
125  }
126 
127  // Update the target state with Ruckig output
128  positions = Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(ruckig_output_->new_position.data(),
129  ruckig_output_->new_position.size());
130  velocities = Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(ruckig_output_->new_velocity.data(),
131  ruckig_output_->new_velocity.size());
132  accelerations = Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(ruckig_output_->new_acceleration.data(),
133  ruckig_output_->new_acceleration.size());
134  have_initial_ruckig_output_ = true;
135 
136  return true;
137 }
138 
139 bool RuckigFilterPlugin::reset(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
140  const Eigen::VectorXd& accelerations)
141 {
142  // Initialize Ruckig
143  ruckig_input_->current_position = std::vector<double>(positions.data(), positions.data() + positions.size());
144  ruckig_input_->current_velocity = std::vector<double>(velocities.data(), velocities.data() + velocities.size());
145  ruckig_input_->current_acceleration =
146  std::vector<double>(accelerations.data(), accelerations.data() + accelerations.size());
147 
148  have_initial_ruckig_output_ = false;
149  return true;
150 }
151 
152 bool RuckigFilterPlugin::getVelAccelJerkBounds(std::vector<double>& joint_velocity_bounds,
153  std::vector<double>& joint_acceleration_bounds,
154  std::vector<double>& joint_jerk_bounds)
155 {
156  if (!robot_model_)
157  {
158  RCLCPP_ERROR(getLogger(), "The robot model was not initialized.");
159  return false;
160  }
161 
162  joint_velocity_bounds.clear();
163  joint_acceleration_bounds.clear();
164  joint_jerk_bounds.clear();
165 
166  auto joint_model_group = robot_model_->getJointModelGroup(params_.planning_group_name);
167  for (const auto& joint : joint_model_group->getActiveJointModels())
168  {
169  const auto& bound = joint->getVariableBounds(joint->getName());
170 
171  if (bound.velocity_bounded_)
172  {
173  // Assume symmetric limits
174  joint_velocity_bounds.push_back(bound.max_velocity_);
175  }
176  else
177  {
178  RCLCPP_ERROR_STREAM(getLogger(), "No joint velocity limit defined for " << joint->getName() << ".");
179  return false;
180  }
181 
182  if (bound.acceleration_bounded_)
183  {
184  // Assume symmetric limits
185  joint_acceleration_bounds.push_back(bound.max_acceleration_);
186  }
187  else
188  {
189  RCLCPP_WARN_STREAM(getLogger(), "No joint acceleration limit defined for " << joint->getName() << ".");
190  return false;
191  }
192 
193  if (bound.jerk_bounded_)
194  {
195  // Assume symmetric limits
196  joint_jerk_bounds.push_back(bound.max_jerk_);
197  }
198  // else, return false
199  else
200  {
201  RCLCPP_WARN_STREAM(getLogger(), "No joint jerk limit was defined for "
202  << joint->getName() << ". The output from Ruckig will not be jerk-limited.");
203  return false;
204  }
205  }
206 
207  return true;
208 }
209 
210 void RuckigFilterPlugin::printRuckigState()
211 {
212  RCLCPP_INFO_STREAM(getLogger(), ruckig_->delta_time << "\nRuckig input:\n"
213  << ruckig_input_->to_string() << "\nRuckig output:\n"
214  << ruckig_output_->to_string());
215 }
216 } // namespace online_signal_smoothing
217 
218 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
bool doSmoothing(Eigen::VectorXd &positions, Eigen::VectorXd &velocities, Eigen::VectorXd &accelerations) override
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
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79