46 Eigen::Isometry3d ref_base_ft_;
49 Eigen::Isometry3d base_ft_;
52 Eigen::Isometry3d base_control_;
55 Eigen::Isometry3d base_tip_;
58 Eigen::Isometry3d base_cog_;
60 Eigen::Isometry3d world_base_;
67 admittance_velocity.setZero();
68 admittance_acceleration.setZero();
73 selected_axes.setZero();
74 auto idx =
static_cast<Eigen::Index
>(num_joints);
75 current_joint_pos = Eigen::VectorXd::Zero(idx);
76 joint_pos = Eigen::VectorXd::Zero(idx);
77 joint_vel = Eigen::VectorXd::Zero(idx);
78 joint_acc = Eigen::VectorXd::Zero(idx);
81 Eigen::VectorXd current_joint_pos;
82 Eigen::VectorXd joint_pos;
83 Eigen::VectorXd joint_vel;
84 Eigen::VectorXd joint_acc;
85 Eigen::Matrix<double, 6, 1> damping;
86 Eigen::Matrix<double, 6, 1> mass;
87 Eigen::Matrix<double, 6, 1> mass_inv;
88 Eigen::Matrix<double, 6, 1> selected_axes;
89 Eigen::Matrix<double, 6, 1> stiffness;
90 Eigen::Matrix<double, 6, 1> wrench_base;
91 Eigen::Matrix<double, 6, 1> admittance_acceleration;
92 Eigen::Matrix<double, 6, 1> admittance_velocity;
93 Eigen::Isometry3d admittance_position;
94 Eigen::Matrix<double, 3, 3> rot_base_control;
95 Eigen::Isometry3d ref_trans_base_ft;
96 std::string ft_sensor_frame;
103 const std::shared_ptr<admittance_controller::ParamListener> & parameter_handler)
105 parameter_handler_ = parameter_handler;
106 parameters_ = parameter_handler_->get_params();
107 num_joints_ = parameters_.joints.size();
113 controller_interface::return_type
configure(
114 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node,
const size_t num_joint);
117 controller_interface::return_type
reset(
const size_t num_joints);
127 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
128 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state);
148 controller_interface::return_type
update(
149 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
150 const geometry_msgs::msg::Wrench & measured_wrench,
151 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
152 const rclcpp::Duration & period,
153 trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);
165 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
166 admittance_controller::Params parameters_;
187 const geometry_msgs::msg::Wrench & measured_wrench,
188 const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
189 const Eigen::Matrix<double, 3, 3> & cog_world_rot);
191 template <
typename T1,
typename T2>
192 void vec_to_eigen(
const std::vector<T1> & data, T2 & matrix);
198 std::shared_ptr<pluginlib::ClassLoader<kinematics_interface::KinematicsInterface>>
200 std::unique_ptr<kinematics_interface::KinematicsInterface> kinematics_;
203 Eigen::Matrix<double, 6, 1> wrench_world_;
212 Eigen::Vector3d cog_pos_;
215 Eigen::Vector3d end_effector_weight_;
218 control_msgs::msg::AdmittanceControllerState state_message_;
controller_interface::return_type configure(const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node, const size_t num_joint)
Configure admittance rule memory using number of joints.
Definition admittance_rule_impl.hpp:35
controller_interface::return_type update(const trajectory_msgs::msg::JointTrajectoryPoint ¤t_joint_state, const geometry_msgs::msg::Wrench &measured_wrench, const trajectory_msgs::msg::JointTrajectoryPoint &reference_joint_state, const rclcpp::Duration &period, trajectory_msgs::msg::JointTrajectoryPoint &desired_joint_states)
Definition admittance_rule_impl.hpp:172
void process_wrench_measurements(const geometry_msgs::msg::Wrench &measured_wrench, const Eigen::Matrix< double, 3, 3 > &sensor_world_rot, const Eigen::Matrix< double, 3, 3 > &cog_world_rot)
Definition admittance_rule_impl.hpp:316