moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <acceleration_filter.h>
Public Member Functions | |
bool | initialize (rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model, size_t num_joints) override |
bool | doSmoothing (Eigen::VectorXd &positions, Eigen::VectorXd &velocities, Eigen::VectorXd &accelerations) override |
bool | reset (const Eigen::VectorXd &positions, const Eigen::VectorXd &velocities, const Eigen::VectorXd &accelerations) override |
~AccelerationLimitedPlugin () override | |
Public Member Functions inherited from online_signal_smoothing::SmoothingBaseClass | |
SmoothingBaseClass () | |
virtual | ~SmoothingBaseClass () |
Definition at line 92 of file acceleration_filter.h.
|
inlineoverride |
memory allocated by osqp is freed in destructor
Definition at line 128 of file acceleration_filter.h.
|
overridevirtual |
Smooth the command signals for all DOF. This function limits the change in velocity using the acceleration specified in the robot model.
positions | array of joint position commands |
velocities | array of joint velocity commands |
accelerations | (unused) |
Implements online_signal_smoothing::SmoothingBaseClass.
Definition at line 246 of file acceleration_filter.cpp.
|
overridevirtual |
Initialize the acceleration based smoothing plugin
node | ROS node, used for parameter retrieval |
robot_model | typically used to retrieve vel/accel/jerk limits |
num_joints | number of actuated joints in the JointGroup Servo controls |
Implements online_signal_smoothing::SmoothingBaseClass.
Definition at line 140 of file acceleration_filter.cpp.
|
overridevirtual |
Reset to a given joint state. This method must be called before doSmoothing.
positions | reset the filters to the joint positions |
velocities | reset the filters to the joint velocities |
accelerations | (unused) |
Implements online_signal_smoothing::SmoothingBaseClass.
Definition at line 334 of file acceleration_filter.cpp.