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 <gravity_compensation/gravity_compensation_params.h>
00038 #include <sensor_msgs/Imu.h>
00039 #include <eigen3/Eigen/Core>
00040 #include <eigen3/Eigen/Geometry>
00041 #include <tf_conversions/tf_eigen.h>
00042 #include <tf/transform_datatypes.h>
00043 #include <tf/transform_broadcaster.h>
00044 #include <eigen_conversions/eigen_msg.h>
00045 #include <boost/thread.hpp>
00046 #include <std_srvs/Empty.h>
00047
00048
00049 class GravityCompensationNode
00050 {
00051 public:
00052 ros::NodeHandle n_;
00053
00054
00055 ros::Subscriber topicSub_imu_;
00056 ros::Subscriber topicSub_ft_raw_;
00057
00058 ros::Publisher topicPub_ft_zeroed_;
00059 ros::Publisher topicPub_ft_compensated_;
00060
00061 ros::ServiceServer calibrate_bias_srv_server_;
00062
00063 tf::TransformBroadcaster tf_br_;
00064
00065
00066 GravityCompensationNode()
00067 {
00068 n_ = ros::NodeHandle("~");
00069 m_g_comp_params = new GravityCompensationParams();
00070 m_g_comp = NULL;
00071 m_received_imu = false;
00072 m_calibrate_bias = false;
00073 m_calib_measurements = 0;
00074 m_ft_bias = Eigen::Matrix<double, 6, 1>::Zero();
00075
00076
00077 topicSub_imu_ = n_.subscribe("imu", 1, &GravityCompensationNode::topicCallback_imu, this);
00078 topicSub_ft_raw_ = n_.subscribe("ft_raw", 1, &GravityCompensationNode::topicCallback_ft_raw, this);
00079
00080
00081 calibrate_bias_srv_server_ = n_.advertiseService("calibrate_bias", &GravityCompensationNode::calibrateBiasSrvCallback, this);
00082
00084 std::string ns;
00085 if(n_.hasParam("ns"))
00086 {
00087 n_.getParam("ns", ns);
00088 topicPub_ft_zeroed_ = n_.advertise<geometry_msgs::WrenchStamped> (ns+std::string("/ft_zeroed"), 1);
00089 topicPub_ft_compensated_ = n_.advertise<geometry_msgs::WrenchStamped> (ns+std::string("/ft_compensated"), 1);
00090 }
00091
00092 else
00093 {
00094 topicPub_ft_zeroed_ = n_.advertise<geometry_msgs::WrenchStamped> ("ft_zeroed", 1);
00095 topicPub_ft_compensated_ = n_.advertise<geometry_msgs::WrenchStamped> ("ft_compensated", 1);
00096 }
00097 }
00098
00099 ~GravityCompensationNode()
00100 {
00101 delete m_g_comp;
00102 delete m_g_comp_params;
00103 }
00104
00105 bool getROSParameters()
00106 {
00108 XmlRpc::XmlRpcValue biasXmlRpc;
00109 Eigen::Matrix<double, 6, 1> bias;
00110 if (n_.hasParam("bias"))
00111 {
00112 n_.getParam("bias", biasXmlRpc);
00113 }
00114
00115 else
00116 {
00117 ROS_ERROR("Parameter 'bias' not set, shutting down node...");
00118 n_.shutdown();
00119 return false;
00120 }
00121
00122
00123 if(biasXmlRpc.size()!=6)
00124 {
00125 ROS_ERROR("Invalid F/T bias parameter size (should be size 6), shutting down node");
00126 n_.shutdown();
00127 return false;
00128 }
00129
00130 for (int i = 0; i < biasXmlRpc.size(); i++)
00131 {
00132 bias(i) = (double)biasXmlRpc[i];
00133 }
00134
00135
00136
00137 double gripper_mass;
00138 if (n_.hasParam("gripper_mass"))
00139 {
00140 n_.getParam("gripper_mass", gripper_mass);
00141 }
00142
00143 else
00144 {
00145 ROS_ERROR("Parameter 'gripper_mass' not available");
00146 n_.shutdown();
00147 return false;
00148 }
00149
00150 if(gripper_mass<0.0)
00151 {
00152 ROS_ERROR("Parameter 'gripper_mass' < 0");
00153 n_.shutdown();
00154 return false;
00155 }
00156
00157
00158
00159
00160 tf::StampedTransform gripper_com;
00161 std::string gripper_com_frame_id;
00162 if (n_.hasParam("gripper_com_frame_id"))
00163 {
00164 n_.getParam("gripper_com_frame_id", gripper_com_frame_id);
00165 }
00166
00167 else
00168 {
00169 ROS_ERROR("Parameter 'gripper_com_frame_id' not available");
00170 n_.shutdown();
00171 return false;
00172 }
00173
00174 gripper_com.frame_id_ = gripper_com_frame_id;
00175
00176
00177 std::string gripper_com_child_frame_id;
00178 if (n_.hasParam("gripper_com_child_frame_id"))
00179 {
00180 n_.getParam("gripper_com_child_frame_id", gripper_com_child_frame_id);
00181 }
00182
00183 else
00184 {
00185 ROS_ERROR("Parameter 'gripper_com_child_frame_id' not available");
00186 n_.shutdown();
00187 return false;
00188 }
00189
00190 gripper_com.child_frame_id_ = gripper_com_child_frame_id;
00191
00192
00193 Eigen::Matrix<double, 6, 1> gripper_com_pose;
00194 XmlRpc::XmlRpcValue gripper_com_pose_XmlRpc;
00195 if (n_.hasParam("gripper_com_pose"))
00196 {
00197 n_.getParam("gripper_com_pose", gripper_com_pose_XmlRpc);
00198 }
00199
00200 else
00201 {
00202 ROS_ERROR("Parameter 'gripper_com_pose' not set, shutting down node...");
00203 n_.shutdown();
00204 return false;
00205 }
00206
00207
00208 if(gripper_com_pose_XmlRpc.size()!=6)
00209 {
00210 ROS_ERROR("Invalid 'gripper_com_pose' parameter size (should be size 6), shutting down node");
00211 n_.shutdown();
00212 return false;
00213 }
00214
00215 for(unsigned int i=0; i<gripper_com_pose_XmlRpc.size(); i++)
00216 {
00217 gripper_com_pose(i) = gripper_com_pose_XmlRpc[i];
00218 }
00219
00220 tf::Vector3 p;
00221 tf::vectorEigenToTF(gripper_com_pose.topRows(3), p);
00222 tf::Quaternion q;
00223 q.setRPY((double)gripper_com_pose(3),
00224 (double)gripper_com_pose(4),
00225 (double)gripper_com_pose(5));
00226
00227 gripper_com = tf::StampedTransform(tf::Transform(q, p),
00228 ros::Time::now(),
00229 gripper_com_frame_id,
00230 gripper_com_child_frame_id);
00231
00232
00233
00234 n_.param("gripper_com_broadcast_frequency",
00235 m_gripper_com_broadcast_frequency, 100.0);
00236
00237 m_g_comp_params->setBias(bias);
00238 m_g_comp_params->setGripperMass(gripper_mass);
00239 m_g_comp_params->setGripperCOM(gripper_com);
00240
00241 m_g_comp = new GravityCompensation(m_g_comp_params);
00242 return true;
00243 }
00244
00245 void topicCallback_imu(const sensor_msgs::Imu::ConstPtr &msg)
00246 {
00247 m_imu = *msg;
00248 m_received_imu = true;
00249 }
00250
00251 void topicCallback_ft_raw(const geometry_msgs::WrenchStamped::ConstPtr &msg)
00252 {
00253 static int error_msg_count=0;
00254
00255 if(!m_received_imu)
00256 {
00257 return;
00258 }
00259
00260 if((ros::Time::now()-m_imu.header.stamp).toSec() > 0.1)
00261 {
00262 error_msg_count++;
00263 if(error_msg_count % 10==0)
00264 ROS_ERROR("Imu reading too old, not able to g-compensate ft measurement");
00265 return;
00266 }
00267
00268 geometry_msgs::WrenchStamped ft_zeroed;
00269 m_g_comp->Zero(*msg, ft_zeroed);
00270 topicPub_ft_zeroed_.publish(ft_zeroed);
00271
00272 geometry_msgs::WrenchStamped ft_compensated;
00273 m_g_comp->Compensate(ft_zeroed, m_imu, ft_compensated);
00274 topicPub_ft_compensated_.publish(ft_compensated);
00275
00276 if(m_calibrate_bias)
00277 {
00278 if(m_calib_measurements++<100)
00279 {
00280 m_ft_bias(0) += ft_compensated.wrench.force.x;
00281 m_ft_bias(1) += ft_compensated.wrench.force.y;
00282 m_ft_bias(2) += ft_compensated.wrench.force.z;
00283 m_ft_bias(3) += ft_compensated.wrench.torque.x;
00284 m_ft_bias(4) += ft_compensated.wrench.torque.y;
00285 m_ft_bias(5) += ft_compensated.wrench.torque.z;
00286 }
00287
00288
00289 if(m_calib_measurements == 100)
00290 {
00291 m_ft_bias = m_ft_bias/100;
00292 m_g_comp_params->setBias(m_g_comp_params->getBias() + m_ft_bias);
00293 m_ft_bias = Eigen::Matrix<double, 6, 1>::Zero();
00294 m_calibrate_bias = false;
00295 m_calib_measurements = 0;
00296 }
00297
00298 }
00299 }
00300
00301
00302 void publish_gripper_com_tf()
00303 {
00304 static ros::Rate gripper_com_broadcast_rate(m_gripper_com_broadcast_frequency);
00305 try
00306 {
00307 while(ros::ok())
00308 {
00309 tf::StampedTransform gripper_com = m_g_comp_params->getGripperCOM();
00310 gripper_com.stamp_ = ros::Time::now();
00311 tf_br_.sendTransform(gripper_com);
00312
00313 gripper_com_broadcast_rate.sleep();
00314 }
00315 }
00316
00317 catch(boost::thread_interrupted&)
00318 {
00319 return;
00320 }
00321 }
00322
00323
00324
00325 bool calibrateBiasSrvCallback(std_srvs::Empty::Request &req,
00326 std_srvs::Empty::Response &res)
00327 {
00328 m_calibrate_bias = true;
00329 return true;
00330 }
00331
00332 private:
00333
00334 GravityCompensationParams *m_g_comp_params;
00335 GravityCompensation *m_g_comp;
00336 sensor_msgs::Imu m_imu;
00337 bool m_received_imu;
00338 double m_gripper_com_broadcast_frequency;
00339
00340 bool m_calibrate_bias;
00341 unsigned int m_calib_measurements;
00342 Eigen::Matrix<double, 6, 1> m_ft_bias;
00343
00344 };
00345
00346 int main(int argc, char **argv)
00347 {
00348
00349 ros::init(argc, argv, "gravity_compensation");
00350 GravityCompensationNode g_comp_node;
00351
00352 if(!g_comp_node.getROSParameters())
00353 {
00354 ROS_ERROR("Error getting ROS parameters");
00355 return 0;
00356 }
00357
00358
00359 double loop_rate_;
00360 g_comp_node.n_.param("loop_rate", loop_rate_, 1000.0);
00361 ros::Rate loop_rate(loop_rate_);
00362
00363
00364 boost::thread t_tf(boost::bind(&GravityCompensationNode::publish_gripper_com_tf, &g_comp_node));
00365
00366
00367
00368
00369 while(ros::ok())
00370 {
00371 ros::spinOnce();
00372 loop_rate.sleep();
00373 }
00374
00375 t_tf.join();
00376
00377
00378 return 0;
00379 }