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
00034
00035 #include <hrl_kinematics/TestStability.h>
00036 #include <ros/ros.h>
00037
00038
00039 namespace hrl_kinematics {
00040
00046 class TestStabilityNode {
00047 public:
00048 TestStabilityNode(Kinematics::FootSupport support = Kinematics::SUPPORT_DOUBLE);
00049 virtual ~TestStabilityNode();
00050 void jointStateCb(const sensor_msgs::JointStateConstPtr& state);
00051
00052 protected:
00053 ros::NodeHandle nh_;
00054 ros::Subscriber joint_state_sub_;
00055 ros::Publisher visualization_pub_, support_polygon_pub_, pcom_pub_;
00056 TestStability test_stability_;
00057 Kinematics::FootSupport support_mode_;
00058 };
00059
00060 TestStabilityNode::TestStabilityNode(Kinematics::FootSupport support)
00061 : support_mode_ (support)
00062 {
00063 ros::NodeHandle nh_private("~");
00064 visualization_pub_ = nh_private.advertise<visualization_msgs::MarkerArray>("stability_visualization", 1);
00065 support_polygon_pub_ = nh_private.advertise<geometry_msgs::PolygonStamped>("support_polygon", 10);
00066 pcom_pub_ = nh_private.advertise<visualization_msgs::Marker>("projected_com", 10);
00067
00068 joint_state_sub_ = nh_.subscribe("joint_states", 1, &TestStabilityNode::jointStateCb, this);
00069 }
00070
00071 TestStabilityNode::~TestStabilityNode(){
00072
00073 }
00074
00075
00076 void TestStabilityNode::jointStateCb(const sensor_msgs::JointStateConstPtr& state){
00077 size_t num_joints = state->position.size();
00078 ROS_DEBUG("Received JointState with %zu joints", num_joints);
00079
00080
00081
00082
00083 std::map<std::string, double> joint_positions;
00084 for (unsigned int i=0; i<state->name.size(); i++)
00085 joint_positions.insert(make_pair(state->name[i], state->position[i]));
00086
00087 tf::Vector3 normal_vector(0.0, 0.0, 1.0);
00088
00089
00090 normal_vector.normalize();
00091
00092 bool stable = test_stability_.isPoseStable(joint_positions, support_mode_, normal_vector);
00093
00094
00095 tf::Point com = test_stability_.getCOM();
00096 if (stable)
00097 ROS_INFO("Pose is stable, pCOM at %f %f", com.x(), com.y());
00098 else
00099 ROS_INFO("Pose is NOT stable, pCOM at %f %f", com.x(), com.y());
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115 support_polygon_pub_.publish(test_stability_.getSupportPolygon());
00116 pcom_pub_.publish(test_stability_.getCOMMarker());
00117
00118 }
00119
00120
00121 }
00122
00123 using namespace hrl_kinematics;
00124
00125 int main(int argc, char** argv)
00126 {
00127 ros::init(argc, argv, "test_stability");
00128
00129 Kinematics::FootSupport support = Kinematics::SUPPORT_DOUBLE;
00130
00131 if (argc == 2){
00132 int i = atoi(argv[1]);
00133 if (i >= 0 && i <= 2)
00134 support = Kinematics::FootSupport(i);
00135
00136 }
00137
00138 try
00139 {
00140 ros::spinOnce();
00141 hrl_kinematics::TestStabilityNode StabilityNode(support);
00142
00143 ros::spin();
00144 }
00145 catch(hrl_kinematics::Kinematics::InitFailed &e)
00146 {
00147 std::cerr << "Could not initialize kinematics node: " << e.what() << std::endl;
00148
00149
00150 return 1;
00151 }
00152
00153 return 0;
00154
00155 }
00156