Class GravityCompensationController
Defined in File gravity_compensation_controller.hpp
Inheritance Relationships
Base Type
public controller_interface::ControllerInterface
Class Documentation
-
class GravityCompensationController : public controller_interface::ControllerInterface
Public Functions
-
GRAVITY_COMPENSATION_CONTROLLER_PUBLIC GravityCompensationController()
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
- GRAVITY_COMPENSATION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override
Protected Types
Protected Functions
-
std::string formatVector(const std::vector<double> &vec)
Protected Attributes
-
std::shared_ptr<ParamListener> param_listener_
-
Params params_
-
KDL::Tree tree_
-
KDL::JntArray q_ddot_
-
KDL::WrenchMap f_ext_
-
bool dither_switch_
-
std::vector<std::string> state_interface_types_ = {hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY,}
-
std::vector<std::string> command_interface_types_ = {hardware_interface::HW_IF_EFFORT}
-
std::vector<std::string> command_joint_names_
-
InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_
-
InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_
-
std::vector<std::string> joint_names_
-
size_t n_joints_
-
std::vector<double> joint_positions_
-
std::vector<double> joint_velocities_
-
std::vector<double> previous_velocities_
-
GRAVITY_COMPENSATION_CONTROLLER_PUBLIC GravityCompensationController()