$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/hrl_kinematics/src/TestStability.cpp $ 00002 // SVN $Id: TestStability.cpp 3069 2012-08-21 14:26:59Z hornunga@informatik.uni-freiburg.de $ 00003 00004 /* 00005 * hrl_kinematics - a kinematics library for humanoid robots based on KDL 00006 * 00007 * Copyright 2011-2012 Armin Hornung, University of Freiburg 00008 * License: BSD 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above copyright 00016 * notice, this list of conditions and the following disclaimer in the 00017 * documentation and/or other materials provided with the distribution. 00018 * * Neither the name of the University of Freiburg nor the names of its 00019 * contributors may be used to endorse or promote products derived from 00020 * this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00023 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00024 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00025 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00026 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00027 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00028 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00029 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00030 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00031 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00035 #include "hrl_kinematics/TestStability.h" 00036 #include <pcl/surface/convex_hull.h> 00037 #include <pcl/point_types.h> 00038 00039 using robot_state_publisher::SegmentPair; 00040 using boost::shared_ptr; 00041 00042 namespace hrl_kinematics { 00043 00044 TestStability::TestStability() 00045 : Kinematics(), rfoot_mesh_link_name("RAnkleRoll_link") 00046 { 00047 00048 initFootPolygon(); 00049 } 00050 00051 TestStability::~TestStability() { 00052 00053 } 00054 00055 bool TestStability::isPoseStable(const std::map<std::string, double>& joint_positions, FootSupport support_mode){ 00056 tf::Vector3 normal(0.0, 0.0, 1.0); 00057 return isPoseStable(joint_positions, support_mode, normal); 00058 } 00059 00060 bool TestStability::isPoseStable(const std::map<std::string, double>& joint_positions, 00061 FootSupport support_mode, const tf::Vector3& normal_vector) 00062 { 00063 00064 tf::Vector3 upright_vector(0.0, 0.0, 1.0); 00065 double angle = acos(upright_vector.dot(normal_vector.normalized())); 00066 00067 tf::Quaternion q; 00068 if (std::abs(angle) < SIMD_EPSILON) 00069 q=tf::createIdentityQuaternion(); 00070 else{ 00071 tf::Vector3 axis = upright_vector.cross(normal_vector).normalized(); 00072 q = tf::Quaternion(axis, angle); 00073 } 00074 tf::Transform rotate_plane(q, tf::Vector3(0,0,0)); 00075 00076 tf::Point com; // center of mass in root frame 00077 double m; 00078 00079 // transforms from root to left and right foot: 00080 tf::Transform tf_right_foot, tf_left_foot; 00081 computeCOM(joint_positions, com, m, tf_right_foot, tf_left_foot); 00082 00083 tf::Transform tf_to_support; 00084 00085 if (support_mode == SUPPORT_SINGLE_LEFT){ 00086 support_polygon_ = foot_support_polygon_left_; 00087 tf_to_support_ = tf_left_foot; 00088 } else { // RIGHT or DOUBLE 00089 support_polygon_ = foot_support_polygon_right_; 00090 tf_to_support_ = tf_right_foot; 00091 00092 } 00093 00094 // rotate and project down 00095 for (unsigned i = 0; i < support_polygon_.size(); ++i){ 00096 support_polygon_[i] = rotate_plane * support_polygon_[i]; 00097 } 00098 00099 00100 // append left if double support: 00101 if (support_mode == SUPPORT_DOUBLE){ 00102 tf::Transform tf_right_to_left = tf_right_foot.inverseTimes(tf_left_foot); 00103 for (unsigned i = 0; i < foot_support_polygon_left_.size(); ++i){ 00104 support_polygon_.push_back(rotate_plane * tf_right_to_left * foot_support_polygon_left_[i]); 00105 } 00106 support_polygon_ = convexHull(support_polygon_); 00107 } 00108 if (support_polygon_.size() <= 2) 00109 return false; 00110 00111 // projected com in support frame, rotated around support plane: 00112 p_com_ = rotate_plane * tf_to_support_.inverse() * com; 00113 p_com_.setZ(0.0); 00114 00115 return pointInConvexHull(p_com_, support_polygon_); 00116 } 00117 00118 geometry_msgs::PolygonStamped TestStability::getSupportPolygon() const{ 00119 geometry_msgs::PolygonStamped footprint_poly; 00120 footprint_poly.header.frame_id = root_link_name_; 00121 footprint_poly.header.stamp = ros::Time::now(); 00122 for (unsigned i=0; i < support_polygon_.size(); ++i){ 00123 geometry_msgs::Point32 p; 00124 tf::Point tfP = tf_to_support_ * support_polygon_[i]; 00125 p.x = tfP.x(); 00126 p.y = tfP.y(); 00127 p.z = tfP.z(); 00128 footprint_poly.polygon.points.push_back(p); 00129 } 00130 00131 return footprint_poly; 00132 } 00133 00134 visualization_msgs::Marker TestStability::getCOMMarker() const{ 00135 00136 visualization_msgs::Marker com_marker; 00137 com_marker.header.stamp = ros::Time::now(); 00138 com_marker.header.frame_id = root_link_name_; 00139 com_marker.action = visualization_msgs::Marker::ADD; 00140 com_marker.type = visualization_msgs::Marker::SPHERE; 00141 tf::pointTFToMsg(tf_to_support_ * p_com_, com_marker.pose.position); 00142 tf::quaternionTFToMsg(tf_to_support_.getRotation(), com_marker.pose.orientation); 00143 com_marker.scale.x = 0.03; 00144 com_marker.scale.y = 0.03; 00145 com_marker.scale.z = 0.005; 00146 com_marker.color.a = 1.0; 00147 com_marker.color.g = 1.0; 00148 com_marker.color.r = 0.0; 00149 00150 00151 return com_marker; 00152 } 00153 00154 std::vector<tf::Point> TestStability::convexHull(const std::vector<tf::Point>& points) const{ 00155 std::vector<tf::Point> hull; 00156 00157 pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_points(new pcl::PointCloud<pcl::PointXYZ>); 00158 pcl::PointCloud<pcl::PointXYZ> chull_points; 00159 pcl::ConvexHull<pcl::PointXYZ> chull; 00160 00161 if (points.empty()){ 00162 ROS_ERROR("convexHull on empty set of points!"); 00163 return hull; 00164 } 00165 00166 for (unsigned i = 0; i < points.size(); ++i){ 00167 pcl_points->points.push_back(pcl::PointXYZ(points[i].x(), points[i].y(), 0.0)); 00168 } 00169 00170 #if ROS_VERSION_MINIMUM(1,8,0) // test for Fuerte (newer PCL) 00171 chull.setDimension(2); 00172 #else 00173 00174 #endif 00175 00176 chull.setInputCloud(pcl_points); 00177 std::vector<pcl::Vertices> polygons; 00178 chull.reconstruct(chull_points, polygons); 00179 00180 if (polygons.size() == 0){ 00181 ROS_ERROR("Convex hull polygons are empty"); 00182 return hull; 00183 } else if (polygons.size() > 1){ 00184 ROS_WARN("Convex hull polygons are larger than 1"); 00185 } 00186 00187 for (unsigned i = 0; i < polygons[0].vertices.size(); ++i){ 00188 int idx = polygons[0].vertices[i]; 00189 tf::Point p(chull_points.points[idx].x, 00190 chull_points.points[idx].y, 00191 chull_points.points[idx].z); 00192 hull.push_back(p); 00193 } 00194 00195 return hull; 00196 } 00197 00198 bool TestStability::pointInConvexHull(const tf::Point& point, const std::vector<tf::Point>& polygon) const{ 00199 assert(polygon.size() >=3); 00200 int positive_direction = 0; 00201 for (unsigned i = 0; i < polygon.size(); ++i){ 00202 int i2 = (i+1)% (polygon.size()); 00203 double dx = polygon[i2].getX() - polygon[i].getX(); 00204 double dy = polygon[i2].getY() - polygon[i].getY(); 00205 if (dx == 0.0 && dy == 0.0){ 00206 ROS_DEBUG("Skipping polygon connection [%d-%d] (identical points)", i, i2); 00207 continue; 00208 } 00209 double line_test = (point.y() - polygon[i].getY())*dx - (point.x() - polygon[i].getX())*dy; 00210 if (i == 0) 00211 positive_direction = (line_test > 0.0); 00212 ROS_DEBUG("Line test [%d-%d] from (%f,%f) to (%f,%f): %f", i, i2, polygon[i].getX(), polygon[i].getY(), 00213 polygon[i2].getX(), polygon[i2].getY(), line_test); 00214 if ((line_test > 0.0) != positive_direction) 00215 return false; 00216 00217 } 00218 00219 return true; 00220 } 00221 00222 void TestStability::initFootPolygon(){ 00223 // TODO: param? 00224 if (!loadFootPolygon()){ 00225 ROS_WARN("Could not load foot mesh, using default points"); 00226 00227 foot_support_polygon_right_.push_back(tf::Point(0.07f, 0.023f, 0.0)); 00228 foot_support_polygon_right_.push_back(tf::Point(0.07f, -0.03f, 0.0)); 00229 foot_support_polygon_right_.push_back(tf::Point(-0.03f, -0.03f, 0.0)); 00230 foot_support_polygon_right_.push_back(tf::Point(-0.03f, 0.02, 0.0)); 00231 } 00232 00233 00234 // mirror for left: 00235 foot_support_polygon_left_ = foot_support_polygon_right_; 00236 for (unsigned i=0; i < foot_support_polygon_left_.size(); ++i){ 00237 foot_support_polygon_left_[i] *= tf::Point(1.0, -1.0, 1.0); 00238 } 00239 // restore order of polygon 00240 foot_support_polygon_left_ = convexHull(foot_support_polygon_left_); 00241 00242 00243 00244 } 00245 00246 bool TestStability::loadFootPolygon(){ 00247 boost::shared_ptr<const urdf::Link> foot_link = urdf_model_.getLink(rfoot_mesh_link_name); 00248 assert(foot_link); 00249 boost::shared_ptr<const urdf::Geometry> geom; 00250 urdf::Pose geom_pose; 00251 if (foot_link->collision && foot_link->collision->geometry){ 00252 geom = foot_link->collision->geometry; 00253 geom_pose = foot_link->collision->origin; 00254 } else if (foot_link->visual && foot_link->visual->geometry){ 00255 geom = foot_link->visual->geometry; 00256 geom_pose = foot_link->visual->origin; 00257 } else{ 00258 ROS_ERROR_STREAM("No geometry for link "<< rfoot_mesh_link_name << " available"); 00259 return false; 00260 } 00261 00262 tf::Pose geom_origin = tf::Pose(btTransform(btQuaternion(geom_pose.rotation.x, geom_pose.rotation.y, geom_pose.rotation.z, geom_pose.rotation.w), 00263 btVector3(geom_pose.position.x, geom_pose.position.y, geom_pose.position.z))); 00264 00265 00266 if (geom->type != urdf::Geometry::MESH){ 00267 ROS_ERROR_STREAM("Geometry for link "<< rfoot_mesh_link_name << " is not a mesh"); 00268 return false; 00269 } else { 00270 shared_ptr<const urdf::Mesh> mesh = boost::dynamic_pointer_cast<const urdf::Mesh>(geom); 00271 00273 tf::Vector3 scale(mesh->scale.x, mesh->scale.y, mesh->scale.z); 00274 shapes::Mesh* shape_mesh = shapes::createMeshFromFilename(mesh->filename, &scale); 00275 size_t vertex_count = shape_mesh->vertexCount; 00276 00278 //const Eigen::Vector3d scale(mesh->scale.x, mesh->scale.y, mesh->scale.z); 00279 //shapes::Mesh* shape_mesh = shapes::createMeshFromFilename(mesh->filename, scale); 00280 //size_t vertex_count = shape_mesh->vertex_count; 00281 00282 for (unsigned int i = 0 ; i < vertex_count ; ++i) 00283 { 00284 unsigned int i3 = i * 3; 00285 00286 tf::Point p(shape_mesh->vertices[i3], shape_mesh->vertices[i3 + 1], shape_mesh->vertices[i3 + 2]); // proj down (z=0) 00287 tf::Point projectedP = geom_origin*p; 00288 projectedP.setZ(0.0); 00289 // transform into local foot frame: 00290 foot_support_polygon_right_.push_back(projectedP); 00291 } 00292 00293 foot_support_polygon_right_ = convexHull(foot_support_polygon_right_); 00294 } 00295 00296 ROS_INFO("Foot polygon loaded with %zu points", foot_support_polygon_right_.size()); 00297 00298 return true; 00299 00300 } 00301 00302 00303 } /* namespace hrl_kinematics */