$search
00001 /* 00002 * Copyright (c) 2010, Thomas Ruehr <ruehr@cs.tum.edu> 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 // roslaunch arm_ik.launch 00031 #include <ros/ros.h> 00032 00033 #include <ias_drawer_executive/RobotArm.h> 00034 00035 ros::Publisher pubR, pubL; 00036 00037 void printPose(const char title[], tf::Stamped<tf::Pose> pose) 00038 { 00039 ROS_INFO("%s %f %f %f %f %f %f %f %s", title, pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z() 00040 , pose.getRotation().x(), pose.getRotation().y(), pose.getRotation().z(), pose.getRotation().w(), pose.frame_id_.c_str()); 00041 } 00042 00043 00044 void poseCallbackR(const geometry_msgs::PoseStamped::ConstPtr& msg) 00045 { 00046 00047 double start_angles[7]; 00048 double solutions[7]; 00049 RobotArm::getInstance(0)->getJointState(start_angles); 00050 00051 tf::Stamped<tf::Pose> nextPose; 00052 tf::poseStampedMsgToTF(*msg, nextPose); 00053 00054 nextPose = RobotArm::getInstance(0)->tool2wrist(nextPose); 00055 geometry_msgs::PoseStamped inWrist; 00056 tf::poseStampedTFToMsg(nextPose,inWrist); 00057 00058 bool ik_res = RobotArm::getInstance(0)->run_ik(inWrist, start_angles,solutions,"r_wrist_roll_link"); 00059 00060 if (!ik_res) { 00061 ROS_ERROR("outside bounds"); 00062 printPose("right arm outside workspace, for wrist", nextPose); 00063 return; 00064 } 00065 00066 pubR.publish(msg); 00067 00068 } 00069 00070 00071 00072 void poseCallbackL(const geometry_msgs::PoseStamped::ConstPtr& msg) 00073 { 00074 00075 double start_angles[7]; 00076 double solutions[7]; 00077 RobotArm::getInstance(1)->getJointState(start_angles); 00078 00079 tf::Stamped<tf::Pose> nextPose; 00080 tf::poseStampedMsgToTF(*msg, nextPose); 00081 00082 nextPose = RobotArm::getInstance(1)->tool2wrist(nextPose); 00083 geometry_msgs::PoseStamped inWrist; 00084 tf::poseStampedTFToMsg(nextPose,inWrist); 00085 00086 bool ik_res = RobotArm::getInstance(1)->run_ik(inWrist, start_angles,solutions,"l_wrist_roll_link"); 00087 00088 if (!ik_res) { 00089 ROS_ERROR("outside bounds"); 00090 printPose("left arm outside workspace, for wrist", nextPose); 00091 return; 00092 } 00093 00094 pubL.publish(msg); 00095 00096 } 00097 00098 00099 int main(int argc, char** argv) 00100 { 00101 // Init the ROS node 00102 ros::init(argc, argv, "WorkSpaceFilter"); 00103 ros::NodeHandle node_handle; 00104 00105 ros::Subscriber subsRight = node_handle.subscribe("/r_workspace_filter", 1, &poseCallbackR); 00106 ros::Subscriber subsLeft = node_handle.subscribe("/l_workspace_filter", 1, &poseCallbackL); 00107 00108 ros::Publisher pubR = node_handle.advertise<geometry_msgs::PoseStamped>( "/r_out_workspace_filter", 100, true ); 00109 ros::Publisher pubL = node_handle.advertise<geometry_msgs::PoseStamped>( "/l_out_workspace_filter", 100, true ); 00110 00111 ROS_INFO("READY"); 00112 00113 ros::spin(); 00114 } 00115