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

implemented setting of speed_slider via ROS topic

This commit is contained in:
Tristan Schnell
2019-07-31 13:05:24 +02:00
parent 323125f84d
commit dc660b854d
5 changed files with 55 additions and 10 deletions

View File

@@ -40,7 +40,7 @@ RTDEClient::RTDEClient(std::string robot_ip, comm::INotifier& notifier, const st
, parser_(recipe_)
, prod_(stream_, parser_)
, pipeline_(prod_, PIPELINE_NAME, notifier)
, writer_(&stream_, input_recipe_file)
, writer_(&stream_, input_recipe_)
, max_frequency_(URE_MAX_FREQUENCY)
{
}

View File

@@ -31,35 +31,63 @@ namespace ur_driver
{
namespace rtde_interface
{
RTDEWriter::RTDEWriter(comm::URStream<PackageHeader>* stream, const std::string& recipe_file) : stream_(stream)
RTDEWriter::RTDEWriter(comm::URStream<PackageHeader>* stream, const std::vector<std::string>& recipe)
: stream_(stream), recipe_(recipe), queue_{ 32 }
{
}
bool RTDEWriter::init(uint8_t recipe_id)
void RTDEWriter::init(uint8_t recipe_id)
{
return false;
recipe_id_ = recipe_id;
writer_thread_ = std::thread(&RTDEWriter::run, this);
}
bool RTDEWriter::start()
void RTDEWriter::run()
{
return false;
uint8_t buffer[4096];
size_t size;
size_t written;
std::unique_ptr<DataPackage> package;
while (true)
{
queue_.waitDequeue(package);
package->setRecipeID(recipe_id_);
size = package->serializePackage(buffer);
stream_->write(buffer, size, written);
}
}
bool RTDEWriter::sendSpeedSlider(double speed_slider_fraction)
{
return false;
std::unique_ptr<DataPackage> package;
package.reset(new DataPackage(recipe_));
package->initEmpty();
uint32_t mask = 1;
package->setData("speed_slider_mask", mask);
package->setData("speed_slider_fraction", speed_slider_fraction);
if (!queue_.tryEnqueue(std::move(package)))
{
return false;
}
return true;
}
bool RTDEWriter::sendStandardDigitalOutput(uint8_t output_pin, bool value)
{
return false;
}
bool RTDEWriter::sendConfigurableDigitalOutput(uint8_t output_pin, bool value)
{
return false;
}
bool RTDEWriter::sendToolDigitalOutput(bool value)
{
return false;
}
bool RTDEWriter::sendStandardAnalogOuput(uint8_t output_pin, bool value)
{
return false;