1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Chnaged magic constant to io_flag_delay_

This commit is contained in:
Thomas Timm Andersen
2015-09-10 13:33:30 +02:00
parent 8d1c8b2e43
commit 1c2b3ad259

View File

@@ -44,10 +44,11 @@ protected:
ros::ServiceServer ioSrv_; ros::ServiceServer ioSrv_;
ros::ServiceServer payloadSrv_; ros::ServiceServer payloadSrv_;
std::thread* rt_publish_thread_; std::thread* rt_publish_thread_;
double io_flag_delay_;
public: public:
RosWrapper(std::string host) : RosWrapper(std::string host) :
as_(nh_, "follow_joint_trajectory", false), robot_(msg_cond_, host) { as_(nh_, "follow_joint_trajectory", false), robot_(msg_cond_, host), io_flag_delay_(0.05) {
std::string joint_prefix = ""; std::string joint_prefix = "";
std::vector<std::string> joint_names; std::vector<std::string> joint_names;
@@ -147,7 +148,7 @@ private:
//} else if (req.fun == ur_msgs::SetIO::Request::FUN_SET_FLAG) { //} else if (req.fun == ur_msgs::SetIO::Request::FUN_SET_FLAG) {
robot_.setFlag(req.pin, req.state > 0.0 ? true : false); robot_.setFlag(req.pin, req.state > 0.0 ? true : false);
//According to urdriver.py, set_flag will fail if called to rapidly in succession //According to urdriver.py, set_flag will fail if called to rapidly in succession
ros::Duration(0.05).sleep(); ros::Duration(io_flag_delay_).sleep();
} else if (req.fun == 3) { } else if (req.fun == 3) {
//} else if (req.fun == ur_msgs::SetIO::Request::FUN_SET_ANALOG_OUT) { //} else if (req.fun == ur_msgs::SetIO::Request::FUN_SET_ANALOG_OUT) {
robot_.setAnalogOut(req.pin, req.state); robot_.setAnalogOut(req.pin, req.state);