Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <ros/ros.h>
00036 #include <gravity_compensation/gravity_compensation.h>
00037 #include <geometry_msgs/PoseStamped.h>
00038 #include <tf_conversions/tf_eigen.h>
00039 #include <eigen3/Eigen/Core>
00040 #include <eigen_conversions/eigen_msg.h>
00041
00042
00043 GravityCompensation::GravityCompensation(GravityCompensationParams *g_comp_params)
00044 {
00045 m_g_comp_params = g_comp_params;
00046 m_tf_listener = new tf::TransformListener();
00047 }
00048
00049 GravityCompensation::~GravityCompensation()
00050 {
00051 delete m_tf_listener;
00052 }
00053
00054
00055 void GravityCompensation::Zero(const geometry_msgs::WrenchStamped &ft_raw,
00056 geometry_msgs::WrenchStamped &ft_zeroed)
00057 {
00058 Eigen::Matrix<double, 6, 1> bias = m_g_comp_params->getBias();
00059
00060 ft_zeroed = ft_raw;
00061 Eigen::Matrix<double, 6, 1> ft_raw_eigen;
00062 Eigen::Matrix<double, 6, 1> ft_zeroed_eigen;
00063 tf::wrenchMsgToEigen(ft_raw.wrench, ft_raw_eigen);
00064
00065 ft_zeroed_eigen = ft_raw_eigen - bias;
00066 tf::wrenchEigenToMsg(ft_zeroed_eigen, ft_zeroed.wrench);
00067 }
00068
00069
00070 bool GravityCompensation::Compensate(const geometry_msgs::WrenchStamped &ft_zeroed,
00071 const sensor_msgs::Imu &gravity,
00072 geometry_msgs::WrenchStamped &ft_compensated)
00073 {
00074
00075 geometry_msgs::Vector3Stamped g;
00076 g.vector = gravity.linear_acceleration;
00077 g.header = gravity.header;
00078 g.header.stamp = ros::Time();
00079
00080
00081 geometry_msgs::Vector3Stamped g_ft_frame;
00082 try
00083 {
00084 m_tf_listener->transformVector(ft_zeroed.header.frame_id, g, g_ft_frame);
00085 }
00086
00087 catch(tf::TransformException &ex)
00088 {
00089 ROS_ERROR("Error transforming gravity vector to ft sensor frame...");
00090 ROS_ERROR("%s.", ex.what());
00091 return false;
00092 }
00093
00094
00095 double gripper_mass = m_g_comp_params->getGripperMass();
00096 Eigen::Vector3d g_ft_frame_eigen;
00097 tf::vectorMsgToEigen(g_ft_frame.vector, g_ft_frame_eigen);
00098
00099
00100 Eigen::Matrix<double, 6, 1> gripper_wrench_eigen;
00101 gripper_wrench_eigen.topRows(3) = g_ft_frame_eigen*gripper_mass;
00102
00103
00104
00105 tf::StampedTransform gripper_com_tf = m_g_comp_params->getGripperCOM();
00106
00107
00108 geometry_msgs::PoseStamped gripper_com;
00109 tf::poseTFToMsg(gripper_com_tf, gripper_com.pose);
00110 gripper_com.header.stamp = ros::Time();
00111 gripper_com.header.frame_id = gripper_com_tf.frame_id_;
00112
00113
00114 geometry_msgs::PoseStamped ft_gripper_com;
00115
00116 try
00117 {
00118 m_tf_listener->transformPose(ft_zeroed.header.frame_id,
00119 gripper_com,
00120 ft_gripper_com);
00121 }
00122
00123 catch(tf::TransformException &ex)
00124 {
00125 ROS_ERROR("Error looking up transform between the gripper COM and the ft sensor frame");
00126 ROS_ERROR("%s.", ex.what());
00127 return false;
00128 }
00129
00130
00131 Eigen::Vector3d r;
00132 tf::pointMsgToEigen(ft_gripper_com.pose.position, r);
00133
00134
00135 Eigen::Vector3d gripper_force_eigen = gripper_wrench_eigen.topRows(3);
00136 Eigen::Vector3d gripper_torque_eigen = r.cross(gripper_force_eigen);
00137 gripper_wrench_eigen.bottomRows(3) = gripper_torque_eigen;
00138
00139
00140 Eigen::Matrix<double, 6, 1> ft_zeroed_eigen;
00141 tf::wrenchMsgToEigen(ft_zeroed.wrench, ft_zeroed_eigen);
00142 Eigen::Matrix<double, 6, 1> ft_compensated_eigen;
00143
00144 ft_compensated_eigen = ft_zeroed_eigen - gripper_wrench_eigen;
00145
00146 tf::wrenchEigenToMsg(ft_compensated_eigen, ft_compensated.wrench);
00147 ft_compensated.header = ft_zeroed.header;
00148
00149 return true;
00150 }