00001
00002
00003
00004
00005
00006
00007
00008 #ifndef UTILS_H_
00009 #define UTILS_H_
00010
00011 #include <ros/ros.h>
00012 #include <geometry_msgs/PolygonStamped.h>
00013 #include <LinearMath/btTransform.h>
00014 #include <string>
00015
00016 namespace cart_state_estimator {
00017
00018 using std::string;
00019
00020 template<typename T>
00021 T getPrivateParam(const std::string& name, const T& default_val) {
00022 T val;
00023 ros::NodeHandle nh("~");
00024 nh.param(name, val, default_val);
00025 ROS_DEBUG_STREAM_NAMED ("init", "Set param " << name << " to value "
00026 << val << " (default was " << default_val << ")");
00027 return val;
00028 }
00029
00030 template<typename T>
00031 T getParam(const std::string& param, const std::string& ns = "~") {
00032 ros::NodeHandle nh(ns);
00033 ROS_DEBUG_STREAM("LOADING "<< param << " from " << nh.getNamespace());
00034 T val;
00035 bool found = nh.getParam(param, val);
00036 ROS_ASSERT_MSG(found, "Did not find param %s in %s", param.c_str(), nh.getNamespace().c_str());
00037 return val;
00038 }
00039
00040 btTransform readTransformParameter(const std::string& ns) {
00041 using XmlRpc::XmlRpcValue;
00042 XmlRpcValue position = getParam<XmlRpcValue> ("position", ns);
00043 XmlRpcValue orientation = getParam<XmlRpcValue> ("orientation", ns);
00044 ROS_ASSERT(position.getType() == XmlRpc::XmlRpcValue::TypeArray &&
00045 orientation.getType() == XmlRpc::XmlRpcValue::TypeArray &&
00046 position.size() == 3 && orientation.size() == 4);
00047 const double x = position[0];
00048 const double y = position[1];
00049 const double z = position[2];
00050 const btVector3 tr(x, y, z);
00051 const btQuaternion q(orientation[0], orientation[1], orientation[2],
00052 orientation[3]);
00053
00054 {
00055 btTransform trans(q, tr);
00056 geometry_msgs::Transform transform;
00057 tf::transformTFToMsg(trans, transform);
00058 ROS_DEBUG_STREAM ("read param from " << ns << " into " << transform);
00059 }
00060 return btTransform(q, tr);
00061 }
00062 }
00063 #endif