Go to the documentation of this file.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 #ifndef HRL_KINEMATICS_TESTSTABILITY_H_
00034 #define HRL_KINEMATICS_TESTSTABILITY_H_
00035
00036 #include <hrl_kinematics/Kinematics.h>
00037
00038 #include <geometric_shapes/shape_operations.h>
00039 #include <geometry_msgs/PolygonStamped.h>
00040
00041 #include <vector>
00042
00043 namespace hrl_kinematics {
00044
00051 class TestStability : public Kinematics{
00052 public:
00053
00063 TestStability(std::string rfoot_mesh_link_name = "RAnkleRoll_link",
00064 std::string root_link_name = "base_link", std::string rfoot_link_name = "r_sole", std::string lfoot_link_name = "l_sole",
00065 const boost::shared_ptr<const urdf::ModelInterface>& urdf_model = boost::shared_ptr<const urdf::ModelInterface>(),
00066 double foot_polygon_scale = 1.0);
00067
00068 virtual ~TestStability();
00069
00078 bool isPoseStable(const std::map<std::string, double>& joint_positions, FootSupport support_mode);
00079
00089 bool isPoseStable(const std::map<std::string, double>& joint_positions, FootSupport support_mode, const tf::Vector3& normal_vector);
00090
00091 void scaleConvexHull(double scale);
00092
00094 geometry_msgs::PolygonStamped getSupportPolygon() const;
00096 visualization_msgs::Marker getCOMMarker() const;
00098 tf::Point getCOM() const {return p_com_;}
00099
00100 protected:
00101 void initFootPolygon(double scale=1.0);
00102 bool loadFootPolygon();
00103 std::vector<tf::Point> convexHull(const std::vector<tf::Point>& points) const;
00105 bool pointInConvexHull(const tf::Point& point, const std::vector<tf::Point>& polygon) const;
00107 std::vector<tf::Point> foot_support_polygon_right_;
00109 std::vector<tf::Point> foot_support_polygon_left_;
00110
00111 tf::Point p_com_;
00112 std::vector<tf::Point> support_polygon_;
00113 tf::Transform tf_to_support_;
00114 std::string rfoot_mesh_link_name_;
00115
00116
00117 double foot_polygon_scale_;
00118 };
00119
00120
00121 typedef boost::shared_ptr<TestStability> TestStabilityPtr;
00122 typedef boost::shared_ptr<const TestStability> TestStabilityConstPtr;
00123
00124 }
00125 #endif