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_;
89 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
91 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
92 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
94 bool has_position_state_interface_ =
false;
95 bool has_velocity_state_interface_ =
false;
96 bool has_acceleration_state_interface_ =
false;
97 bool has_position_command_interface_ =
false;
98 bool has_velocity_command_interface_ =
false;
99 bool has_acceleration_command_interface_ =
false;
100 bool has_effort_command_interface_ =
false;
104 const std::vector<std::string> allowed_interface_types_ = {
109 const std::vector<std::string> allowed_reference_interfaces_types_ = {
111 std::vector<std::reference_wrapper<double>> position_reference_;
112 std::vector<std::reference_wrapper<double>> velocity_reference_;
115 std::unique_ptr<admittance_controller::AdmittanceRule> admittance_;
118 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
121 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr
122 input_joint_command_subscriber_;
123 rclcpp::Subscription<geometry_msgs::msg::WrenchStamped>::SharedPtr
124 input_wrench_command_subscriber_;
125 rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
128 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
131 std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> joint_command_msg_;
135 input_joint_command_;
137 std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
139 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;
140 trajectory_msgs::msg::JointTrajectoryPoint last_reference_;
147 trajectory_msgs::msg::JointTrajectoryPoint reference_, joint_state_, reference_admittance_;
148 geometry_msgs::msg::Wrench ft_values_;
155 trajectory_msgs::msg::JointTrajectoryPoint & state_current,
156 geometry_msgs::msg::Wrench & ft_values);