Go to the documentation of this file.00001 #include "ros/ros.h"
00002 
00003 #include <boost/bind.hpp>
00004 #include <boost/ref.hpp>
00005 
00006 #include "robotiq_c_model_control/c_model_ethercat_client.h"
00007 #include <robotiq_c_model_control/CModel_robot_input.h>
00008 #include "robotiq_ethercat/ethercat_manager.h"
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 void changeCallback(robotiq_c_model_control::CModelEtherCatClient& client,
00022                     const robotiq_c_model_control::CModelEtherCatClient::GripperOutput::ConstPtr& msg)
00023 {
00024   client.writeOutputs(*msg);
00025 }
00026 
00027 
00028 int main(int argc, char** argv)
00029 {
00030   using robotiq_ethercat::EtherCatManager;
00031   using robotiq_c_model_control::CModelEtherCatClient;
00032 
00033   typedef CModelEtherCatClient::GripperOutput GripperOutput;
00034   typedef CModelEtherCatClient::GripperInput GripperInput;
00035 
00036   ros::init(argc, argv, "robotiq_c_model_gripper_node");
00037   
00038   ros::NodeHandle nh ("~");
00039 
00040   
00041   std::string ifname;
00042   int slave_no;
00043   bool activate;  
00044 
00045   nh.param<std::string>("ifname", ifname, "eth1");
00046   nh.param<int>("slave_number", slave_no, 1);
00047   nh.param<bool>("activate", activate, true);
00048 
00049   
00050   EtherCatManager manager(ifname);
00051   
00052   CModelEtherCatClient client(manager, slave_no);
00053 
00054   
00055   if (activate)
00056   {
00057     
00058     GripperOutput out;
00059     out.rACT = 0x1;
00060     client.writeOutputs(out);
00061   }
00062 
00063   
00064   ros::Subscriber sub = 
00065         nh.subscribe<GripperOutput>("output", 1,
00066                                     boost::bind(changeCallback, boost::ref(client), _1));
00067 
00068   ros::Publisher pub = nh.advertise<GripperInput>("input", 100);
00069 
00070   ros::Rate rate(10); 
00071 
00072   while (ros::ok()) 
00073   {
00074     CModelEtherCatClient::GripperInput input = client.readInputs();
00075     pub.publish(input);
00076     ros::spinOnce();
00077     rate.sleep();
00078   }
00079 
00080   return 0;
00081 }