37 #include <geometry_msgs/PoseStamped.h> 39 #include <eigen3/Eigen/Core> 56 geometry_msgs::WrenchStamped &ft_zeroed)
61 Eigen::Matrix<double, 6, 1> ft_raw_eigen;
62 Eigen::Matrix<double, 6, 1> ft_zeroed_eigen;
65 ft_zeroed_eigen = ft_raw_eigen - bias;
71 const sensor_msgs::Imu &gravity,
72 geometry_msgs::WrenchStamped &ft_compensated)
75 geometry_msgs::Vector3Stamped g;
76 g.vector.x = -gravity.linear_acceleration.x;
77 g.vector.y = -gravity.linear_acceleration.y;
78 g.vector.z = -gravity.linear_acceleration.z;
79 g.header = gravity.header;
83 geometry_msgs::Vector3Stamped g_ft_frame;
91 ROS_ERROR(
"Error transforming gravity vector to ft sensor frame...");
98 Eigen::Vector3d g_ft_frame_eigen;
102 Eigen::Matrix<double, 6, 1> gripper_wrench_eigen;
103 gripper_wrench_eigen.topRows(3) = g_ft_frame_eigen*gripper_mass;
110 geometry_msgs::PoseStamped gripper_com;
113 gripper_com.header.frame_id = gripper_com_tf.
frame_id_;
116 geometry_msgs::PoseStamped ft_gripper_com;
127 ROS_ERROR(
"Error looking up transform between the gripper COM and the ft sensor frame");
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;
142 Eigen::Matrix<double, 6, 1> ft_zeroed_eigen;
144 Eigen::Matrix<double, 6, 1> ft_compensated_eigen;
146 ft_compensated_eigen = ft_zeroed_eigen - gripper_wrench_eigen;
149 ft_compensated.header = ft_zeroed.header;
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)
tf::StampedTransform getGripperCOM()
GravityCompensationParams * m_g_comp_params
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
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)
virtual ~GravityCompensation()