moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
ruckig_filter.h
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
35/* Author: Andy Zelenak
36Description: Applies jerk/acceleration/velocity limits to online motion commands
37 */
38
39#pragma once
40
41#include <cstddef>
42
45#include <moveit_ruckig_filter_parameters.hpp>
46
47#include <ruckig/ruckig.hpp>
48
50{
51
53{
54public:
62 bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
63 size_t num_joints) override;
64
72 bool doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations) override;
73
81 bool reset(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
82 const Eigen::VectorXd& accelerations) override;
83
84private:
88 void printRuckigState();
89
94 bool getVelAccelJerkBounds(std::vector<double>& joint_velocity_bounds, std::vector<double>& joint_acceleration_bounds,
95 std::vector<double>& joint_jerk_bounds);
96
98 online_signal_smoothing::Params params_;
100 moveit::core::RobotModelConstPtr robot_model_;
101 bool have_initial_ruckig_output_ = false;
102 std::optional<ruckig::Ruckig<ruckig::DynamicDOFs>> ruckig_;
103 std::optional<ruckig::InputParameter<ruckig::DynamicDOFs>> ruckig_input_;
104 std::optional<ruckig::OutputParameter<ruckig::DynamicDOFs>> ruckig_output_;
105};
106} // namespace online_signal_smoothing
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