Skip to content

Commit

Permalink
advancing in creation of gravity_compensation .. still have to finish…
Browse files Browse the repository at this point in the history
… the node
  • Loading branch information
fevb committed Nov 12, 2013
1 parent a66c991 commit a88f93b
Show file tree
Hide file tree
Showing 4 changed files with 300 additions and 45 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@

#include <vector>
#include <tf/transform_datatypes.h>
#include <eigen3/Eigen/Core>

class GravityCompensationParams
{
Expand All @@ -49,30 +50,31 @@ class GravityCompensationParams

// set/get the F/T sensor bias
// used to 'zero' the F/T sensor signal
bool setBias(const std::vector<double> &bias);
std::vector<double> getBias();
void setBias(const Eigen::Matrix<double, 6, 1> &bias);
Eigen::Matrix<double, 6, 1> getBias();

// set/get the mass of the gripper
// used for compensating gravity
bool setGripperMass(const double &gripper_mass);
void setGripperMass(const double &gripper_mass);
double getGripperMass();

// set/get the COM of the gripper
// used for compensating gravity
// compensation assumes that the gripper COM is fixed
// Used for compensating gravity.
// Compensation assumes that the gripper COM is fixed
// with respect to the F/T sensor
bool setGripperCOM(const tf::StampedTransform &gripper_com);
void setGripperCOM(const tf::StampedTransform &gripper_com);
tf::StampedTransform getGripperCOM();

private:

// 6 element bias vector
std::vector<double> m_bias;
Eigen::Matrix<double, 6, 1> m_bias;

// the mass of the gripper
double m_gripper_mass;

// location of the center of mass of the gripper
// (fixed) pose of the center of mass of the gripper
// with respect to the F/T sensor
tf::StampedTransform m_gripper_com;

};
Expand Down
34 changes: 18 additions & 16 deletions gravity_compensation/src/gravity_compensation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,16 +55,15 @@ GravityCompensation::~GravityCompensation()
void GravityCompensation::Zero(const geometry_msgs::WrenchStamped &ft_raw,
geometry_msgs::WrenchStamped &ft_zeroed)
{
std::vector<double> bias = m_g_comp_params->getBias();
Eigen::Matrix<double, 6, 1> bias = m_g_comp_params->getBias();

ft_zeroed = ft_raw;
ft_zeroed.wrench.force.x = ft_raw.wrench.force.x-bias[0];
ft_zeroed.wrench.force.y = ft_raw.wrench.force.y-bias[1];
ft_zeroed.wrench.force.z = ft_raw.wrench.force.z-bias[2];
ft_zeroed.wrench.torque.x = ft_raw.wrench.torque.x-bias[3];
ft_zeroed.wrench.torque.y = ft_raw.wrench.torque.y-bias[4];
ft_zeroed.wrench.torque.z = ft_raw.wrench.torque.z-bias[5];
Eigen::Matrix<double, 6, 1> ft_raw_eigen;
Eigen::Matrix<double, 6, 1> ft_zeroed_eigen;
tf::wrenchMsgToEigen(ft_raw.wrench, ft_raw_eigen);

ft_zeroed_eigen = ft_raw_eigen - bias;
tf::wrenchEigenToMsg(ft_zeroed_eigen, ft_zeroed.wrench);
}


Expand Down Expand Up @@ -102,20 +101,23 @@ bool GravityCompensation::Compensate(const geometry_msgs::WrenchStamped &ft_zero
gripper_wrench_eigen.topRows(3) = g_ft_frame_eigen*gripper_mass;


tf::StampedTransform gripper_com = m_g_comp_params->getGripperCOM();
geometry_msgs::PoseStamped gripper_com_pose;
tf::poseTFToMsg(gripper_com, gripper_com_pose.pose);
gripper_com_pose.header.frame_id = gripper_com.child_frame_id_;
gripper_com_pose.header.stamp = ros::Time();
// grab the gripper_com
tf::StampedTransform gripper_com_tf = m_g_comp_params->getGripperCOM();

// convert the gripper_com to geometry_msgs::PoseStamped
geometry_msgs::PoseStamped gripper_com;
tf::poseTFToMsg(gripper_com_tf, gripper_com.pose);
gripper_com.header.stamp = ros::Time();
gripper_com.header.frame_id = gripper_com_tf.frame_id_;

// make sure the gripper COM is expressed with respect to the F/T sensor frame
geometry_msgs::PoseStamped ft_gripper_com_pose;
geometry_msgs::PoseStamped ft_gripper_com;

try
{
m_tf_listener->transformPose(ft_zeroed.header.frame_id,
gripper_com_pose,
ft_gripper_com_pose);
gripper_com,
ft_gripper_com);
}

catch(tf::TransformException &ex)
Expand All @@ -127,7 +129,7 @@ bool GravityCompensation::Compensate(const geometry_msgs::WrenchStamped &ft_zero

// convert to Eigen to do cross product to compute the torque
Eigen::Vector3d r;
tf::pointMsgToEigen(ft_gripper_com_pose.pose.position, r);
tf::pointMsgToEigen(ft_gripper_com.pose.position, r);

// compute torque generated by weight of the gripper
Eigen::Vector3d gripper_torque_eigen = r.cross(gripper_wrench_eigen.topRows(3));
Expand Down
266 changes: 266 additions & 0 deletions gravity_compensation/src/gravity_compensation_node.cpp
Original file line number Diff line number Diff line change
@@ -1 +1,267 @@
/*
* gravity_compensation.cpp
*
* Created on: Nov 12, 2013
* Authors: Francisco Viña
* fevb <at> kth.se
*/

/* Copyright (c) 2013, Francisco Viña, CVAP, KTH
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of KTH nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL KTH BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/

#include <ros/ros.h>
#include <gravity_compensation/gravity_compensation.h>
#include <gravity_compensation/gravity_compensation_params.h>
#include <sensor_msgs/Imu.h>
#include <eigen3/Eigen/Core>
#include <eigen3/Eigen/Geometry>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>
#include <eigen_conversions/eigen_msg.h>


class GravityCompensationNode
{
public:
ros::NodeHandle n_;

// subscribe to accelerometer (imu) readings
ros::Subscriber topicSub_imu_;
ros::Subscriber topicSub_ft_raw_;

ros::Publisher topicPub_ft_zeroed_;
ros::Publisher topicPub_ft_compensated_;

tf::TransformBroadcaster tf_br_;


GravityCompensationNode()
{
n_ = ros::NodeHandle("~");
m_g_comp_params = new GravityCompensationParams();
m_g_comp = NULL;

// subscribe to accelerometer topic and raw F/T sensor topic
topicSub_imu_ = n_.subscribe("imu", 1, &GravityCompensationNode::topicCallback_imu, this);
topicSub_ft_raw_ = n_.subscribe("ft_raw", 1, &GravityCompensationNode::topicCallback_ft_raw, this);

/// implementation of topics to publish
topicPub_ft_zeroed_ = n_.advertise<geometry_msgs::WrenchStamped> ("ft_zeroed", 1);
topicPub_ft_compensated_ = n_.advertise<geometry_msgs::WrenchStamped> ("ft_compensated", 1);
}

~GravityCompensationNode()
{
delete m_g_comp;
delete m_g_comp_params;
}

bool getROSParameters()
{
/// Get F/T sensor bias
XmlRpc::XmlRpcValue biasXmlRpc;
Eigen::Matrix<double, 6, 1> bias;
if (n_.hasParam("bias"))
{
n_.getParam("bias", biasXmlRpc);
}

else
{
ROS_ERROR("Parameter 'bias' not set, shutting down node...");
n_.shutdown();
return false;
}


if(biasXmlRpc.size()!=6)
{
ROS_ERROR("Invalid F/T bias parameter size (should be size 6), shutting down node");
n_.shutdown();
return false;
}

for (int i = 0; i < biasXmlRpc.size(); i++)
{
bias(i) = (double)biasXmlRpc[i];
}


// get the mass of the gripper
double gripper_mass;
if (n_.hasParam("gripper_mass"))
{
n_.getParam("gripper_mass", gripper_mass);
}

else
{
ROS_ERROR("Parameter 'gripper_mass' not available");
n_.shutdown();
return false;
}

if(gripper_mass<0.0)
{
ROS_ERROR("Parameter 'gripper_mass' < 0");
n_.shutdown();
return false;
}

// get the pose of the COM of the gripper
// we assume that it is fixed with respect to FT sensor frame
// first get the frame ID
tf::StampedTransform gripper_com;
std::string gripper_com_frame_id;
if (n_.hasParam("gripper_com_frame_id"))
{
n_.getParam("gripper_com_frame_id", gripper_com_frame_id);
}

else
{
ROS_ERROR("Parameter 'gripper_com_frame_id' not available");
n_.shutdown();
return false;
}

gripper_com.frame_id_ = gripper_com_frame_id;

// now get the CHILD frame ID
std::string gripper_com_child_frame_id;
if (n_.hasParam("gripper_com_child_frame_id"))
{
n_.getParam("gripper_com_child_frame_id", gripper_com_child_frame_id);
}

else
{
ROS_ERROR("Parameter 'gripper_com_child_frame_id' not available");
n_.shutdown();
return false;
}

gripper_com.child_frame_id_ = gripper_com_child_frame_id;

// now get the actual gripper COM pose
Eigen::Matrix<double, 6, 1> gripper_com_pose;
XmlRpc::XmlRpcValue gripper_com_pose_XmlRpc;
if (n_.hasParam("gripper_com_pose"))
{
n_.getParam("gripper_com_pose", gripper_com_pose_XmlRpc);
}

else
{
ROS_ERROR("Parameter 'gripper_com_pose' not set, shutting down node...");
n_.shutdown();
return false;
}


if(gripper_com_pose_XmlRpc.size()!=6)
{
ROS_ERROR("Invalid 'gripper_com_pose' parameter size (should be size 6), shutting down node");
n_.shutdown();
return false;
}

for(unsigned int i=0; i<gripper_com_pose_XmlRpc.size(); i++)
{
gripper_com_pose(i) = gripper_com_pose_XmlRpc[i];
}

tf::Vector3 p;
tf::vectorEigenToTF(gripper_com_pose.topRows(3), p);
tf::Quaternion q;
q.setRPY((double)gripper_com_pose(3),
(double)gripper_com_pose(4),
(double)gripper_com_pose(5));

gripper_com.Transform(q, p);


m_g_comp_params->setBias(bias);
m_g_comp_params->setGripperMass(gripper_mass);
m_g_comp_params->setGripperCOM(gripper_com);

m_g_comp = new GravityCompensation(m_g_comp_params);
return true;
}

void topicCallback_imu(const sensor_msgs::Imu::ConstPtr &msg)
{
m_imu = *msg;
}

void topicCallback_ft_raw(const geometry_msgs::WrenchStamped::ConstPtr &msg)
{
geometry_msgs::WrenchStamped ft_zeroed;
m_g_comp->Zero(*msg, ft_zeroed);
topicPub_ft_zeroed_.publish(ft_zeroed);


geometry_msgs::WrenchStamped ft_compensated;
m_g_comp->Compensate(ft_zeroed, m_imu, ft_compensated);
topicPub_ft_compensated_.publish(ft_compensated);
}

void publish_gripper_com_tf()
{
tf::StampedTransform gripper_com = m_g_comp_params->getGripperCOM();
gripper_com.stamp_ = ros::Time::now();
tf_br_.sendTransform(gripper_com);
}

private:

GravityCompensationParams *m_g_comp_params;
GravityCompensation *m_g_comp;
sensor_msgs::Imu m_imu;

};

int main(int argc, char **argv)
{

ros::init(argc, argv, "gravity_compensation");
GravityCompensationNode g_comp_node;

// tf broadcasting frequency
double tf_broad_frequency;

// loop frequency
double loop_frequency;

g_comp_node.n_.param("tf_broadcast_frequency", tf_broad_frequency, 100.0);
g_comp_node.n_.param("loop_frequency", loop_frequency, 1000.0);


// todo: add two threads, one for reading ft and imu and one for publish tf

return 0;
}

Loading

0 comments on commit a88f93b

Please sign in to comment.