45 controller_interface::CallbackReturn
on_init()
override;
61 controller_interface::CallbackReturn on_configure(
62 const rclcpp_lifecycle::State & previous_state)
override;
64 controller_interface::CallbackReturn on_activate(
65 const rclcpp_lifecycle::State & previous_state)
override;
67 controller_interface::CallbackReturn on_deactivate(
68 const rclcpp_lifecycle::State & previous_state)
override;
70 controller_interface::CallbackReturn on_error(
71 const rclcpp_lifecycle::State & previous_state)
override;
74 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
80 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
82 size_t num_joints_ = 0;
83 std::vector<std::string> command_joint_names_;
85 bool has_position_state_interface_ =
false;
86 bool has_velocity_state_interface_ =
false;
87 bool has_acceleration_state_interface_ =
false;
88 bool has_position_command_interface_ =
false;
89 bool has_velocity_command_interface_ =
false;
90 bool has_acceleration_command_interface_ =
false;
91 bool has_effort_command_interface_ =
false;
95 const std::vector<std::string> allowed_interface_types_ = {
100 std::vector<std::reference_wrapper<double>> position_reference_;
101 std::vector<std::reference_wrapper<double>> velocity_reference_;
104 std::unique_ptr<admittance_controller::AdmittanceRule> admittance_;
107 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
110 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr
111 input_joint_command_subscriber_;
112 rclcpp::Subscription<geometry_msgs::msg::WrenchStamped>::SharedPtr
113 input_wrench_command_subscriber_;
114 rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
117 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
121 input_joint_command_;
123 std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
126 trajectory_msgs::msg::JointTrajectoryPoint joint_command_msg_;
127 geometry_msgs::msg::WrenchStamped wrench_command_msg_;
129 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;
130 trajectory_msgs::msg::JointTrajectoryPoint last_reference_;
137 trajectory_msgs::msg::JointTrajectoryPoint reference_, joint_state_, reference_admittance_;
138 geometry_msgs::msg::Wrench ft_values_;
145 trajectory_msgs::msg::JointTrajectoryPoint & state_current,
146 geometry_msgs::msg::Wrench & ft_values);