00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _arm_movements_by_pose_alg_h_ 00026 #define _arm_movements_by_pose_alg_h_ 00027 00028 #include <iri_arm_movements_by_pose/ArmMovementsByPoseConfig.h> 00029 #include "mutex.h" 00030 00031 //include arm_movements_by_pose_alg main library 00032 // #include <pcl/ModelCoefficients.h> 00033 #include <tf/transform_broadcaster.h> 00034 #include <tf/transform_listener.h> 00035 #include <tf/transform_datatypes.h> 00036 00037 // eigen 00038 #include <Eigen/Core> 00039 #include <Eigen/Geometry> 00040 00046 class ArmMovementsByPoseAlgorithm 00047 { 00048 protected: 00055 CMutex alg_mutex_; 00056 00057 // private attributes and methods 00058 private: 00059 tf::TransformBroadcaster tf_br; 00060 tf::TransformListener tf_listener; 00061 00062 // private parameters 00063 double hand_size_offset; 00064 double wam_security_distance; 00065 bool robot_wam; 00066 00067 geometry_msgs::PoseStamped get_pose_from_tf_with_offset(geometry_msgs::PoseStamped pose_orig, std::vector<float> plane_coefs); 00068 00069 00070 public: 00077 typedef iri_arm_movements_by_pose::ArmMovementsByPoseConfig Config; 00078 00085 Config config_; 00086 00095 ArmMovementsByPoseAlgorithm(void); 00096 00102 void lock(void) { alg_mutex_.enter(); }; 00103 00109 void unlock(void) { alg_mutex_.exit(); }; 00110 00118 bool try_enter(void) { return alg_mutex_.try_enter(); }; 00119 00131 void config_update(Config& new_cfg, uint32_t level=0); 00132 00133 // here define all arm_movements_by_pose_alg interface methods to retrieve and set 00134 // the driver parameters 00135 00142 ~ArmMovementsByPoseAlgorithm(void); 00143 00144 00146 00152 std::vector<geometry_msgs::PoseStamped> get_transformed_poses(std::vector<geometry_msgs::PoseStamped> poses, 00153 std::vector<float> plane_coefficients); 00154 00160 std::vector<geometry_msgs::PoseStamped> get_initial_position(); 00161 00162 00168 geometry_msgs::Quaternion rotate_pitch(geometry_msgs::Quaternion orientation_msgs, double angle); 00169 00175 geometry_msgs::Quaternion rotate_roll(geometry_msgs::Quaternion orientation_msgs, double angle); 00176 00182 geometry_msgs::Quaternion rotate_yaw(geometry_msgs::Quaternion orientation_msgs, double angle); 00183 00184 00185 // public parameters 00191 std::string tf_target_str; 00192 00193 }; 00194 00195 #endif