$search
00001 /* 00002 * util.h 00003 * 00004 * Created on: Aug 6, 2010 00005 * Author: jscholz 00006 */ 00007 00008 #ifndef UTIL_H_ 00009 #define UTIL_H_ 00010 00011 #include <ros/ros.h> 00012 #include <LinearMath/btTransform.h> 00013 #include <geometry_msgs/PolygonStamped.h> 00014 #include <string> 00015 #include <boost/format.hpp> 00016 00017 /********* 00018 * UTILS * 00019 *********/ 00020 namespace manipulation_transforms_util { 00021 template<typename T> 00022 T getParam(const ros::NodeHandle &nh, const std::string ¶m) { 00023 T val; 00024 bool found = nh.getParam(param, val); 00025 ROS_ASSERT_MSG(found, "Did not find param %s in %s", param.c_str(), nh.getNamespace().c_str()); 00026 00027 return val; 00028 } 00029 00030 btTransform readTransformParameter(const ros::NodeHandle &nh, 00031 const std::string &name) { 00032 using XmlRpc::XmlRpcValue; 00033 XmlRpcValue position = getParam<XmlRpcValue> (nh, name + "/position"); 00034 XmlRpcValue orientation = getParam<XmlRpcValue> (nh, name + "/orientation"); 00035 ROS_ASSERT_MSG(position.getType() == XmlRpc::XmlRpcValue::TypeArray && 00036 orientation.getType() == XmlRpc::XmlRpcValue::TypeArray && 00037 position.size() == 3 && orientation.size() == 4, 00038 "Expected parameter type array with position and orientation for %s", (nh.getNamespace() + "/" + name).c_str()); 00039 const double x = position[0]; 00040 const double y = position[1]; 00041 const double z = position[2]; 00042 const btVector3 tr(x, y, z); 00043 const btQuaternion q(orientation[0], orientation[1], orientation[2], 00044 orientation[3]); 00045 00046 { // debugging 00047 btTransform trans(q, tr); 00048 geometry_msgs::Transform transform; 00049 tf::transformTFToMsg(trans, transform); 00050 ROS_DEBUG_STREAM ("read transform param from " << nh.getNamespace() << " into transform: " << std::endl << transform); 00051 } 00052 return btTransform(q, tr); 00053 } 00054 00055 std::string btTransform_to_string(const btTransform &t) { 00056 btVector3 v = t.getOrigin(); 00057 btQuaternion r = t.getRotation(); 00058 return (boost::format("((%.3f, %.3f, %.3f), (%.3f, %.3f, %.3f, %.3f))") 00059 % v.x() % v.y() % v.z() % r.x() % r.y() % r.z() % r.w()).str(); 00060 } 00061 00062 std::string btVector3_to_string(const btVector3 &v) { 00063 return (boost::format("% .3f, % .3f, % .3f") % v.x() % v.y() % v.z()).str(); 00064 } 00065 00066 std::string btMatrix3x3_to_string(const btMatrix3x3 &m) { 00067 return (btVector3_to_string(m.getRow(0)) + "\n" + btVector3_to_string( 00068 m.getRow(1)) + "\n" + btVector3_to_string(m.getRow(2)) + "\n"); 00069 } 00070 } // namespace manipulation_transforms_util 00071 00072 #endif /* UTIL_H_ */