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