39 admittance_velocity.setZero();
40 admittance_acceleration.setZero();
45 selected_axes.setZero();
46 auto idx =
static_cast<Eigen::Index
>(num_joints);
47 current_joint_pos = Eigen::VectorXd::Zero(idx);
48 joint_pos = Eigen::VectorXd::Zero(idx);
49 joint_vel = Eigen::VectorXd::Zero(idx);
50 joint_acc = Eigen::VectorXd::Zero(idx);
53 Eigen::VectorXd current_joint_pos;
54 Eigen::VectorXd joint_pos;
55 Eigen::VectorXd joint_vel;
56 Eigen::VectorXd joint_acc;
57 Eigen::Matrix<double, 6, 1> damping;
58 Eigen::Matrix<double, 6, 1> mass;
59 Eigen::Matrix<double, 6, 1> mass_inv;
60 Eigen::Matrix<double, 6, 1> selected_axes;
61 Eigen::Matrix<double, 6, 1> stiffness;
62 Eigen::Matrix<double, 6, 1> wrench_base;
63 Eigen::Matrix<double, 6, 1> admittance_acceleration;
64 Eigen::Matrix<double, 6, 1> admittance_velocity;
65 Eigen::Isometry3d admittance_position;
66 Eigen::Matrix<double, 3, 3> rot_base_control;
67 Eigen::Isometry3d ref_trans_base_ft;
68 std::string ft_sensor_frame;
75 const std::shared_ptr<admittance_controller::ParamListener> & parameter_handler)
77 parameter_handler_ = parameter_handler;
78 parameters_ = parameter_handler_->get_params();
79 num_joints_ = parameters_.joints.size();
85 controller_interface::return_type
configure(
86 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node,
const size_t num_joint,
87 const std::string & robot_description);
90 controller_interface::return_type
reset(
const size_t num_joints);
114 controller_interface::return_type
update(
115 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
116 const geometry_msgs::msg::Wrench & measured_wrench,
117 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
118 const rclcpp::Duration & period,
119 trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);
131 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
132 admittance_controller::Params parameters_;
153 const geometry_msgs::msg::Wrench & measured_wrench,
154 const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
155 const Eigen::Matrix<double, 3, 3> & cog_world_rot);
157 template <
typename T1,
typename T2>
158 void vec_to_eigen(
const std::vector<T1> & data, T2 & matrix);
164 std::shared_ptr<pluginlib::ClassLoader<kinematics_interface::KinematicsInterface>>
166 std::unique_ptr<kinematics_interface::KinematicsInterface> kinematics_;
169 Eigen::Matrix<double, 6, 1> wrench_world_;
175 Eigen::Vector3d cog_pos_;
178 Eigen::Vector3d end_effector_weight_;
181 control_msgs::msg::AdmittanceControllerState state_message_;
controller_interface::return_type configure(const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node, const size_t num_joint, const std::string &robot_description)
Configure admittance rule memory using number of joints.
Definition admittance_rule_impl.hpp:37
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:141
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:309