#include <smoothing_base_class.h>
|
| SmoothingBaseClass () |
|
virtual | ~SmoothingBaseClass () |
|
virtual bool | initialize (rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model, size_t num_joints)=0 |
|
virtual bool | doSmoothing (Eigen::VectorXd &positions, Eigen::VectorXd &velocities, Eigen::VectorXd &accelerations)=0 |
|
virtual bool | reset (const Eigen::VectorXd &positions, const Eigen::VectorXd &velocities, const Eigen::VectorXd &accelerations)=0 |
|
Definition at line 58 of file smoothing_base_class.h.
◆ SmoothingBaseClass()
online_signal_smoothing::SmoothingBaseClass::SmoothingBaseClass |
( |
| ) |
|
|
default |
◆ ~SmoothingBaseClass()
online_signal_smoothing::SmoothingBaseClass::~SmoothingBaseClass |
( |
| ) |
|
|
virtualdefault |
◆ doSmoothing()
virtual bool online_signal_smoothing::SmoothingBaseClass::doSmoothing |
( |
Eigen::VectorXd & |
positions, |
|
|
Eigen::VectorXd & |
velocities, |
|
|
Eigen::VectorXd & |
accelerations |
|
) |
| |
|
pure virtual |
◆ initialize()
virtual bool online_signal_smoothing::SmoothingBaseClass::initialize |
( |
rclcpp::Node::SharedPtr |
node, |
|
|
moveit::core::RobotModelConstPtr |
robot_model, |
|
|
size_t |
num_joints |
|
) |
| |
|
pure virtual |
◆ reset()
virtual bool online_signal_smoothing::SmoothingBaseClass::reset |
( |
const Eigen::VectorXd & |
positions, |
|
|
const Eigen::VectorXd & |
velocities, |
|
|
const Eigen::VectorXd & |
accelerations |
|
) |
| |
|
pure virtual |
The documentation for this class was generated from the following files: