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

Added URScript interface - untested

This commit is contained in:
Thomas Timm Andersen
2015-09-15 17:23:57 +02:00
parent 273236f7c1
commit 8f3ae49e28
3 changed files with 22 additions and 9 deletions

View File

@@ -10,6 +10,7 @@ find_package(catkin REQUIRED COMPONENTS
geometry_msgs geometry_msgs
roscpp roscpp
sensor_msgs sensor_msgs
std_msgs
trajectory_msgs trajectory_msgs
ur_msgs ur_msgs
) )

View File

@@ -45,6 +45,7 @@
<build_depend>geometry_msgs</build_depend> <build_depend>geometry_msgs</build_depend>
<build_depend>roscpp</build_depend> <build_depend>roscpp</build_depend>
<build_depend>sensor_msgs</build_depend> <build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>trajectory_msgs</build_depend> <build_depend>trajectory_msgs</build_depend>
<build_depend>ur_msgs</build_depend> <build_depend>ur_msgs</build_depend>
<run_depend>actionlib</run_depend> <run_depend>actionlib</run_depend>
@@ -52,6 +53,7 @@
<run_depend>geometry_msgs</run_depend> <run_depend>geometry_msgs</run_depend>
<run_depend>roscpp</run_depend> <run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend> <run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>trajectory_msgs</run_depend> <run_depend>trajectory_msgs</run_depend>
<run_depend>ur_msgs</run_depend> <run_depend>ur_msgs</run_depend>

View File

@@ -31,6 +31,7 @@
#include "ur_msgs/SetPayloadResponse.h" #include "ur_msgs/SetPayloadResponse.h"
#include "ur_msgs/SetIORequest.h" #include "ur_msgs/SetIORequest.h"
#include "ur_msgs/SetIOResponse.h" #include "ur_msgs/SetIOResponse.h"
#include "std_msgs/String.h"
class RosWrapper { class RosWrapper {
protected: protected:
@@ -42,9 +43,10 @@ protected:
actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction>::Goal goal_; actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction>::Goal goal_;
control_msgs::FollowJointTrajectoryFeedback feedback_; control_msgs::FollowJointTrajectoryFeedback feedback_;
control_msgs::FollowJointTrajectoryResult result_; control_msgs::FollowJointTrajectoryResult result_;
ros::Subscriber speedSub_; ros::Subscriber speed_sub_;
ros::ServiceServer ioSrv_; ros::Subscriber urscript_sub_;
ros::ServiceServer payloadSrv_; ros::ServiceServer io_srv_;
ros::ServiceServer payload_srv_;
std::thread* rt_publish_thread_; std::thread* rt_publish_thread_;
double io_flag_delay_; double io_flag_delay_;
double max_velocity_; double max_velocity_;
@@ -52,8 +54,9 @@ protected:
public: public:
RosWrapper(std::string host) : RosWrapper(std::string host) :
as_(nh_, "follow_joint_trajectory", false), robot_(rt_msg_cond_, msg_cond_, host), io_flag_delay_( as_(nh_, "follow_joint_trajectory", false), robot_(rt_msg_cond_,
0.05), joint_offsets_(6, 0.0) { msg_cond_, host), io_flag_delay_(0.05), joint_offsets_(6,
0.0) {
std::string joint_prefix = ""; std::string joint_prefix = "";
std::vector<std::string> joint_names; std::vector<std::string> joint_names;
@@ -103,12 +106,14 @@ public:
as_.start(); as_.start();
//subscribe to the data topic of interest //subscribe to the data topic of interest
speedSub_ = nh_.subscribe("joint_speed", 1, &RosWrapper::speedInterface, speed_sub_ = nh_.subscribe("joint_speed", 1,
this); &RosWrapper::speedInterface, this);
urscript_sub_ = nh_.subscribe("ur_driver/URSCcript", 1,
&RosWrapper::urscriptInterface, this);
ioSrv_ = nh_.advertiseService("ur_driver/set_io", &RosWrapper::setIO, io_srv_ = nh_.advertiseService("ur_driver/set_io", &RosWrapper::setIO,
this); this);
payloadSrv_ = nh_.advertiseService("ur_driver/set_payload", payload_srv_ = nh_.advertiseService("ur_driver/set_payload",
&RosWrapper::setPayload, this); &RosWrapper::setPayload, this);
rt_publish_thread_ = new std::thread( rt_publish_thread_ = new std::thread(
@@ -314,6 +319,11 @@ private:
msg->points[0].velocities[3], msg->points[0].velocities[4], msg->points[0].velocities[3], msg->points[0].velocities[4],
msg->points[0].velocities[5], acc); msg->points[0].velocities[5], acc);
}
void urscriptInterface(const std_msgs::String::ConstPtr& msg) {
robot_.rt_interface_->addCommandToQueue(msg->data);
} }
void publishRTMsg() { void publishRTMsg() {