gravity_compensation_node.cpp
Go to the documentation of this file.
1 /*
2  * gravity_compensation_node.cpp
3  *
4  * Created on: Nov 12, 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>
38 #include <sensor_msgs/Imu.h>
39 #include <eigen3/Eigen/Core>
40 #include <eigen3/Eigen/Geometry>
42 #include <tf/transform_datatypes.h>
45 #include <boost/thread.hpp>
46 #include <std_srvs/Empty.h>
47 
48 
50 {
51 public:
53 
54  // subscribe to accelerometer (imu) readings
57 
60 
62 
64 
65 
67  {
68  n_ = ros::NodeHandle("~");
70  m_g_comp = NULL;
71  m_received_imu = false;
72  m_calibrate_bias = false;
74  m_ft_bias = Eigen::Matrix<double, 6, 1>::Zero();
75 
76  // subscribe to accelerometer topic and raw F/T sensor topic
77  topicSub_imu_ = n_.subscribe("imu", 1, &GravityCompensationNode::topicCallback_imu, this);
78  topicSub_ft_raw_ = n_.subscribe("ft_raw", 1, &GravityCompensationNode::topicCallback_ft_raw, this);
79 
80  // bias calibration service
81  calibrate_bias_srv_server_ = n_.advertiseService("calibrate_bias", &GravityCompensationNode::calibrateBiasSrvCallback, this);
82 
84  std::string ns;
85  if(n_.hasParam("ns"))
86  {
87  n_.getParam("ns", ns);
88  topicPub_ft_zeroed_ = n_.advertise<geometry_msgs::WrenchStamped> (ns+std::string("/ft_zeroed"), 1);
89  topicPub_ft_compensated_ = n_.advertise<geometry_msgs::WrenchStamped> (ns+std::string("/ft_compensated"), 1);
90  }
91 
92  else
93  {
94  topicPub_ft_zeroed_ = n_.advertise<geometry_msgs::WrenchStamped> ("ft_zeroed", 1);
95  topicPub_ft_compensated_ = n_.advertise<geometry_msgs::WrenchStamped> ("ft_compensated", 1);
96  }
97  }
98 
100  {
101  delete m_g_comp;
102  delete m_g_comp_params;
103  }
104 
106  {
108  XmlRpc::XmlRpcValue biasXmlRpc;
109  Eigen::Matrix<double, 6, 1> bias;
110  if (n_.hasParam("bias"))
111  {
112  n_.getParam("bias", biasXmlRpc);
113  }
114 
115  else
116  {
117  ROS_ERROR("Parameter 'bias' not set, shutting down node...");
118  n_.shutdown();
119  return false;
120  }
121 
122 
123  if(biasXmlRpc.size()!=6)
124  {
125  ROS_ERROR("Invalid F/T bias parameter size (should be size 6), shutting down node");
126  n_.shutdown();
127  return false;
128  }
129 
130  for (int i = 0; i < biasXmlRpc.size(); i++)
131  {
132  bias(i) = (double)biasXmlRpc[i];
133  }
134 
135 
136  // get the mass of the gripper
137  double gripper_mass;
138  if (n_.hasParam("gripper_mass"))
139  {
140  n_.getParam("gripper_mass", gripper_mass);
141  }
142 
143  else
144  {
145  ROS_ERROR("Parameter 'gripper_mass' not available");
146  n_.shutdown();
147  return false;
148  }
149 
150  if(gripper_mass<0.0)
151  {
152  ROS_ERROR("Parameter 'gripper_mass' < 0");
153  n_.shutdown();
154  return false;
155  }
156 
157  // get the pose of the COM of the gripper
158  // we assume that it is fixed with respect to FT sensor frame
159  // first get the frame ID
160  tf::StampedTransform gripper_com;
161  std::string gripper_com_frame_id;
162  if (n_.hasParam("gripper_com_frame_id"))
163  {
164  n_.getParam("gripper_com_frame_id", gripper_com_frame_id);
165  }
166 
167  else
168  {
169  ROS_ERROR("Parameter 'gripper_com_frame_id' not available");
170  n_.shutdown();
171  return false;
172  }
173 
174  gripper_com.frame_id_ = gripper_com_frame_id;
175 
176  // now get the CHILD frame ID
177  std::string gripper_com_child_frame_id;
178  if (n_.hasParam("gripper_com_child_frame_id"))
179  {
180  n_.getParam("gripper_com_child_frame_id", gripper_com_child_frame_id);
181  }
182 
183  else
184  {
185  ROS_ERROR("Parameter 'gripper_com_child_frame_id' not available");
186  n_.shutdown();
187  return false;
188  }
189 
190  gripper_com.child_frame_id_ = gripper_com_child_frame_id;
191 
192  // now get the actual gripper COM pose
193  Eigen::Matrix<double, 6, 1> gripper_com_pose;
194  XmlRpc::XmlRpcValue gripper_com_pose_XmlRpc;
195  if (n_.hasParam("gripper_com_pose"))
196  {
197  n_.getParam("gripper_com_pose", gripper_com_pose_XmlRpc);
198  }
199 
200  else
201  {
202  ROS_ERROR("Parameter 'gripper_com_pose' not set, shutting down node...");
203  n_.shutdown();
204  return false;
205  }
206 
207 
208  if(gripper_com_pose_XmlRpc.size()!=6)
209  {
210  ROS_ERROR("Invalid 'gripper_com_pose' parameter size (should be size 6), shutting down node");
211  n_.shutdown();
212  return false;
213  }
214 
215  for(unsigned int i=0; i<gripper_com_pose_XmlRpc.size(); i++)
216  {
217  gripper_com_pose(i) = gripper_com_pose_XmlRpc[i];
218  }
219 
220  tf::Vector3 p;
221  tf::vectorEigenToTF(gripper_com_pose.topRows(3), p);
222  tf::Quaternion q;
223  q.setRPY((double)gripper_com_pose(3),
224  (double)gripper_com_pose(4),
225  (double)gripper_com_pose(5));
226 
227  gripper_com = tf::StampedTransform(tf::Transform(q, p),
228  ros::Time::now(),
229  gripper_com_frame_id,
230  gripper_com_child_frame_id);
231 
232  // get the publish frequency for the gripper
233  // center of mass tf
234  n_.param("gripper_com_broadcast_frequency",
236 
237  m_g_comp_params->setBias(bias);
238  m_g_comp_params->setGripperMass(gripper_mass);
239  m_g_comp_params->setGripperCOM(gripper_com);
240 
242  return true;
243  }
244 
245  void topicCallback_imu(const sensor_msgs::Imu::ConstPtr &msg)
246  {
247  m_imu = *msg;
248  m_received_imu = true;
249  }
250 
251  void topicCallback_ft_raw(const geometry_msgs::WrenchStamped::ConstPtr &msg)
252  {
253  static int error_msg_count=0;
254 
255  if(!m_received_imu)
256  {
257  ROS_ERROR("No Imu reading");
258  return;
259  }
260 
261  if((ros::Time::now()-m_imu.header.stamp).toSec() > 0.1)
262  {
263  error_msg_count++;
264  if(error_msg_count % 10==0)
265  ROS_ERROR("Imu reading too old, not able to g-compensate ft measurement");
266  return;
267  }
268 
269  geometry_msgs::WrenchStamped ft_zeroed;
270  m_g_comp->Zero(*msg, ft_zeroed);
271  topicPub_ft_zeroed_.publish(ft_zeroed);
272 
273  geometry_msgs::WrenchStamped ft_compensated;
274  m_g_comp->Compensate(ft_zeroed, m_imu, ft_compensated);
275  topicPub_ft_compensated_.publish(ft_compensated);
276 
277  if(m_calibrate_bias)
278  {
279  if(m_calib_measurements < 100)
280  {
281  m_ft_bias(0) += ft_compensated.wrench.force.x;
282  m_ft_bias(1) += ft_compensated.wrench.force.y;
283  m_ft_bias(2) += ft_compensated.wrench.force.z;
284  m_ft_bias(3) += ft_compensated.wrench.torque.x;
285  m_ft_bias(4) += ft_compensated.wrench.torque.y;
286  m_ft_bias(5) += ft_compensated.wrench.torque.z;
288  }
289  else
290  {
291  // set the new bias
294  m_ft_bias = Eigen::Matrix<double, 6, 1>::Zero();
295  m_calibrate_bias = false;
297  }
298  }
299  }
300 
301  // thread function for publishing the gripper center of mass transform
303  {
304  static ros::Rate gripper_com_broadcast_rate(m_gripper_com_broadcast_frequency);
305  try
306  {
307  while(ros::ok())
308  {
310  gripper_com.stamp_ = ros::Time::now();
311  tf_br_.sendTransform(gripper_com);
312 
313  gripper_com_broadcast_rate.sleep();
314  }
315  }
316 
317  catch(boost::thread_interrupted&)
318  {
319  return;
320  }
321  }
322 
323  // only to be called when the robot is standing still and
324  // while not holding anything / applying any forces
325  bool calibrateBiasSrvCallback(std_srvs::Empty::Request &req,
326  std_srvs::Empty::Response &res)
327  {
328  m_calibrate_bias = true;
329  return true;
330  }
331 
332 private:
333 
336  sensor_msgs::Imu m_imu;
339 
341  unsigned int m_calib_measurements;
342  Eigen::Matrix<double, 6, 1> m_ft_bias;
343 
344 };
345 
346 int main(int argc, char **argv)
347 {
348 
349  ros::init(argc, argv, "gravity_compensation");
350  GravityCompensationNode g_comp_node;
351 
352  if(!g_comp_node.getROSParameters())
353  {
354  ROS_ERROR("Error getting ROS parameters");
355  return 0;
356  }
357 
358  // loop frequency
359  double loop_rate_;
360  g_comp_node.n_.param("loop_rate", loop_rate_, 1000.0);
361  ros::Rate loop_rate(loop_rate_);
362 
363  // add a thread for publishing the gripper COM transform frame
364  boost::thread t_tf(boost::bind(&GravityCompensationNode::publish_gripper_com_tf, &g_comp_node));
365 
366 // ros::AsyncSpinner s(2);
367 // s.start();
368 
369  while(ros::ok())
370  {
371  ros::spinOnce();
372  loop_rate.sleep();
373  }
374 
375  t_tf.join();
376 
377 
378  return 0;
379 }
void setGripperMass(const double &gripper_mass)
int main(int argc, char **argv)
void topicCallback_ft_raw(const geometry_msgs::WrenchStamped::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setBias(const Eigen::Matrix< double, 6, 1 > &bias)
int size() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::ServiceServer calibrate_bias_srv_server_
void vectorEigenToTF(const Eigen::Vector3d &e, tf::Vector3 &t)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Eigen::Matrix< double, 6, 1 > m_ft_bias
std::string child_frame_id_
bool calibrateBiasSrvCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
bool Compensate(const geometry_msgs::WrenchStamped &ft_zeroed, const sensor_msgs::Imu &gravity, geometry_msgs::WrenchStamped &ft_compensated)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
void topicCallback_imu(const sensor_msgs::Imu::ConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
void setGripperCOM(const tf::StampedTransform &gripper_com)
Eigen::Matrix< double, 6, 1 > getBias()
bool getParam(const std::string &key, std::string &s) const
void Zero(const geometry_msgs::WrenchStamped &ft_raw, geometry_msgs::WrenchStamped &ft_zeroed)
static Time now()
bool hasParam(const std::string &key) const
tf::TransformBroadcaster tf_br_
ROSCPP_DECL void spinOnce()
GravityCompensationParams * m_g_comp_params
#define ROS_ERROR(...)
std::string frame_id_


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