$search

hrl_kinematics::TestStability Class Reference

#include <TestStability.h>

Inheritance diagram for hrl_kinematics::TestStability:
Inheritance graph
[legend]

List of all members.

Public Member Functions

tf::Point getCOM () const
visualization_msgs::Marker getCOMMarker () const
geometry_msgs::PolygonStamped getSupportPolygon () const
bool isPoseStable (const std::map< std::string, double > &joint_positions, FootSupport support_mode, const tf::Vector3 &normal_vector)
bool isPoseStable (const std::map< std::string, double > &joint_positions, FootSupport support_mode)
 TestStability ()
virtual ~TestStability ()

Protected Member Functions

std::vector< tf::PointconvexHull (const std::vector< tf::Point > &points) const
void initFootPolygon ()
bool loadFootPolygon ()
bool pointInConvexHull (const tf::Point &point, const std::vector< tf::Point > &polygon) const
 tests if point is in polygon in 2D. point and polygon will be projected down to z=0 (z values will be ignored)

Protected Attributes

std::vector< tf::Pointfoot_support_polygon_left_
 Support polygon (x,y) for the left foot (mirrored from right).
std::vector< tf::Pointfoot_support_polygon_right_
 Support polygon (x,y) for the right foot.
tf::Point p_com_
std::string rfoot_mesh_link_name
std::vector< tf::Pointsupport_polygon_
tf::Transform tf_to_support_

Detailed Description

Class to test whether the kinematic state of a (humanoid) robot is statically stable, given its joint configuration, support mode and the normal vector of the supporting plane.

See also:
isPoseStable()

Definition at line 54 of file TestStability.h.


Constructor & Destructor Documentation

hrl_kinematics::TestStability::TestStability (  ) 

Definition at line 44 of file TestStability.cpp.

hrl_kinematics::TestStability::~TestStability (  )  [virtual]

Definition at line 51 of file TestStability.cpp.


Member Function Documentation

std::vector< tf::Point > hrl_kinematics::TestStability::convexHull ( const std::vector< tf::Point > &  points  )  const [protected]

Definition at line 154 of file TestStability.cpp.

tf::Point hrl_kinematics::TestStability::getCOM (  )  const [inline]
Returns:
the center of mass

Definition at line 85 of file TestStability.h.

visualization_msgs::Marker hrl_kinematics::TestStability::getCOMMarker (  )  const
Returns:
the center of mass (for visualization)

Definition at line 134 of file TestStability.cpp.

geometry_msgs::PolygonStamped hrl_kinematics::TestStability::getSupportPolygon (  )  const
Returns:
the support polygon (for visualization)

Definition at line 118 of file TestStability.cpp.

void hrl_kinematics::TestStability::initFootPolygon (  )  [protected]

Definition at line 222 of file TestStability.cpp.

bool hrl_kinematics::TestStability::isPoseStable ( const std::map< std::string, double > &  joint_positions,
FootSupport  support_mode,
const tf::Vector3 normal_vector 
)

Test stability based on center of mass and support polygon, assuming the robot is standing on an arbitrary supporting plane (given by normal_vector)

Parameters:
joint_positions given robot configuration
support_mode which foot the robot is standing on (SUPPORT_SINGLE_RIGHT, SUPPORT_SINGLE_LEFT, SUPPORT_DOUBLE)
normal_vector normal vector of the supporting plane
Returns:
true if pose is stable

Definition at line 60 of file TestStability.cpp.

bool hrl_kinematics::TestStability::isPoseStable ( const std::map< std::string, double > &  joint_positions,
FootSupport  support_mode 
)

Test stability based on center of mass and support polygon, assuming the robot is standing on a horizontal supporting plane.

Parameters:
joint_positions given robot configuration
support_mode which foot the robot is standing on (SUPPORT_SINGLE_RIGHT, SUPPORT_SINGLE_LEFT, SUPPORT_DOUBLE)
Returns:
true if pose is stable

Definition at line 55 of file TestStability.cpp.

bool hrl_kinematics::TestStability::loadFootPolygon (  )  [protected]

Definition at line 246 of file TestStability.cpp.

bool hrl_kinematics::TestStability::pointInConvexHull ( const tf::Point point,
const std::vector< tf::Point > &  polygon 
) const [protected]

tests if point is in polygon in 2D. point and polygon will be projected down to z=0 (z values will be ignored)

Definition at line 198 of file TestStability.cpp.


Member Data Documentation

Support polygon (x,y) for the left foot (mirrored from right).

Definition at line 96 of file TestStability.h.

Support polygon (x,y) for the right foot.

Definition at line 94 of file TestStability.h.

Definition at line 98 of file TestStability.h.

Definition at line 101 of file TestStability.h.

Definition at line 99 of file TestStability.h.

Definition at line 100 of file TestStability.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


hrl_kinematics
Author(s): Armin Hornung
autogenerated on Tue Mar 5 11:36:40 2013