Class JointImpedanceWithIKExampleController
Inheritance Relationships
Base Type
public controller_interface::ControllerInterface
Class Documentation
-
class JointImpedanceWithIKExampleController : public controller_interface::ControllerInterface
joint impedance example controller get desired pose and use inverse kinematics LMA (Levenberg-Marquardt) from Orocos KDL. IK returns the desired joint positions from the desired pose. Desired joint positions are fed to the impedance control law together with the current joint velocities to calculate the desired joint torques.
Public Types
-
using Vector7d = Eigen::Matrix<double, 7, 1>
Public Functions
-
controller_interface::InterfaceConfiguration command_interface_configuration() const override
-
controller_interface::InterfaceConfiguration state_interface_configuration() const override
-
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
-
CallbackReturn on_init() override
-
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override
-
using Vector7d = Eigen::Matrix<double, 7, 1>