Public Member Functions | |
void | initialize () |
void | jointStateCb (const sensor_msgs::JointStateConstPtr &state) |
TestStabilityNode (Kinematics::FootSupport support=Kinematics::SUPPORT_DOUBLE) | |
TestStabilityNode (ros::NodeHandle _nh_, TestStability _test_stability_, Kinematics::FootSupport support) | |
virtual | ~TestStabilityNode () |
Protected Attributes | |
ros::Subscriber | joint_state_sub_ |
ros::NodeHandle | nh_ |
ros::Publisher | pcom_pub_ |
Kinematics::FootSupport | support_mode_ |
ros::Publisher | support_polygon_pub_ |
TestStability | test_stability_ |
ros::Publisher | visualization_pub_ |
Simple node to use the Kinematics and TestStability classes. Based on the current kinematic state, it will output wheather the state is stable and publish some visualization
Definition at line 43 of file test_stability.cpp.
hrl_kinematics::TestStabilityNode::TestStabilityNode | ( | Kinematics::FootSupport | support = Kinematics::SUPPORT_DOUBLE | ) |
Definition at line 65 of file test_stability.cpp.
hrl_kinematics::TestStabilityNode::TestStabilityNode | ( | ros::NodeHandle | _nh_, |
TestStability | _test_stability_, | ||
Kinematics::FootSupport | support | ||
) |
Definition at line 59 of file test_stability.cpp.
hrl_kinematics::TestStabilityNode::~TestStabilityNode | ( | ) | [virtual] |
Definition at line 71 of file test_stability.cpp.
Definition at line 75 of file test_stability.cpp.
void hrl_kinematics::TestStabilityNode::jointStateCb | ( | const sensor_msgs::JointStateConstPtr & | state | ) |
Definition at line 85 of file test_stability.cpp.
Definition at line 53 of file test_stability.cpp.
Definition at line 52 of file test_stability.cpp.
Definition at line 54 of file test_stability.cpp.
Definition at line 56 of file test_stability.cpp.
Definition at line 54 of file test_stability.cpp.
Definition at line 55 of file test_stability.cpp.
Definition at line 54 of file test_stability.cpp.