Public Member Functions | |
void | jointStateCb (const sensor_msgs::JointStateConstPtr &state) |
TestStabilityNode (Kinematics::FootSupport support=Kinematics::SUPPORT_DOUBLE) | |
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 46 of file test_stability.cpp.
hrl_kinematics::TestStabilityNode::TestStabilityNode | ( | Kinematics::FootSupport | support = Kinematics::SUPPORT_DOUBLE | ) |
Definition at line 60 of file test_stability.cpp.
hrl_kinematics::TestStabilityNode::~TestStabilityNode | ( | ) | [virtual] |
Definition at line 71 of file test_stability.cpp.
void hrl_kinematics::TestStabilityNode::jointStateCb | ( | const sensor_msgs::JointStateConstPtr & | state | ) |
Definition at line 76 of file test_stability.cpp.
Definition at line 54 of file test_stability.cpp.
Definition at line 53 of file test_stability.cpp.
Definition at line 55 of file test_stability.cpp.
Definition at line 57 of file test_stability.cpp.
Definition at line 55 of file test_stability.cpp.
Definition at line 56 of file test_stability.cpp.
Definition at line 55 of file test_stability.cpp.