moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
acceleration_filter.h
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
35/* Author: Paul Gesel
36Description: applies smoothing by limiting the acceleration between consecutive commands.
37The purpose of the plugin is to prevent the robot's acceleration limits from being violated by instantaneous changes
38to the servo command topics.
39
40 In the diagrams below, the c-v lines show the displacement that will occur given the current velocity. The t-c lines
41 shows the displacement between the current position and the desired position. The dashed lines shows the maximum
42 possible displacements that are within the acceleration limits. The v-t lines shows the acceleration commands that
43 will be used by this acceleration-limiting plugin. The x point shows the position that will be used for each scenario.
44
45Scenario A: The desired position is within the acceleration limits. The next commanded point will be exactly the
46desired point.
47 ________
48 | |
49c --|-----xt |
50 \__|__ v |
51 |________|
52
53Scenario B: The line between the current position and the desired position intersects the acceleration limits, but the
54reference position is not within the bounds. The next commanded point will be the point on the displacement line that
55is closest to the reference.
56 ________
57 | |
58c --|--------x------t
59 \__|__ v |
60 |________|
61
62Scenario C: Neither the displacement line intersects the acceleration limits nor does the reference point lie within
63the limits. In this case, the next commanded point will be the one that minimizes the robot's velocity while
64maintaining its direction.
65 ________
66 | |
67c --------x--- v |
68 \ | |
69 \ |________|
70 t
71 */
72
73#pragma once
74
75#include <cstddef>
76
81#include <moveit_acceleration_filter_parameters.hpp>
82
83#include <osqp.h>
84#include <types.h>
85#include <Eigen/Sparse>
86
88{
90
91// Plugin
93{
94public:
102 bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
103 size_t num_joints) override;
104
113 bool doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations) override;
114
122 bool reset(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
123 const Eigen::VectorXd& accelerations) override;
124
129 {
130 if (osqp_workspace_ != nullptr)
131 {
132 osqp_cleanup(osqp_workspace_);
133 }
134 }
135
136private:
138 rclcpp::Node::SharedPtr node_;
140 online_signal_smoothing::Params params_;
142 size_t num_joints_;
144 Eigen::VectorXd last_velocities_;
145 Eigen::VectorXd last_positions_;
147 Eigen::VectorXd cur_acceleration_;
148 Eigen::VectorXd positions_offset_;
149 Eigen::VectorXd velocities_offset_;
151 Eigen::VectorXd max_acceleration_limits_;
152 Eigen::VectorXd min_acceleration_limits_;
154 moveit::core::RobotModelConstPtr robot_model_;
156 Eigen::SparseMatrix<double> constraints_sparse_;
158 OSQPDataWrapperPtr osqp_data_;
159 OSQPWorkspace* osqp_workspace_ = nullptr;
160 OSQPSettings osqp_settings_;
161};
162} // namespace online_signal_smoothing
#define MOVEIT_STRUCT_FORWARD(C)
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
Wrapper struct to make memory management easier for using osqp's C API.