ezn64_usb_control.cpp
Go to the documentation of this file.
00001 /*********************************************************************************************/
00031 /* Author: Frantisek Durovsky */
00032 
00033 #include <ezn64_usb_control.h>
00034 
00035 int 
00036 main(int argc, char *argv[])
00037 {
00038   ros::init(argc, argv, "ezn64_usb_control");
00039   ros::NodeHandle nh;
00040 
00041   //Create gripper object instance
00042   schunk_ezn64::EZN64_usb gripper(&nh);
00043          
00044   //Initialize user interface
00045   ros::ServiceServer reference_service         = nh.advertiseService("schunk_ezn64/reference", &schunk_ezn64::EZN64_usb::referenceCallback, &gripper);
00046   ros::ServiceServer set_position_service      = nh.advertiseService("schunk_ezn64/set_position", &schunk_ezn64::EZN64_usb::setPositionCallback, &gripper);
00047   ros::ServiceServer get_error_service         = nh.advertiseService("schunk_ezn64/get_error", &schunk_ezn64::EZN64_usb::getErrorCallback, &gripper);
00048   ros::ServiceServer get_position_service      = nh.advertiseService("schunk_ezn64/get_position", &schunk_ezn64::EZN64_usb::getPositionCallback, &gripper);
00049   ros::ServiceServer acknowledge_error_service = nh.advertiseService("schunk_ezn64/acknowledge_error", &schunk_ezn64::EZN64_usb::acknowledgeErrorCallback, &gripper);
00050   ros::ServiceServer stop_service              = nh.advertiseService("schunk_ezn64/stop", &schunk_ezn64::EZN64_usb::stopCallback, &gripper);
00051   
00052   ros::Timer timer = nh.createTimer(ros::Duration(gripper.TF_UPDATE_PERIOD), &schunk_ezn64::EZN64_usb::timerCallback, &gripper);
00053   gripper.joint_pub = nh.advertise<sensor_msgs::JointState>("joint_states", 1); 
00054   
00055   ros::spin();
00056 
00057   return(EXIT_SUCCESS);
00058 }


schunk_ezn64
Author(s): Frantisek Durovsky
autogenerated on Fri Feb 12 2016 00:21:41