bool setForceSrv(wsg_50_common::Conf::Request &req, wsg_50_common::Conf::Response &res) { setGraspingForceLimit(req.val); return true; }
int main( int argc, char **argv ) { ros::init(argc, argv, "wsg_50"); ros::NodeHandle nh("~"); signal(SIGINT, sigint_handler); double rate, grasping_force; std::string device; int bitrate; nh.param("read_rate", rate, 30.0); nh.param("grasping_force", grasping_force, 80.0); nh.param("device", device, std::string("/dev/ttyUSB3")); nh.param("bitrate", bitrate, 38400); nh.param("use_fmf", use_fmf, true); // Connect to device int res_con; ROS_INFO("Connecting to %s: (rs232) at %d ...", device.c_str(), bitrate); res_con = cmd_connect_serial(device.c_str(), bitrate); if (res_con == 0 ) { ROS_INFO("Gripper connection stablished"); // Services ros::ServiceServer moveSS, graspSS, releaseSS, homingSS, stopSS, ackSS, incrementSS, setAccSS, setForceSS; ros::ServiceServer move_no_waitingSS, grasp_no_waitingSS, release_no_waitingSS, homing_no_waitingSS, stop_no_waitingSS, setAcc_no_waitingSS, setForce_no_waitingSS, setLimitsSS, clearLimitsSS, getLimitsSS; moveSS = nh.advertiseService("move", moveSrv); graspSS = nh.advertiseService("grasp", graspSrv); releaseSS = nh.advertiseService("release", releaseSrv); homingSS = nh.advertiseService("homing", homingSrv); stopSS = nh.advertiseService("stop", stopSrv); ackSS = nh.advertiseService("ack", ackSrv); setAccSS = nh.advertiseService("set_acceleration", setAccSrv); setForceSS = nh.advertiseService("set_force", setForceSrv); move_no_waitingSS = nh.advertiseService("move_no_waiting", moveSrv_no_waiting); grasp_no_waitingSS = nh.advertiseService("grasp_no_waiting", graspSrv_no_waiting); release_no_waitingSS = nh.advertiseService("release_no_waiting", releaseSrv_no_waiting); homing_no_waitingSS = nh.advertiseService("homing_no_waiting", homingSrv_no_waiting); stop_no_waitingSS = nh.advertiseService("stop_no_waiting", stopSrv_no_waiting); setAcc_no_waitingSS = nh.advertiseService("set_acceleration_no_waiting", setAccSrv_no_waiting); setForce_no_waitingSS = nh.advertiseService("set_force_no_waiting", setForceSrv_no_waiting); setLimitsSS = nh.advertiseService("set_soft_limits", setLimitsSrv); clearLimitsSS = nh.advertiseService("clear_soft_limits", clearLimitsSrv); getLimitsSS = nh.advertiseService("view_soft_limits", getLimitsSrv); // Publisher g_pub_state = nh.advertise<wsg_50_common::Status>("status", 1000); g_pub_joint = nh.advertise<sensor_msgs::JointState>("joint_states", 10); g_pub_moving = nh.advertise<std_msgs::Bool>("moving", 10); ROS_INFO("Ready to use, homing now..."); homing(); if (grasping_force > 0.0) { ROS_INFO("Setting grasping force limit to %5.1f", grasping_force); setGraspingForceLimit(grasping_force); } if (use_fmf) { ROS_INFO("Force measure fingers data reading: ON"); ROS_INFO("Reading finger info (type 0 - generic, 1 - WSG-FMF) ..."); getFingerInfo(0, info_fingers[0]); getFingerInfo(1, info_fingers[1]); ROS_INFO("Finger 0 type %d: data size %d bytes", info_fingers[0].type, info_fingers[0].data_size); ROS_INFO("Finger 1 type %d: data size %d bytes", info_fingers[1].type, info_fingers[1].data_size); if (info_fingers[0].type != info_fingers[1].type) info_fingers[0].type = info_fingers[1].type = 1; } else { ROS_INFO("Force measure fingers data reading: OFF"); info_fingers[0].type = info_fingers[1].type = 0; } ROS_INFO("Init done. Starting timer/thread with target rate %.1f.", rate); std::thread th; g_thread = true; th = std::thread(read_thread, (int)(1000.0/rate)); ros::spin(); } else { ROS_ERROR("Unable to connect, please check the port and address used."); } return 0; }
int main( int argc, char **argv ) { ros::init(argc, argv, "wsg_50"); ros::NodeHandle nh("~"); signal(SIGINT, sigint_handler); std::string ip, protocol, com_mode; int port, local_port; double rate, grasping_force; bool use_udp = false; nh.param("ip", ip, std::string("192.168.1.20")); nh.param("port", port, 1000); nh.param("local_port", local_port, 1501); nh.param("protocol", protocol, std::string("")); nh.param("com_mode", com_mode, std::string("")); nh.param("rate", rate, 1.0); // With custom script, up to 30Hz are possible nh.param("grasping_force", grasping_force, 0.0); if (protocol == "udp") use_udp = true; else protocol = "tcp"; if (com_mode == "script") g_mode_script = true; else if (com_mode == "auto_update") g_mode_periodic = true; else { com_mode = "polling"; g_mode_polling = true; } ROS_INFO("Connecting to %s:%d (%s); communication mode: %s ...", ip.c_str(), port, protocol.c_str(), com_mode.c_str()); // Connect to device using TCP/USP int res_con; if (!use_udp) res_con = cmd_connect_tcp( ip.c_str(), port ); else res_con = cmd_connect_udp(local_port, ip.c_str(), port ); if (res_con == 0 ) { ROS_INFO("Gripper connection stablished"); // Services ros::ServiceServer moveSS, graspSS, releaseSS, homingSS, stopSS, ackSS, incrementSS, setAccSS, setForceSS; if (g_mode_script || g_mode_polling) { moveSS = nh.advertiseService("move", moveSrv); graspSS = nh.advertiseService("grasp", graspSrv); releaseSS = nh.advertiseService("release", releaseSrv); homingSS = nh.advertiseService("homing", homingSrv); stopSS = nh.advertiseService("stop", stopSrv); ackSS = nh.advertiseService("ack", ackSrv); incrementSS = nh.advertiseService("move_incrementally", incrementSrv); setAccSS = nh.advertiseService("set_acceleration", setAccSrv); setForceSS = nh.advertiseService("set_force", setForceSrv); } // Subscriber ros::Subscriber sub_position, sub_speed; if (g_mode_script || g_mode_periodic) sub_position = nh.subscribe("goal_position", 5, position_cb); if (g_mode_script) sub_speed = nh.subscribe("goal_speed", 5, speed_cb); // Publisher g_pub_state = nh.advertise<wsg_50_common::Status>("status", 1000); g_pub_joint = nh.advertise<sensor_msgs::JointState>("joint_states", 10); if (g_mode_script || g_mode_periodic) g_pub_moving = nh.advertise<std_msgs::Bool>("moving", 10); ROS_INFO("Ready to use. Homing and taring now..."); homing(); ros::Duration(0.5).sleep(); doTare(); if (grasping_force > 0.0) { ROS_INFO("Setting grasping force limit to %5.1f", grasping_force); setGraspingForceLimit(grasping_force); } ROS_INFO("Init done. Starting timer/thread with target rate %.1f.", rate); std::thread th; ros::Timer tmr; if (g_mode_polling || g_mode_script) tmr = nh.createTimer(ros::Duration(1.0/rate), timer_cb); if (g_mode_periodic) th = std::thread(read_thread, (int)(1000.0/rate)); ros::spin(); } else { ROS_ERROR("Unable to connect, please check the port and address used."); } ROS_INFO("Exiting..."); g_mode_periodic = false; g_mode_script = false; g_mode_polling = false; sleep(1); cmd_disconnect(); return 0; }