gravity_compensation.cpp
Go to the documentation of this file.
1 /*
2  * gravity_compensation.cpp
3  *
4  * Created on: Nov 11, 2013
5  * Authors: Francisco Viña
6  * fevb <at> kth.se
7  */
8 
9 /* Copyright (c) 2013, Francisco Viña, CVAP, KTH
10  All rights reserved.
11 
12  Redistribution and use in source and binary forms, with or without
13  modification, are permitted provided that the following conditions are met:
14  * Redistributions of source code must retain the above copyright
15  notice, this list of conditions and the following disclaimer.
16  * Redistributions in binary form must reproduce the above copyright
17  notice, this list of conditions and the following disclaimer in the
18  documentation and/or other materials provided with the distribution.
19  * Neither the name of KTH nor the
20  names of its contributors may be used to endorse or promote products
21  derived from this software without specific prior written permission.
22 
23  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
24  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
25  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
26  DISCLAIMED. IN NO EVENT SHALL KTH BE LIABLE FOR ANY
27  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
28  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
30  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
32  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 */
34 
35 #include <ros/ros.h>
37 #include <geometry_msgs/PoseStamped.h>
39 #include <eigen3/Eigen/Core>
41 
42 
44 {
45  m_g_comp_params = g_comp_params;
47 }
48 
50 {
51  delete m_tf_listener;
52 }
53 
54 
55 void GravityCompensation::Zero(const geometry_msgs::WrenchStamped &ft_raw,
56  geometry_msgs::WrenchStamped &ft_zeroed)
57 {
58  Eigen::Matrix<double, 6, 1> bias = m_g_comp_params->getBias();
59 
60  ft_zeroed = ft_raw;
61  Eigen::Matrix<double, 6, 1> ft_raw_eigen;
62  Eigen::Matrix<double, 6, 1> ft_zeroed_eigen;
63  tf::wrenchMsgToEigen(ft_raw.wrench, ft_raw_eigen);
64 
65  ft_zeroed_eigen = ft_raw_eigen - bias;
66  tf::wrenchEigenToMsg(ft_zeroed_eigen, ft_zeroed.wrench);
67 }
68 
69 
70 bool GravityCompensation::Compensate(const geometry_msgs::WrenchStamped &ft_zeroed,
71  const sensor_msgs::Imu &gravity,
72  geometry_msgs::WrenchStamped &ft_compensated)
73 {
74 
75  geometry_msgs::Vector3Stamped g;
76  g.vector.x = -gravity.linear_acceleration.x; // IMU will measure gravity in the opposite direction from F/T sensor, check https://github.com/kth-ros-pkg/force_torque_tools/pull/18
77  g.vector.y = -gravity.linear_acceleration.y;
78  g.vector.z = -gravity.linear_acceleration.z;
79  g.header = gravity.header;
80  g.header.stamp = ros::Time();
81 
82  // convert the accelerometer reading to the F/T sensor frame
83  geometry_msgs::Vector3Stamped g_ft_frame;
84  try
85  {
86  m_tf_listener->transformVector(ft_zeroed.header.frame_id, g, g_ft_frame);
87  }
88 
89  catch(tf::TransformException &ex)
90  {
91  ROS_ERROR("Error transforming gravity vector to ft sensor frame...");
92  ROS_ERROR("%s.", ex.what());
93  return false;
94  }
95 
96 
97  double gripper_mass = m_g_comp_params->getGripperMass();
98  Eigen::Vector3d g_ft_frame_eigen;
99  tf::vectorMsgToEigen(g_ft_frame.vector, g_ft_frame_eigen);
100 
101 
102  Eigen::Matrix<double, 6, 1> gripper_wrench_eigen;
103  gripper_wrench_eigen.topRows(3) = g_ft_frame_eigen*gripper_mass;
104 
105 
106  // grab the gripper_com
108 
109  // convert the gripper_com to geometry_msgs::PoseStamped
110  geometry_msgs::PoseStamped gripper_com;
111  tf::poseTFToMsg(gripper_com_tf, gripper_com.pose);
112  gripper_com.header.stamp = ros::Time();
113  gripper_com.header.frame_id = gripper_com_tf.frame_id_;
114 
115  // make sure the gripper COM is expressed with respect to the F/T sensor frame
116  geometry_msgs::PoseStamped ft_gripper_com;
117 
118  try
119  {
120  m_tf_listener->transformPose(ft_zeroed.header.frame_id,
121  gripper_com,
122  ft_gripper_com);
123  }
124 
125  catch(tf::TransformException &ex)
126  {
127  ROS_ERROR("Error looking up transform between the gripper COM and the ft sensor frame");
128  ROS_ERROR("%s.", ex.what());
129  return false;
130  }
131 
132  // convert to Eigen to do cross product to compute the torque
133  Eigen::Vector3d r;
134  tf::pointMsgToEigen(ft_gripper_com.pose.position, r);
135 
136  // compute torque generated by weight of the gripper
137  Eigen::Vector3d gripper_force_eigen = gripper_wrench_eigen.topRows(3);
138  Eigen::Vector3d gripper_torque_eigen = r.cross(gripper_force_eigen);
139  gripper_wrench_eigen.bottomRows(3) = gripper_torque_eigen;
140 
141  // compensate force & torque
142  Eigen::Matrix<double, 6, 1> ft_zeroed_eigen;
143  tf::wrenchMsgToEigen(ft_zeroed.wrench, ft_zeroed_eigen);
144  Eigen::Matrix<double, 6, 1> ft_compensated_eigen;
145 
146  ft_compensated_eigen = ft_zeroed_eigen - gripper_wrench_eigen;
147 
148  tf::wrenchEigenToMsg(ft_compensated_eigen, ft_compensated.wrench);
149  ft_compensated.header = ft_zeroed.header;
150 
151  return true;
152 }
tf::TransformListener * m_tf_listener
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
GravityCompensation(GravityCompensationParams *g_comp_params)
bool Compensate(const geometry_msgs::WrenchStamped &ft_zeroed, const sensor_msgs::Imu &gravity, geometry_msgs::WrenchStamped &ft_compensated)
void wrenchMsgToEigen(const geometry_msgs::Wrench &m, Eigen::Matrix< double, 6, 1 > &e)
void pointMsgToEigen(const geometry_msgs::Point &m, Eigen::Vector3d &e)
GravityCompensationParams * m_g_comp_params
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
void wrenchEigenToMsg(const Eigen::Matrix< double, 6, 1 > &e, geometry_msgs::Wrench &m)
Eigen::Matrix< double, 6, 1 > getBias()
void Zero(const geometry_msgs::WrenchStamped &ft_raw, geometry_msgs::WrenchStamped &ft_zeroed)
void transformVector(const std::string &target_frame, const geometry_msgs::Vector3Stamped &stamped_in, geometry_msgs::Vector3Stamped &stamped_out) const
#define ROS_ERROR(...)
std::string frame_id_


gravity_compensation
Author(s): Francisco Vina
autogenerated on Mon May 10 2021 02:27:45