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