38 #include <sensor_msgs/Imu.h> 39 #include <eigen3/Eigen/Core> 40 #include <eigen3/Eigen/Geometry> 45 #include <boost/thread.hpp> 46 #include <std_srvs/Empty.h> 74 m_ft_bias = Eigen::Matrix<double, 6, 1>::Zero();
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);
94 topicPub_ft_zeroed_ = n_.
advertise<geometry_msgs::WrenchStamped> (
"ft_zeroed", 1);
95 topicPub_ft_compensated_ = n_.
advertise<geometry_msgs::WrenchStamped> (
"ft_compensated", 1);
109 Eigen::Matrix<double, 6, 1> bias;
117 ROS_ERROR(
"Parameter 'bias' not set, shutting down node...");
123 if(biasXmlRpc.
size()!=6)
125 ROS_ERROR(
"Invalid F/T bias parameter size (should be size 6), shutting down node");
130 for (
int i = 0; i < biasXmlRpc.
size(); i++)
132 bias(i) = (double)biasXmlRpc[i];
140 n_.
getParam(
"gripper_mass", gripper_mass);
145 ROS_ERROR(
"Parameter 'gripper_mass' not available");
152 ROS_ERROR(
"Parameter 'gripper_mass' < 0");
161 std::string gripper_com_frame_id;
162 if (n_.
hasParam(
"gripper_com_frame_id"))
164 n_.
getParam(
"gripper_com_frame_id", gripper_com_frame_id);
169 ROS_ERROR(
"Parameter 'gripper_com_frame_id' not available");
174 gripper_com.
frame_id_ = gripper_com_frame_id;
177 std::string gripper_com_child_frame_id;
178 if (n_.
hasParam(
"gripper_com_child_frame_id"))
180 n_.
getParam(
"gripper_com_child_frame_id", gripper_com_child_frame_id);
185 ROS_ERROR(
"Parameter 'gripper_com_child_frame_id' not available");
193 Eigen::Matrix<double, 6, 1> gripper_com_pose;
195 if (n_.
hasParam(
"gripper_com_pose"))
197 n_.
getParam(
"gripper_com_pose", gripper_com_pose_XmlRpc);
202 ROS_ERROR(
"Parameter 'gripper_com_pose' not set, shutting down node...");
208 if(gripper_com_pose_XmlRpc.
size()!=6)
210 ROS_ERROR(
"Invalid 'gripper_com_pose' parameter size (should be size 6), shutting down node");
215 for(
unsigned int i=0; i<gripper_com_pose_XmlRpc.
size(); i++)
217 gripper_com_pose(i) = gripper_com_pose_XmlRpc[i];
223 q.
setRPY((
double)gripper_com_pose(3),
224 (
double)gripper_com_pose(4),
225 (
double)gripper_com_pose(5));
229 gripper_com_frame_id,
230 gripper_com_child_frame_id);
234 n_.
param(
"gripper_com_broadcast_frequency",
253 static int error_msg_count=0;
264 if(error_msg_count % 10==0)
265 ROS_ERROR(
"Imu reading too old, not able to g-compensate ft measurement");
269 geometry_msgs::WrenchStamped ft_zeroed;
271 topicPub_ft_zeroed_.
publish(ft_zeroed);
273 geometry_msgs::WrenchStamped ft_compensated;
275 topicPub_ft_compensated_.
publish(ft_compensated);
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;
294 m_ft_bias = Eigen::Matrix<double, 6, 1>::Zero();
313 gripper_com_broadcast_rate.
sleep();
317 catch(boost::thread_interrupted&)
326 std_srvs::Empty::Response &res)
346 int main(
int argc,
char **argv)
349 ros::init(argc, argv,
"gravity_compensation");
354 ROS_ERROR(
"Error getting ROS parameters");
360 g_comp_node.
n_.
param(
"loop_rate", loop_rate_, 1000.0);
GravityCompensation * m_g_comp
void setGripperMass(const double &gripper_mass)
int main(int argc, char **argv)
GravityCompensationNode()
~GravityCompensationNode()
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)
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)
ros::Publisher topicPub_ft_zeroed_
Eigen::Matrix< double, 6, 1 > m_ft_bias
double m_gripper_com_broadcast_frequency
unsigned int m_calib_measurements
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 ¶m_name, T ¶m_val, const T &default_val) const
ros::Subscriber topicSub_ft_raw_
ros::Publisher topicPub_ft_compensated_
void topicCallback_imu(const sensor_msgs::Imu::ConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::StampedTransform getGripperCOM()
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)
void publish_gripper_com_tf()
bool hasParam(const std::string &key) const
tf::TransformBroadcaster tf_br_
ROSCPP_DECL void spinOnce()
GravityCompensationParams * m_g_comp_params
ros::Subscriber topicSub_imu_