00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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(1.0);
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) < FLT_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;
00077 double m;
00078
00079
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 {
00089 support_polygon_ = foot_support_polygon_right_;
00090 tf_to_support_ = tf_right_foot;
00091
00092 }
00093
00094
00095 for (unsigned i = 0; i < support_polygon_.size(); ++i){
00096 support_polygon_[i] = rotate_plane * support_polygon_[i];
00097 }
00098
00099
00100 if (support_mode == SUPPORT_DOUBLE){
00101 tf::Transform tf_right_to_left = tf_right_foot.inverseTimes(tf_left_foot);
00102 for (unsigned i = 0; i < foot_support_polygon_left_.size(); ++i){
00103 support_polygon_.push_back(rotate_plane * tf_right_to_left * foot_support_polygon_left_[i]);
00104 }
00105 support_polygon_ = convexHull(support_polygon_);
00106 }
00107 if (support_polygon_.size() <= 2)
00108 return false;
00109
00110
00111 p_com_ = rotate_plane * tf_to_support_.inverse() * com;
00112 p_com_.setZ(0.0);
00113
00114 return pointInConvexHull(p_com_, support_polygon_);
00115 }
00116
00117 geometry_msgs::PolygonStamped TestStability::getSupportPolygon() const{
00118 geometry_msgs::PolygonStamped footprint_poly;
00119 footprint_poly.header.frame_id = root_link_name_;
00120 footprint_poly.header.stamp = ros::Time::now();
00121 for (unsigned i=0; i < support_polygon_.size(); ++i){
00122 geometry_msgs::Point32 p;
00123 tf::Point tfP = tf_to_support_ * support_polygon_[i];
00124 p.x = tfP.x();
00125 p.y = tfP.y();
00126 p.z = tfP.z();
00127 footprint_poly.polygon.points.push_back(p);
00128 }
00129
00130 return footprint_poly;
00131 }
00132
00133 visualization_msgs::Marker TestStability::getCOMMarker() const{
00134
00135 visualization_msgs::Marker com_marker;
00136 com_marker.header.stamp = ros::Time::now();
00137 com_marker.header.frame_id = root_link_name_;
00138 com_marker.action = visualization_msgs::Marker::ADD;
00139 com_marker.type = visualization_msgs::Marker::SPHERE;
00140 tf::pointTFToMsg(tf_to_support_ * p_com_, com_marker.pose.position);
00141 tf::quaternionTFToMsg(tf_to_support_.getRotation(), com_marker.pose.orientation);
00142 com_marker.scale.x = 0.03;
00143 com_marker.scale.y = 0.03;
00144 com_marker.scale.z = 0.005;
00145 com_marker.color.a = 1.0;
00146 com_marker.color.g = 1.0;
00147 com_marker.color.r = 0.0;
00148
00149
00150 return com_marker;
00151 }
00152
00153 std::vector<tf::Point> TestStability::convexHull(const std::vector<tf::Point>& points) const{
00154 std::vector<tf::Point> hull;
00155
00156 pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_points(new pcl::PointCloud<pcl::PointXYZ>);
00157 pcl::PointCloud<pcl::PointXYZ> chull_points;
00158 pcl::ConvexHull<pcl::PointXYZ> chull;
00159
00160 if (points.empty()){
00161 ROS_ERROR("convexHull on empty set of points!");
00162 return hull;
00163 }
00164
00165 for (unsigned i = 0; i < points.size(); ++i){
00166 pcl_points->points.push_back(pcl::PointXYZ(points[i].x(), points[i].y(), 0.0));
00167 }
00168
00169 #if ROS_VERSION_MINIMUM(1,8,0) // test for Fuerte (newer PCL)
00170 chull.setDimension(2);
00171 #else
00172
00173 #endif
00174
00175 chull.setInputCloud(pcl_points);
00176 std::vector<pcl::Vertices> polygons;
00177 chull.reconstruct(chull_points, polygons);
00178
00179 if (polygons.size() == 0){
00180 ROS_ERROR("Convex hull polygons are empty");
00181 return hull;
00182 } else if (polygons.size() > 1){
00183 ROS_WARN("Convex hull polygons are larger than 1");
00184 }
00185
00186 for (unsigned i = 0; i < polygons[0].vertices.size(); ++i){
00187 int idx = polygons[0].vertices[i];
00188 tf::Point p(chull_points.points[idx].x,
00189 chull_points.points[idx].y,
00190 chull_points.points[idx].z);
00191 hull.push_back(p);
00192 }
00193
00194 return hull;
00195 }
00196
00197 bool TestStability::pointInConvexHull(const tf::Point& point, const std::vector<tf::Point>& polygon) const{
00198 assert(polygon.size() >=3);
00199 int positive_direction = 0;
00200 for (unsigned i = 0; i < polygon.size(); ++i){
00201 int i2 = (i+1)% (polygon.size());
00202 double dx = polygon[i2].getX() - polygon[i].getX();
00203 double dy = polygon[i2].getY() - polygon[i].getY();
00204 if (dx == 0.0 && dy == 0.0){
00205 ROS_DEBUG("Skipping polygon connection [%d-%d] (identical points)", i, i2);
00206 continue;
00207 }
00208 double line_test = (point.y() - polygon[i].getY())*dx - (point.x() - polygon[i].getX())*dy;
00209 if (i == 0)
00210 positive_direction = (line_test > 0.0);
00211 ROS_DEBUG("Line test [%d-%d] from (%f,%f) to (%f,%f): %f", i, i2, polygon[i].getX(), polygon[i].getY(),
00212 polygon[i2].getX(), polygon[i2].getY(), line_test);
00213 if ((line_test > 0.0) != positive_direction)
00214 return false;
00215
00216 }
00217
00218 return true;
00219 }
00220
00221 void TestStability::initFootPolygon(double scale_convex_hull){
00222
00223
00224 scale_convex_hull_ = scale_convex_hull;
00225
00226
00227 if (!loadFootPolygon()){
00228 ROS_WARN("Could not load foot mesh, using default points");
00229
00230 foot_support_polygon_right_.push_back(tf::Point(0.07f, 0.023f, 0.0));
00231 foot_support_polygon_right_.push_back(tf::Point(0.07f, -0.03f, 0.0));
00232 foot_support_polygon_right_.push_back(tf::Point(-0.03f, -0.03f, 0.0));
00233 foot_support_polygon_right_.push_back(tf::Point(-0.03f, 0.02, 0.0));
00234 }
00235
00236
00237 foot_support_polygon_left_ = foot_support_polygon_right_;
00238 for (unsigned i=0; i < foot_support_polygon_left_.size(); ++i){
00239 foot_support_polygon_left_[i] *= tf::Point(1.0, -1.0, 1.0);
00240 }
00241
00242
00243 foot_support_polygon_left_ = convexHull(foot_support_polygon_left_);
00244 }
00245
00246
00247 bool TestStability::loadFootPolygon(){
00248 boost::shared_ptr<const urdf::Link> foot_link = urdf_model_.getLink(rfoot_mesh_link_name);
00249 assert(foot_link);
00250 boost::shared_ptr<const urdf::Geometry> geom;
00251 urdf::Pose geom_pose;
00252 if (foot_link->collision && foot_link->collision->geometry){
00253 geom = foot_link->collision->geometry;
00254 geom_pose = foot_link->collision->origin;
00255 } else if (foot_link->visual && foot_link->visual->geometry){
00256 geom = foot_link->visual->geometry;
00257 geom_pose = foot_link->visual->origin;
00258 } else{
00259 ROS_ERROR_STREAM("No geometry for link "<< rfoot_mesh_link_name << " available");
00260 return false;
00261 }
00262
00263 tf::Pose geom_origin = tf::Pose(tf::Transform(tf::Quaternion(geom_pose.rotation.x, geom_pose.rotation.y, geom_pose.rotation.z, geom_pose.rotation.w),
00264 tf::Vector3(geom_pose.position.x, geom_pose.position.y, geom_pose.position.z)));
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
00279
00280
00281
00282
00283 std::vector<tf::Point> foot_SP_right;
00284 for (unsigned int i = 0 ; i < vertex_count ; ++i)
00285 {
00286 unsigned int i3 = i * 3;
00287
00288 tf::Point p(shape_mesh->vertices[i3], shape_mesh->vertices[i3 + 1], shape_mesh->vertices[i3 + 2]);
00289 tf::Point projectedP = geom_origin*p;
00290 projectedP.setZ(0.0);
00291
00292
00293 foot_SP_right.push_back(projectedP);
00294 }
00295
00296
00297 float sum_x_coord = 0.0;
00298 float sum_y_coord = 0.0;
00299 tf::Point r_foot_center;
00300 for (unsigned int i = 0 ; i < foot_SP_right.size(); ++i)
00301 {
00302 sum_x_coord = sum_x_coord + foot_SP_right[i].x();
00303 sum_y_coord = sum_y_coord + foot_SP_right[i].y();
00304 }
00305
00306 r_foot_center.setX(sum_x_coord/foot_SP_right.size());
00307 r_foot_center.setY(sum_y_coord/foot_SP_right.size());
00308
00309
00310 std::vector<tf::Point> foot_SP_right_center;
00311 tf::Point foot_point;
00312 for (unsigned int i = 0 ; i < foot_SP_right.size(); ++i){
00313
00314 foot_point.setX( (foot_SP_right[i].x() - r_foot_center.x()) * scale_convex_hull_ );
00315 foot_point.setY( (foot_SP_right[i].y() - r_foot_center.y()) * scale_convex_hull_ );
00316 foot_SP_right_center.push_back(foot_point);
00317 }
00318
00319
00320 std::vector<tf::Point> scaled_SP_right;
00321 for (unsigned int i = 0 ; i < foot_SP_right_center.size() ; ++i){
00322
00323 foot_point.setX( foot_SP_right_center[i].x() + r_foot_center.x() ) ;
00324 foot_point.setY( foot_SP_right_center[i].y() + r_foot_center.y() ) ;
00325 scaled_SP_right.push_back(foot_point);
00326 }
00327
00328
00329
00330
00331
00332
00333
00334
00335
00336 foot_support_polygon_right_ = convexHull(scaled_SP_right);
00337
00338 }
00339
00340 ROS_INFO("Foot polygon loaded with %zu points", foot_support_polygon_right_.size());
00341
00342 return true;
00343
00344 }
00345
00346
00347
00348 void TestStability::scaleConvexHull(double scaling_factor)
00349 {
00350
00351 initFootPolygon(scaling_factor);
00352 }
00353
00354
00355
00356 }