$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/hrl_kinematics/src/test_stability.cpp $ 00002 // SVN $Id: test_stability.cpp 3069 2012-08-21 14:26:59Z hornunga@informatik.uni-freiburg.de $ 00003 00004 /* 00005 * hrl_kinematics - a kinematics library for humanoid robots based on KDL 00006 * 00007 * Copyright 2011-2012 Armin Hornung, University of Freiburg 00008 * License: BSD 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above copyright 00016 * notice, this list of conditions and the following disclaimer in the 00017 * documentation and/or other materials provided with the distribution. 00018 * * Neither the name of the University of Freiburg nor the names of its 00019 * contributors may be used to endorse or promote products derived from 00020 * this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00023 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00024 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00025 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00026 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00027 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00028 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00029 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00030 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00031 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 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 // TODO: need to obtain current support mode 00081 00082 // get joint positions from state message 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); // planar support 00088 // for testing, normal vector of arbitrary plane: 00089 //tf::Vector3 normal_vector(0.5, 0.0, 1.0); 00090 normal_vector.normalize(); 00091 00092 bool stable = test_stability_.isPoseStable(joint_positions, support_mode_, normal_vector); 00093 00094 // print info 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 // publish visualization: 00102 00103 // TODO link coms: 00104 // visualization_msgs::MarkerArray com_vis_markers; 00105 // 00106 // visualization_pub_.publish(vis_markers); 00107 // visualization_msgs::Marker marker; 00108 // createCoGMarker(kdl_tree_.getRootSegment()->first, "torso", 0.04, com, marker); 00109 // 00110 // com_vis_markers_.markers.push_back(marker); 00111 // 00112 // 00113 // visualization_pub_.publish(com_vis_markers_); 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 // TODO: does not work? 00149 //ROS_INFO("Could not initialize kinematics node: %s\n", e.what()); 00150 return 1; 00151 } 00152 00153 return 0; 00154 00155 } 00156