wam_tutorial.cpp
Go to the documentation of this file.
00001 #include "wam_tutorial.h"
00002 
00003 /* wam_tutorial node code */
00004 
00005 WamTutorial::WamTutorial() {
00006   //init class attributes if necessary
00007   this->gocenter = true;
00008   this->targetid = 0;
00009 
00010   this->numtargets = 10;
00011   this->tfMessage_msg.transforms.resize(numtargets+2);
00012   this->angles.resize(5);
00013   this->angles[0] = 0.0;
00014   this->angles[1] = M_PI/4.0;
00015   this->angles[2] = 3.0*M_PI/4.0;
00016   this->angles[3] = 9.0/8.0*M_PI;
00017   this->angles[4] = 13.0/8.0*M_PI;
00018   //string for port names
00019   std::string port_name;
00020 
00021   // [init publishers]
00022   port_name = ros::names::append(ros::this_node::getName(), "tf"); 
00023   this->tf_publisher = this->nh_.advertise<tf::tfMessage>(port_name, 5);
00024   
00025   // [init subscribers]
00026   port_name = ros::names::append(ros::this_node::getName(), "pose"); 
00027   this->pose_subscriber = this->nh_.subscribe(port_name, 5, &WamTutorial::pose_callback, this);
00028   port_name = ros::names::append(ros::this_node::getName(), "joint_states"); 
00029   this->joint_states_subscriber = this->nh_.subscribe(port_name, 5, &WamTutorial::joint_states_callback, this);
00030   
00031   // [init services]
00032   
00033   // [init clients]
00034   port_name = ros::names::append(ros::this_node::getName(), "pose_move2"); 
00035   pose_move2_client = this->nh_.serviceClient<iri_wam_common_msgs::pose_move>(port_name);
00036 
00037   port_name = ros::names::append(ros::this_node::getName(), "pose_move"); 
00038   pose_move_client = this->nh_.serviceClient<iri_wam_common_msgs::pose_move>(port_name);
00039   port_name = ros::names::append(ros::this_node::getName(), "joints_move"); 
00040   joint_move_client = this->nh_.serviceClient<iri_wam_common_msgs::joints_move>(port_name);
00041   
00042   // [init action servers]
00043   
00044   // [init action clients]
00045 }
00046 
00047 void WamTutorial::mainLoop(void)
00048 {
00049   //lock access to driver if necessary
00050   //this->driver_.lock();
00051   tf::StampedTransform transform;
00052   geometry_msgs::TransformStamped msg;
00053   std::ostringstream oss;
00054   std::ostringstream oss2;
00055   std::ostringstream oss3;
00056   std::string targetname("target");
00057   // [fill msg Header if necessary]
00058   //<publisher_name>.header.stamp = ros::Time::now();
00059   //<publisher_name>.header.frame_id = "<publisher_topic_name>";
00060 
00061   // [fill msg structures]
00062   //this->tfMessage_msg.data = my_var;
00063   
00064 
00065   //joint_move_srv.request.resize(7);
00066   //joint_move_srv.request.joints[0] = 0.0; 
00067   //joint_move_srv.request.joints[1] = 0.0; 
00068   //joint_move_srv.request.joints[2] = 0.2; 
00069   //joint_move_srv.request.joints[3] = 0.0; 
00070   //joint_move_srv.request.joints[4] = 0.0; 
00071   //joint_move_srv.request.joints[5] = 0.0; 
00072   //joint_move_srv.request.joints[6] = 0.0; 
00073   //if (joint_move_client.call(joint_move_srv)) { 
00074   //  ROS_INFO(joint_move_srv.response.success);
00075   //} else { 
00076   //  ROS_ERROR("Failed to call service joint_move"); 
00077   //}
00078   
00079   // [fill action structure and make request to the action server]
00080 
00081   // [publish messages]
00082   this->tfMessage_msg.transforms[0].header.stamp = ros::Time::now();
00083   this->tfMessage_msg.transforms[0].header.frame_id = "wam0";
00084   this->tfMessage_msg.transforms[0].child_frame_id = "central";
00085   this->tfMessage_msg.transforms[0].transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0,0,0); 
00086 
00087   this->tfMessage_msg.transforms[0].transform.translation.x = 0.55; 
00088   this->tfMessage_msg.transforms[0].transform.translation.y = 0.2; 
00089   this->tfMessage_msg.transforms[0].transform.translation.z = 0.1; 
00090 
00091   this->tfMessage_msg.transforms[1].header.stamp = ros::Time::now();
00092   this->tfMessage_msg.transforms[1].header.frame_id = "central";
00093   this->tfMessage_msg.transforms[1].child_frame_id = "target0b";
00094   this->tfMessage_msg.transforms[1].transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0,0,0); 
00095 
00096   this->tfMessage_msg.transforms[1].transform.translation.x = 0.0; 
00097   this->tfMessage_msg.transforms[1].transform.translation.y = 0.0; 
00098   this->tfMessage_msg.transforms[1].transform.translation.z = 0.3; 
00099 
00100   for(uint i=2;i<tfMessage_msg.transforms.size();i+=2){
00101     this->tfMessage_msg.transforms[i].header.stamp = ros::Time::now();
00102     this->tfMessage_msg.transforms[i].header.frame_id = "central";
00103     std::ostringstream oss;
00104     oss << targetname << i/2;
00105     this->tfMessage_msg.transforms[i].child_frame_id = oss.str();
00106     this->tfMessage_msg.transforms[i].transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(angles[(i+1)/2%5],0,0); 
00107     this->tfMessage_msg.transforms[i].transform.translation.x = 0.0; 
00108     this->tfMessage_msg.transforms[i].transform.translation.y = 0.0; 
00109     this->tfMessage_msg.transforms[i].transform.translation.z = 0.0; 
00110 
00111     this->tfMessage_msg.transforms[i+1].header.stamp = ros::Time::now();
00112     this->tfMessage_msg.transforms[i+1].header.frame_id = oss.str();
00113     oss << "b";
00114     this->tfMessage_msg.transforms[i+1].child_frame_id = oss.str();
00115     this->tfMessage_msg.transforms[i+1].transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0,0,0); 
00116 
00117     this->tfMessage_msg.transforms[i+1].transform.translation.x = 0.0; 
00118     this->tfMessage_msg.transforms[i+1].transform.translation.y = 0.0; 
00119     this->tfMessage_msg.transforms[i+1].transform.translation.z = 0.3; 
00120   } 
00121 
00122   tf::tfMessage tfMessage_msgaux(this->tfMessage_msg);
00123   this->tf_publisher.publish(tfMessage_msgaux);
00124 
00125   oss3 << targetname << targetid << "b";
00126   calculate_error(oss3.str());
00127 
00128     if(gocenter){
00129       gocenter = false;
00130       ROS_INFO("Going to central");
00131       try{
00132         listener.lookupTransform("wam0", "central", ros::Time(0), transform);
00133         tf::transformStampedTFToMsg(transform,msg);
00134         //Sembla increible, pero els valors estan desplaçats...
00136         pose_move_srv.request.pose.orientation.y = msg.transform.rotation.x;
00137         pose_move_srv.request.pose.orientation.z = msg.transform.rotation.y;
00138         pose_move_srv.request.pose.orientation.w = msg.transform.rotation.z;
00139         pose_move_srv.request.pose.orientation.x = msg.transform.rotation.w;
00140         
00141         pose_move_srv.request.pose.position.x = msg.transform.translation.x;
00142         pose_move_srv.request.pose.position.y = msg.transform.translation.y;
00143         pose_move_srv.request.pose.position.z = msg.transform.translation.z;
00144         std::cout << "moving to:" << msg << std::endl;
00145         sleep(1);
00146         //kaijen ik
00147         if (pose_move2_client.call(pose_move_srv)) { 
00148           ROS_INFO("pose_move2: %d", pose_move_srv.response.success); 
00149           calculate_error("central");
00150         } else { 
00151           ROS_ERROR("Failed to call service pose_move2"); 
00152         }
00153       } catch (tf::TransformException ex){
00154         ROS_ERROR("%s",ex.what());
00155       } 
00156     }else{ 
00157       gocenter = true;
00158       targetid++;
00159       targetid = targetid%6;
00160       oss2 << targetname << targetid << "b";
00161       ROS_INFO("Going to %s",oss2.str().c_str());
00162       try{
00163         listener.lookupTransform("wam0", oss2.str(), ros::Time(0), transform);
00164 
00165 //change this with http://www.ros.org/wiki/tf/Overview/Using%20Published%20Transforms
00166 
00167         tf::transformStampedTFToMsg(transform,msg);
00168         pose_move_srv.request.pose.orientation.y = msg.transform.rotation.x;
00169         pose_move_srv.request.pose.orientation.z = msg.transform.rotation.y;
00170         pose_move_srv.request.pose.orientation.w = msg.transform.rotation.z;
00171         pose_move_srv.request.pose.orientation.x = msg.transform.rotation.w;
00172         
00173         pose_move_srv.request.pose.position.x = msg.transform.translation.x;
00174         pose_move_srv.request.pose.position.y = msg.transform.translation.y;
00175         pose_move_srv.request.pose.position.z = msg.transform.translation.z;
00176           std::cout << "moving to:" << msg << std::endl;
00177         sleep(1);
00178         //kaijen ik
00179         if (pose_move2_client.call(pose_move_srv)) { 
00180           ROS_INFO("pose_move2: %d", pose_move_srv.response.success); 
00181         } else { 
00182           ROS_ERROR("Failed to call service pose_move2"); 
00183         }
00184       } catch (tf::TransformException ex){
00185         ROS_ERROR("%s",ex.what());
00186       } 
00187     }
00188   // [fill srv structure and make request to the server]
00189   
00190 //  pose_move_srv.request.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0.785,0.785,0.785); 
00191 //
00192 //  pose_move_srv.request.pose.position.x = 0.4; 
00193 //  pose_move_srv.request.pose.position.y = 0.2; 
00194 //  pose_move_srv.request.pose.position.z = 0.1; 
00195 
00196 //  if (pose_move_client.call(pose_move_srv)) { 
00197 //    ROS_INFO("pose_move: %d", pose_move_srv.response.success); 
00198 //  } else { 
00199 //    ROS_ERROR("Failed to call service pose_move"); 
00200 //  }
00201 
00202   //unlock access to driver if previously blocked
00203   //this->driver_.unlock();
00204 }
00205 
00206 /*  [subscriber callbacks] */
00207 void WamTutorial::pose_callback(const geometry_msgs::PoseStamped::ConstPtr& msg) 
00208 { 
00209   //std::cout << msg->data << std::endl; 
00210 
00211 }
00212 void WamTutorial::joint_states_callback(const sensor_msgs::JointState::ConstPtr& msg) 
00213 { 
00214 
00215   //std::cout << msg->data << std::endl; 
00216 
00217 }
00218 
00219 /*  [service callbacks] */
00220 
00221 /*  [action callbacks] */
00222 
00223 /*  [action requests] */
00224 
00225 void WamTutorial::calculate_error(std::string target) {
00226 
00227   tf::StampedTransform transform;
00228   geometry_msgs::TransformStamped msg;
00229   try{
00230       listener.lookupTransform("wam7", target, ros::Time(0), transform);
00231       tf::transformStampedTFToMsg(transform,msg);
00232       std::cout << "transform error " << msg << std::endl;
00233   } catch (tf::TransformException ex){
00234     ROS_ERROR("%s",ex.what());
00235   } 
00236 }
00237 
00238 
00239 int main(int argc, char** argv) {
00240     ros::init(argc, argv, "wam_tut");
00241     WamTutorial wam_tutorial;
00242     ros::Rate loop_rate(10); 
00243     while(ros::ok()){
00244       wam_tutorial.mainLoop();
00245       ros::spinOnce();
00246       loop_rate.sleep(); 
00247     }
00248 }


iri_wam_tutorial
Author(s):
autogenerated on Fri Dec 6 2013 20:18:18