-
Notifications
You must be signed in to change notification settings - Fork 372
removed admittance_transforms_ struct and relevant functions as it acts just as a intermediary storage #1668
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 12 commits
fc3360b
f77ff24
abdf596
ad47704
4784892
4ffa105
48378a5
8d35bc0
9081e35
5962158
98dac98
63ed846
899722f
b3d26a7
a8af9ab
4c8ebf1
a48546b
55b07ac
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
@@ -108,9 +108,6 @@ controller_interface::return_type AdmittanceRule::reset(const size_t num_joints) | |||||||||||
// reset admittance state | ||||||||||||
admittance_state_ = AdmittanceState(num_joints); | ||||||||||||
|
||||||||||||
// reset transforms and rotations | ||||||||||||
admittance_transforms_ = AdmittanceTransforms(); | ||||||||||||
|
||||||||||||
// reset forces | ||||||||||||
wrench_world_.setZero(); | ||||||||||||
end_effector_weight_.setZero(); | ||||||||||||
|
@@ -144,33 +141,6 @@ void AdmittanceRule::apply_parameters_update() | |||||||||||
} | ||||||||||||
} | ||||||||||||
|
||||||||||||
bool AdmittanceRule::get_all_transforms( | ||||||||||||
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state, | ||||||||||||
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state) | ||||||||||||
{ | ||||||||||||
// get reference transforms | ||||||||||||
bool success = kinematics_->calculate_link_transform( | ||||||||||||
reference_joint_state.positions, parameters_.ft_sensor.frame.id, | ||||||||||||
admittance_transforms_.ref_base_ft_); | ||||||||||||
|
||||||||||||
// get transforms at current configuration | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.ft_sensor.frame.id, admittance_transforms_.base_ft_); | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.kinematics.tip, admittance_transforms_.base_tip_); | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.fixed_world_frame.frame.id, | ||||||||||||
admittance_transforms_.world_base_); | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.gravity_compensation.frame.id, | ||||||||||||
admittance_transforms_.base_cog_); | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.control.frame.id, | ||||||||||||
admittance_transforms_.base_control_); | ||||||||||||
|
||||||||||||
return success; | ||||||||||||
} | ||||||||||||
|
||||||||||||
// Update from reference joint states | ||||||||||||
controller_interface::return_type AdmittanceRule::update( | ||||||||||||
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state, | ||||||||||||
|
@@ -185,37 +155,52 @@ controller_interface::return_type AdmittanceRule::update( | |||||||||||
apply_parameters_update(); | ||||||||||||
} | ||||||||||||
|
||||||||||||
bool success = get_all_transforms(current_joint_state, reference_joint_state); | ||||||||||||
bool success = true; | ||||||||||||
|
||||||||||||
// Reusable transform variable | ||||||||||||
Eigen::Isometry3d tf; | ||||||||||||
|
||||||||||||
// --- FT sensor frame to base frame (translation + rotation) --- | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.ft_sensor.frame.id, tf); | ||||||||||||
admittance_state_.ref_trans_base_ft = tf; | ||||||||||||
|
||||||||||||
// apply filter and update wrench_world_ vector | ||||||||||||
Eigen::Matrix<double, 3, 3> rot_world_sensor = | ||||||||||||
admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_ft_.rotation(); | ||||||||||||
Eigen::Matrix<double, 3, 3> rot_world_cog = | ||||||||||||
admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_cog_.rotation(); | ||||||||||||
process_wrench_measurements(measured_wrench, rot_world_sensor, rot_world_cog); | ||||||||||||
// --- world frame to base frame (we only need the rotation) --- | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.fixed_world_frame.frame.id, tf); | ||||||||||||
Eigen::Matrix3d rot_world_base = tf.rotation(); | ||||||||||||
mgeethik marked this conversation as resolved.
Show resolved
Hide resolved
|
||||||||||||
|
||||||||||||
// transform wrench_world_ into base frame | ||||||||||||
// --- control/base frame to base frame (rotation only) --- | ||||||||||||
success &= kinematics_->calculate_link_transform( | ||||||||||||
current_joint_state.positions, parameters_.kinematics.base, tf); | ||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
Shouldn't it be this? ros2_controllers/admittance_controller/include/admittance_controller/admittance_rule_impl.hpp Lines 167 to 169 in 945a360
|
||||||||||||
admittance_state_.rot_base_control = tf.rotation(); | ||||||||||||
|
||||||||||||
// wrench processing (gravity + filter) in world | ||||||||||||
process_wrench_measurements( | ||||||||||||
measured_wrench, | ||||||||||||
// pass rotations into sensor and CoG: | ||||||||||||
rot_world_base * admittance_state_.ref_trans_base_ft.rotation(), | ||||||||||||
mgeethik marked this conversation as resolved.
Show resolved
Hide resolved
|
||||||||||||
rot_world_base * /* CoG rotation */ tf.rotation()); | ||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. In place of There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. true. I will change this. |
||||||||||||
|
||||||||||||
// transform filtered wrench into the robot base frame | ||||||||||||
// transform filtered wrench into the robot base frame | ||||||||||||
mgeethik marked this conversation as resolved.
Show resolved
Hide resolved
|
||||||||||||
admittance_state_.wrench_base.block<3, 1>(0, 0) = | ||||||||||||
admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(0, 0); | ||||||||||||
rot_world_base.transpose() * wrench_world_.block<3, 1>(0, 0); | ||||||||||||
admittance_state_.wrench_base.block<3, 1>(3, 0) = | ||||||||||||
admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(3, 0); | ||||||||||||
rot_world_base.transpose() * wrench_world_.block<3, 1>(3, 0); | ||||||||||||
|
||||||||||||
// Compute admittance control law | ||||||||||||
// populate current joint positions in the state | ||||||||||||
vec_to_eigen(current_joint_state.positions, admittance_state_.current_joint_pos); | ||||||||||||
admittance_state_.rot_base_control = admittance_transforms_.base_control_.rotation(); | ||||||||||||
admittance_state_.ref_trans_base_ft = admittance_transforms_.ref_base_ft_; | ||||||||||||
admittance_state_.ft_sensor_frame = parameters_.ft_sensor.frame.id; | ||||||||||||
saikishor marked this conversation as resolved.
Show resolved
Hide resolved
|
||||||||||||
success &= calculate_admittance_rule(admittance_state_, dt); | ||||||||||||
|
||||||||||||
// if a failure occurred during any kinematics interface calls, return an error and don't | ||||||||||||
// modify the desired reference | ||||||||||||
// compute admittance dynamics | ||||||||||||
success &= calculate_admittance_rule(admittance_state_, dt); | ||||||||||||
if (!success) | ||||||||||||
{ | ||||||||||||
desired_joint_state = reference_joint_state; | ||||||||||||
return controller_interface::return_type::ERROR; | ||||||||||||
} | ||||||||||||
|
||||||||||||
// update joint desired joint state | ||||||||||||
// Update final desired_joint_state using the computed transforms | ||||||||||||
for (size_t i = 0; i < num_joints_; ++i) | ||||||||||||
{ | ||||||||||||
auto idx = static_cast<Eigen::Index>(i); | ||||||||||||
|
Uh oh!
There was an error while loading. Please reload this page.