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

removed unused legacy code

This commit is contained in:
Tristan Schnell
2019-06-13 15:37:36 +02:00
committed by Felix Mauch
parent d0e995ff7c
commit 3aafabec29
18 changed files with 0 additions and 1716 deletions

View File

@@ -1,173 +0,0 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Copyright 2015, 2016 Thomas Timm Andersen (original version)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "ur_rtde_driver/ur/commander.h"
#include "ur_rtde_driver/log.h"
namespace ur_driver
{
bool URCommander::write(const std::string& s)
{
size_t len = s.size();
const uint8_t* data = reinterpret_cast<const uint8_t*>(s.c_str());
size_t written;
return stream_.write(data, len, written);
}
void URCommander::formatArray(std::ostringstream& out, std::array<double, 6>& values)
{
std::string mod("[");
for (auto const& val : values)
{
out << mod << val;
mod = ",";
}
out << "]";
}
bool URCommander::uploadProg(const std::string& s)
{
LOG_DEBUG("Sending program [%s]", s.c_str());
return write(s);
}
bool URCommander::setToolVoltage(uint8_t voltage)
{
if (voltage != 0 || voltage != 12 || voltage != 24)
return false;
std::ostringstream out;
out << "set_tool_voltage(" << (int)voltage << ")\n";
std::string s(out.str());
return write(s);
}
bool URCommander::setFlag(uint8_t pin, bool value)
{
std::ostringstream out;
out << "set_flag(" << (int)pin << "," << (value ? "True" : "False") << ")\n";
std::string s(out.str());
return write(s);
}
bool URCommander::setPayload(double value)
{
std::ostringstream out;
out << "set_payload(" << std::fixed << std::setprecision(5) << value << ")\n";
std::string s(out.str());
return write(s);
}
bool URCommander::stopj(double a)
{
std::ostringstream out;
out << "stopj(" << std::fixed << std::setprecision(5) << a << ")\n";
std::string s(out.str());
return write(s);
}
bool URCommander_V1_X::speedj(std::array<double, 6>& speeds, double acceleration)
{
std::ostringstream out;
out << std::fixed << std::setprecision(5);
out << "speedj(";
formatArray(out, speeds);
out << "," << acceleration << "," << 0.02 << ")\n";
std::string s(out.str());
return write(s);
}
bool URCommander_V1_X::setAnalogOut(uint8_t pin, double value)
{
std::ostringstream out;
out << "sec io_fun():\n"
<< "set_analog_out(" << (int)pin << "," << std::fixed << std::setprecision(4) << value << ")\n"
<< "end\n";
std::string s(out.str());
return write(s);
}
bool URCommander_V1_X::setDigitalOut(uint8_t pin, bool value)
{
std::ostringstream out;
out << "sec io_fun():\n"
<< "set_digital_out(" << (int)pin << "," << (value ? "True" : "False") << ")\n"
<< "end\n";
std::string s(out.str());
return write(s);
}
bool URCommander_V3_X::setAnalogOut(uint8_t pin, double value)
{
std::ostringstream out;
out << "sec io_fun():\n"
<< "set_standard_analog_out(" << (int)pin << "," << std::fixed << std::setprecision(5) << value << ")\n"
<< "end\n";
std::string s(out.str());
return write(s);
}
bool URCommander_V3_X::setDigitalOut(uint8_t pin, bool value)
{
std::ostringstream out;
std::string func;
if (pin < 8)
{
func = "set_standard_digital_out";
}
else if (pin < 16)
{
func = "set_configurable_digital_out";
pin -= 8;
}
else if (pin < 18)
{
func = "set_tool_digital_out";
pin -= 16;
}
else
return false;
out << "sec io_fun():\n"
<< func << "(" << (int)pin << "," << (value ? "True" : "False") << ")\n"
<< "end\n";
std::string s(out.str());
return write(s);
}
bool URCommander_V3_1__2::speedj(std::array<double, 6>& speeds, double acceleration)
{
std::ostringstream out;
out << std::fixed << std::setprecision(5);
out << "speedj(";
formatArray(out, speeds);
out << "," << acceleration << ")\n";
std::string s(out.str());
return write(s);
}
bool URCommander_V3_3::speedj(std::array<double, 6>& speeds, double acceleration)
{
std::ostringstream out;
out << std::fixed << std::setprecision(5);
out << "speedj(";
formatArray(out, speeds);
out << "," << acceleration << "," << 0.008 << ")\n";
std::string s(out.str());
return write(s);
}
} // namespace ur_driver

View File

@@ -1,124 +0,0 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Copyright 2015, 2016 Thomas Timm Andersen (original version)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "ur_rtde_driver/ur/master_board.h"
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_driver
{
bool SharedMasterBoardData::parseWith(BinParser& bp)
{
bp.parse(analog_input_range0);
bp.parse(analog_input_range1);
bp.parse(analog_input0);
bp.parse(analog_input1);
bp.parse(analog_output_domain0);
bp.parse(analog_output_domain1);
bp.parse(analog_output0);
bp.parse(analog_output1);
bp.parse(master_board_temperature);
bp.parse(robot_voltage_48V);
bp.parse(robot_current);
bp.parse(master_IO_current);
return true;
}
bool MasterBoardData_V1_X::parseWith(BinParser& bp)
{
if (!bp.checkSize<MasterBoardData_V1_X>())
return false;
bp.parse<uint16_t, 10>(digital_input_bits);
bp.parse<uint16_t, 10>(digital_output_bits);
SharedMasterBoardData::parseWith(bp);
bp.parse(master_safety_state);
bp.parse(master_on_off_state);
bp.parse(euromap67_interface_installed);
if (euromap67_interface_installed)
{
if (!bp.checkSize(MasterBoardData_V1_X::EURO_SIZE))
return false;
bp.parse(euromap_input_bits);
bp.parse(euromap_output_bits);
bp.parse(euromap_voltage);
bp.parse(euromap_current);
}
return true;
}
bool MasterBoardData_V3_0__1::parseWith(BinParser& bp)
{
if (!bp.checkSize<MasterBoardData_V3_0__1>())
return false;
bp.parse<uint32_t, 18>(digital_input_bits);
bp.parse<uint32_t, 18>(digital_output_bits);
SharedMasterBoardData::parseWith(bp);
bp.parse(safety_mode);
bp.parse(in_reduced_mode);
bp.parse(euromap67_interface_installed);
if (euromap67_interface_installed)
{
if (!bp.checkSize(MasterBoardData_V3_0__1::EURO_SIZE))
return false;
bp.parse(euromap_input_bits);
bp.parse(euromap_output_bits);
bp.parse(euromap_voltage);
bp.parse(euromap_current);
}
bp.consume(sizeof(uint32_t));
return true;
}
bool MasterBoardData_V3_2::parseWith(BinParser& bp)
{
if (!bp.checkSize<MasterBoardData_V3_2>())
return false;
MasterBoardData_V3_0__1::parseWith(bp);
bp.parse(operational_mode_selector_input);
bp.parse(three_position_enabling_device_input);
return true;
}
bool MasterBoardData_V1_X::consumeWith(URStatePacketConsumer& consumer)
{
return consumer.consume(*this);
}
bool MasterBoardData_V3_0__1::consumeWith(URStatePacketConsumer& consumer)
{
return consumer.consume(*this);
}
bool MasterBoardData_V3_2::consumeWith(URStatePacketConsumer& consumer)
{
return consumer.consume(*this);
}
} // namespace ur_driver

View File

@@ -1,40 +0,0 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Copyright 2015, 2016 Thomas Timm Andersen (original version)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "ur_rtde_driver/ur/messages.h"
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_driver
{
bool VersionMessage::parseWith(BinParser& bp)
{
bp.parse(project_name);
bp.parse(major_version);
bp.parse(minor_version);
bp.parse(svn_version);
bp.consume(sizeof(uint32_t)); // undocumented field??
bp.parseRemainder(build_date);
return true; // not really possible to check dynamic size packets
}
bool VersionMessage::consumeWith(URMessagePacketConsumer& consumer)
{
return consumer.consume(*this);
}
} // namespace ur_driver

View File

@@ -1,105 +0,0 @@
/*
* Copyright 2017, 2018 Simon Rasmussen (refactor)
*
* Copyright 2015, 2016 Thomas Timm Andersen (original version)
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "ur_rtde_driver/ur/robot_mode.h"
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_driver
{
bool SharedRobotModeData::parseWith(BinParser& bp)
{
bp.parse(timestamp);
bp.parse(physical_robot_connected);
bp.parse(real_robot_enabled);
bp.parse(robot_power_on);
bp.parse(emergency_stopped);
bp.parse(protective_stopped);
bp.parse(program_running);
bp.parse(program_paused);
return true;
}
bool RobotModeData_V1_X::parseWith(BinParser& bp)
{
if (!bp.checkSize<RobotModeData_V1_X>())
return false;
SharedRobotModeData::parseWith(bp);
bp.parse(robot_mode);
bp.parse(speed_fraction);
return true;
}
bool RobotModeData_V3_0__1::parseWith(BinParser& bp)
{
if (!bp.checkSize<RobotModeData_V3_0__1>())
return false;
SharedRobotModeData::parseWith(bp);
bp.parse(robot_mode);
bp.parse(control_mode);
bp.parse(target_speed_fraction);
bp.parse(speed_scaling);
return true;
}
bool RobotModeData_V3_2::parseWith(BinParser& bp)
{
if (!bp.checkSize<RobotModeData_V3_2>())
return false;
RobotModeData_V3_0__1::parseWith(bp);
bp.parse(target_speed_fraction_limit);
return true;
}
bool RobotModeData_V3_5::parseWith(BinParser& bp)
{
if (!bp.checkSize<RobotModeData_V3_5>())
return false;
RobotModeData_V3_2::parseWith(bp);
bp.parse(unknown_internal_use);
return true;
}
bool RobotModeData_V1_X::consumeWith(URStatePacketConsumer& consumer)
{
return consumer.consume(*this);
}
bool RobotModeData_V3_0__1::consumeWith(URStatePacketConsumer& consumer)
{
return consumer.consume(*this);
}
bool RobotModeData_V3_2::consumeWith(URStatePacketConsumer& consumer)
{
return consumer.consume(*this);
}
bool RobotModeData_V3_5::consumeWith(URStatePacketConsumer& consumer)
{
return consumer.consume(*this);
}
} // namespace ur_driver