Skip to content

Commit

Permalink
Change the e-skin calibration parameters based on new data.
Browse files Browse the repository at this point in the history
  • Loading branch information
mmurooka committed May 24, 2024
1 parent 8a2ddaf commit 8640f23
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions src/TactileSensorPlugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,8 +185,8 @@ void TactileSensorPlugin::before(mc_control::MCGlobalController & gc)
tf::pointMsgToEigen(cellMsg.pose.position, position);
tf::quaternionMsgToEigen(cellMsg.pose.orientation, quat);
Eigen::Vector3d normal = -1.0 * quat.toRotationMatrix().col(2);
// \todo Calibrate force measurements from e-Skin
Eigen::Vector3d force = 10.0 * (cellMsg.forces[0] + cellMsg.forces[1] + cellMsg.forces[2]) * normal;
// Edit here to change the conversion calibration from e-Skin tactile measurements to force
Eigen::Vector3d force = 35.0 * (cellMsg.forces[0] + cellMsg.forces[1] + cellMsg.forces[2]) * normal;
Eigen::Vector3d moment = position.cross(force);
wrench.force() += force;
wrench.moment() += moment;
Expand Down

0 comments on commit 8640f23

Please sign in to comment.