mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
moved rtde recipe to external text file
This commit is contained in:
@@ -51,7 +51,7 @@ class RTDEClient
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
RTDEClient() = delete;
|
RTDEClient() = delete;
|
||||||
RTDEClient(std::string robot_ip, comm::INotifier& notifier);
|
RTDEClient(std::string robot_ip, comm::INotifier& notifier, const std::string& recipe_file);
|
||||||
~RTDEClient() = default;
|
~RTDEClient() = default;
|
||||||
bool init();
|
bool init();
|
||||||
bool start();
|
bool start();
|
||||||
@@ -64,6 +64,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
comm::URStream<PackageHeader> stream_;
|
comm::URStream<PackageHeader> stream_;
|
||||||
|
std::vector<std::string> recipe_;
|
||||||
RTDEParser parser_;
|
RTDEParser parser_;
|
||||||
comm::URProducer<PackageHeader> prod_;
|
comm::URProducer<PackageHeader> prod_;
|
||||||
comm::Pipeline<PackageHeader> pipeline_;
|
comm::Pipeline<PackageHeader> pipeline_;
|
||||||
@@ -73,7 +74,7 @@ private:
|
|||||||
constexpr static const double CB3_MAX_FREQUENCY = 125.0;
|
constexpr static const double CB3_MAX_FREQUENCY = 125.0;
|
||||||
constexpr static const double URE_MAX_FREQUENCY = 500.0;
|
constexpr static const double URE_MAX_FREQUENCY = 500.0;
|
||||||
|
|
||||||
std::vector<std::string> readRecipe();
|
std::vector<std::string> readRecipe(const std::string& recipe_file);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace rtde_interface
|
} // namespace rtde_interface
|
||||||
|
|||||||
@@ -46,7 +46,7 @@ public:
|
|||||||
* \param robot_ip IP-address under which the robot is reachable.
|
* \param robot_ip IP-address under which the robot is reachable.
|
||||||
* \param script_file URScript file that should be sent to the robot
|
* \param script_file URScript file that should be sent to the robot
|
||||||
*/
|
*/
|
||||||
UrDriver(const std::string& robot_ip, const std::string& script_file);
|
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& recipe_file);
|
||||||
virtual ~UrDriver() = default;
|
virtual ~UrDriver() = default;
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
|
|||||||
@@ -19,6 +19,7 @@
|
|||||||
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller"/>
|
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller"/>
|
||||||
<arg name="stopped_controllers" default=""/>
|
<arg name="stopped_controllers" default=""/>
|
||||||
<arg name="urscript_file" default="$(find ur_rtde_driver)/resources/servoj.urscript"/>
|
<arg name="urscript_file" default="$(find ur_rtde_driver)/resources/servoj.urscript"/>
|
||||||
|
<arg name="rtde_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_recipe.txt"/>
|
||||||
<!-- robot model -->
|
<!-- robot model -->
|
||||||
<include file="$(find ur_description)/launch/ur10_upload.launch">
|
<include file="$(find ur_description)/launch/ur10_upload.launch">
|
||||||
<arg name="limited" value="$(arg limited)"/>
|
<arg name="limited" value="$(arg limited)"/>
|
||||||
@@ -29,6 +30,7 @@
|
|||||||
<node name="ur_hardware_interface" pkg="ur_rtde_driver" type="ur_rtde_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="true">
|
<node name="ur_hardware_interface" pkg="ur_rtde_driver" type="ur_rtde_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="true">
|
||||||
<param name="robot_ip" type="str" value="$(arg robot_ip)"/>
|
<param name="robot_ip" type="str" value="$(arg robot_ip)"/>
|
||||||
<param name="script_file" value="$(arg urscript_file)"/>
|
<param name="script_file" value="$(arg urscript_file)"/>
|
||||||
|
<param name="recipe_file" value="$(arg rtde_recipe_file)"/>
|
||||||
<!--<param name="reverse_port" type="int" value="$(arg reverse_port)" />-->
|
<!--<param name="reverse_port" type="int" value="$(arg reverse_port)" />-->
|
||||||
<!--<param name="min_payload" type="double" value="$(arg min_payload)"/>-->
|
<!--<param name="min_payload" type="double" value="$(arg min_payload)"/>-->
|
||||||
<!--<param name="max_payload" type="double" value="$(arg max_payload)"/>-->
|
<!--<param name="max_payload" type="double" value="$(arg max_payload)"/>-->
|
||||||
|
|||||||
5
ur_rtde_driver/resources/rtde_recipe.txt
Normal file
5
ur_rtde_driver/resources/rtde_recipe.txt
Normal file
@@ -0,0 +1,5 @@
|
|||||||
|
timestamp
|
||||||
|
actual_q
|
||||||
|
actual_qd
|
||||||
|
speed_scaling
|
||||||
|
target_speed_fraction
|
||||||
@@ -20,13 +20,14 @@ int main(int argc, char* argv[])
|
|||||||
{
|
{
|
||||||
std::string robot_ip = "192.168.56.101";
|
std::string robot_ip = "192.168.56.101";
|
||||||
std::string script_filename = "urprog.urscript";
|
std::string script_filename = "urprog.urscript";
|
||||||
|
std::string recipe_filename = "rtde_recipe.txt";
|
||||||
|
|
||||||
if (argc > 2)
|
if (argc > 2)
|
||||||
{
|
{
|
||||||
robot_ip = argv[1];
|
robot_ip = argv[1];
|
||||||
}
|
}
|
||||||
|
|
||||||
UrDriver driver(robot_ip, script_filename);
|
UrDriver driver(robot_ip, script_filename, recipe_filename);
|
||||||
|
|
||||||
while (true)
|
while (true)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -46,14 +46,21 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
|
|||||||
joint_efforts_ = { { 0, 0, 0, 0, 0, 0 } };
|
joint_efforts_ = { { 0, 0, 0, 0, 0, 0 } };
|
||||||
std::string robot_ip = robot_hw_nh.param<std::string>("robot_ip", "192.168.56.101");
|
std::string robot_ip = robot_hw_nh.param<std::string>("robot_ip", "192.168.56.101");
|
||||||
std::string script_filename;
|
std::string script_filename;
|
||||||
|
std::string recipe_filename;
|
||||||
if (!robot_hw_nh.getParam("script_file", script_filename))
|
if (!robot_hw_nh.getParam("script_file", script_filename))
|
||||||
{
|
{
|
||||||
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("script_file") << " not given.");
|
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("script_file") << " not given.");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!robot_hw_nh.getParam("recipe_file", recipe_filename))
|
||||||
|
{
|
||||||
|
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("recipe_file") << " not given.");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
ROS_INFO_STREAM("Initializing urdriver");
|
ROS_INFO_STREAM("Initializing urdriver");
|
||||||
ur_driver_.reset(new UrDriver(robot_ip, script_filename));
|
ur_driver_.reset(new UrDriver(robot_ip, script_filename, recipe_filename));
|
||||||
|
|
||||||
if (!root_nh.getParam("hardware_interface/joints", joint_names_))
|
if (!root_nh.getParam("hardware_interface/joints", joint_names_))
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -31,9 +31,10 @@ namespace ur_driver
|
|||||||
{
|
{
|
||||||
namespace rtde_interface
|
namespace rtde_interface
|
||||||
{
|
{
|
||||||
RTDEClient::RTDEClient(std::string robot_ip, comm::INotifier& notifier)
|
RTDEClient::RTDEClient(std::string robot_ip, comm::INotifier& notifier, const std::string& recipe_file)
|
||||||
: stream_(robot_ip, UR_RTDE_PORT)
|
: stream_(robot_ip, UR_RTDE_PORT)
|
||||||
, parser_(readRecipe())
|
, recipe_(readRecipe(recipe_file))
|
||||||
|
, parser_(recipe_)
|
||||||
, prod_(stream_, parser_)
|
, prod_(stream_, parser_)
|
||||||
, pipeline_(prod_, PIPELINE_NAME, notifier)
|
, pipeline_(prod_, PIPELINE_NAME, notifier)
|
||||||
, max_frequency_(URE_MAX_FREQUENCY)
|
, max_frequency_(URE_MAX_FREQUENCY)
|
||||||
@@ -83,11 +84,11 @@ bool RTDEClient::init()
|
|||||||
LOG_INFO("Setting up RTDE communication with frequency %f", max_frequency_);
|
LOG_INFO("Setting up RTDE communication with frequency %f", max_frequency_);
|
||||||
if (protocol_version == 2)
|
if (protocol_version == 2)
|
||||||
{
|
{
|
||||||
size = ControlPackageSetupOutputsRequest::generateSerializedRequest(buffer, max_frequency_, readRecipe());
|
size = ControlPackageSetupOutputsRequest::generateSerializedRequest(buffer, max_frequency_, recipe_);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
size = ControlPackageSetupOutputsRequest::generateSerializedRequest(buffer, readRecipe());
|
size = ControlPackageSetupOutputsRequest::generateSerializedRequest(buffer, recipe_);
|
||||||
}
|
}
|
||||||
stream_.write(buffer, size, written);
|
stream_.write(buffer, size, written);
|
||||||
return pipeline_.getLatestProduct(package, std::chrono::milliseconds(1000));
|
return pipeline_.getLatestProduct(package, std::chrono::milliseconds(1000));
|
||||||
@@ -104,14 +105,16 @@ bool RTDEClient::start()
|
|||||||
rtde_interface::ControlPackageStart* tmp = dynamic_cast<rtde_interface::ControlPackageStart*>(package.get());
|
rtde_interface::ControlPackageStart* tmp = dynamic_cast<rtde_interface::ControlPackageStart*>(package.get());
|
||||||
return tmp->accepted_;
|
return tmp->accepted_;
|
||||||
}
|
}
|
||||||
std::vector<std::string> RTDEClient::readRecipe()
|
std::vector<std::string> RTDEClient::readRecipe(const std::string& recipe_file)
|
||||||
{
|
{
|
||||||
std::vector<std::string> recipe;
|
std::vector<std::string> recipe;
|
||||||
recipe.push_back("timestamp");
|
std::ifstream file(recipe_file);
|
||||||
recipe.push_back("actual_q");
|
std::string line;
|
||||||
recipe.push_back("actual_qd");
|
while (std::getline(file, line))
|
||||||
recipe.push_back("speed_scaling");
|
{
|
||||||
recipe.push_back("target_speed_fraction");
|
recipe.push_back(line);
|
||||||
|
}
|
||||||
|
recipe_ = recipe;
|
||||||
return recipe;
|
return recipe;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -42,11 +42,12 @@ static const std::string SERVO_J_REPLACE("{{SERVO_J_REPLACE}}");
|
|||||||
static const std::string SERVER_IP_REPLACE("{{SERVER_IP_REPLACE}}");
|
static const std::string SERVER_IP_REPLACE("{{SERVER_IP_REPLACE}}");
|
||||||
static const std::string SERVER_PORT_REPLACE("{{SERVER_PORT_REPLACE}}");
|
static const std::string SERVER_PORT_REPLACE("{{SERVER_PORT_REPLACE}}");
|
||||||
|
|
||||||
ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_file)
|
ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_file,
|
||||||
|
const std::string& recipe_file)
|
||||||
: servoj_time_(0.008), servoj_gain_(750), servoj_lookahead_time_(0.03)
|
: servoj_time_(0.008), servoj_gain_(750), servoj_lookahead_time_(0.03)
|
||||||
{
|
{
|
||||||
LOG_INFO("Initializing RTDE client");
|
LOG_INFO("Initializing RTDE client");
|
||||||
rtde_client_.reset(new rtde_interface::RTDEClient(robot_ip, notifier_));
|
rtde_client_.reset(new rtde_interface::RTDEClient(robot_ip, notifier_, recipe_file));
|
||||||
|
|
||||||
if (!rtde_client_->init())
|
if (!rtde_client_->init())
|
||||||
{
|
{
|
||||||
|
|||||||
Reference in New Issue
Block a user