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; }
int main( int argc, char **argv ) { ros::init(argc, argv, "wsg_50"); ros::NodeHandle nh; std::string ip; int port; ROS_INFO("WSG 50 - ROS NODE"); nh.param("wsg_50_tcp/ip", ip, std::string("192.168.1.20")); nh.param("wsg_50_tcp/port", port, 1000); // Connect to device using TCP if( cmd_connect_tcp( ip.c_str(), port ) == 0 ) { ROS_INFO("TCP connection stablished"); // Services ros::ServiceServer moveSS = nh.advertiseService("wsg_50/move", moveSrv); ros::ServiceServer graspSS = nh.advertiseService("wsg_50/grasp", graspSrv); ros::ServiceServer releaseSS = nh.advertiseService("wsg_50/release", releaseSrv); ros::ServiceServer homingSS = nh.advertiseService("wsg_50/homing", homingSrv); ros::ServiceServer stopSS = nh.advertiseService("wsg_50/stop", stopSrv); ros::ServiceServer ackSS = nh.advertiseService("wsg_50/ack", ackSrv); ros::ServiceServer incrementSS = nh.advertiseService("wsg_50/move_incrementally", incrementSrv); ros::ServiceServer setAccSS = nh.advertiseService("wsg_50/set_acceleration", setAccSrv); ros::ServiceServer setForceSS = nh.advertiseService("wsg_50/set_force", setForceSrv); // Publisher ros::Publisher state_pub = nh.advertise<wsg_50_common::Status>("wsg_50/status", 1000); ros::Publisher joint_states_pub = nh.advertise<sensor_msgs::JointState>("/joint_states", 10); ROS_INFO("Ready to use."); homing(); ros::Rate loop_rate(1); // loop at 1Hz while( ros::ok() ){ //Loop waiting for orders and updating the state //Create the msg to send wsg_50_common::Status status_msg; //Get state values const char * aux; aux = systemState(); int op = getOpening(); int acc = getAcceleration(); int force = getGraspingForceLimit(); std::stringstream ss; ss << aux; status_msg.status = ss.str(); status_msg.width = op; status_msg.acc = acc; status_msg.force = force; state_pub.publish(status_msg); sensor_msgs::JointState joint_states; joint_states.header.stamp = ros::Time::now();; joint_states.header.frame_id = "wsg_50_gripper_base_link"; joint_states.name.push_back("wsg_50_gripper_base_joint_gripper_left"); joint_states.name.push_back("wsg_50_gripper_base_joint_gripper_right"); joint_states.position.resize(2); joint_states.position[0] = -op/2000.0; joint_states.position[1] = op/2000.0; //joint_states.velocity.resize(2); //joint_states.velocity[0]; //joint_states.velocity[1]; joint_states.effort.resize(2); joint_states.effort[0] = force; joint_states.effort[1] = force; joint_states_pub.publish(joint_states); loop_rate.sleep(); ros::spinOnce(); } }else{ ROS_ERROR("Unable to connect via TCP, please check the port and address used."); } // Disconnect - won't be executed atm. as the endless loop in test() // will never return. cmd_disconnect(); return 0; }