1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +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,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.
*/
#pragma once
#include <chrono>
#include <cstdlib>
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_driver
{
class EventCounter : public URRTPacketConsumer
{
private:
typedef std::chrono::high_resolution_clock Clock;
Clock::time_point events_[250];
size_t idx_ = 0;
Clock::time_point last_;
public:
void trigger()
{
// auto now = Clock::now();
// LOG_INFO("Time diff: %d ms", std::chrono::duration_cast<std::chrono::microseconds>(now - last_));
// last_ = now;
// return;
events_[idx_] = Clock::now();
idx_ += 1;
if (idx_ > 250)
{
std::chrono::time_point<std::chrono::high_resolution_clock> t_min =
std::chrono::time_point<std::chrono::high_resolution_clock>::max();
std::chrono::time_point<std::chrono::high_resolution_clock> t_max =
std::chrono::time_point<std::chrono::high_resolution_clock>::min();
for (auto const& e : events_)
{
if (e < t_min)
t_min = e;
if (e > t_max)
t_max = e;
}
auto diff = t_max - t_min;
auto secs = std::chrono::duration_cast<std::chrono::seconds>(diff).count();
auto ms = std::chrono::duration_cast<std::chrono::microseconds>(diff).count();
std::chrono::duration<double> test(t_max - t_min);
LOG_INFO("Recieved 250 messages at %f Hz", (250.0 / test.count()));
idx_ = 0;
}
}
public:
bool consume(RTState_V1_6__7& state)
{
trigger();
return true;
}
bool consume(RTState_V1_8& state)
{
trigger();
return true;
}
bool consume(RTState_V3_0__1& state)
{
trigger();
return true;
}
bool consume(RTState_V3_2__3& state)
{
trigger();
return true;
}
void setupConsumer()
{
last_ = Clock::now();
}
void teardownConsumer()
{
}
void stopConsumer()
{
}
};
} // namespace ur_driver

View File

@@ -1,82 +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.
*/
#pragma once
#include <ros/ros.h>
#include <ur_msgs/SetIO.h>
#include <ur_msgs/SetIORequest.h>
#include <ur_msgs/SetIOResponse.h>
#include <ur_msgs/SetPayload.h>
#include <ur_msgs/SetPayloadRequest.h>
#include <ur_msgs/SetPayloadResponse.h>
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/commander.h"
namespace ur_driver
{
class IOService
{
private:
ros::NodeHandle nh_;
URCommander& commander_;
ros::ServiceServer io_service_;
ros::ServiceServer payload_service_;
bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& resp)
{
LOG_INFO("setIO called with [%d, %d]", req.fun, req.pin);
bool res = false;
bool flag = req.state > 0.0 ? true : false;
switch (req.fun)
{
case ur_msgs::SetIO::Request::FUN_SET_DIGITAL_OUT:
res = commander_.setDigitalOut(req.pin, flag);
break;
case ur_msgs::SetIO::Request::FUN_SET_ANALOG_OUT:
res = commander_.setAnalogOut(req.pin, req.state);
break;
case ur_msgs::SetIO::Request::FUN_SET_TOOL_VOLTAGE:
res = commander_.setToolVoltage(static_cast<uint8_t>(req.state));
break;
case ur_msgs::SetIO::Request::FUN_SET_FLAG:
res = commander_.setFlag(req.pin, flag);
break;
default:
LOG_WARN("Invalid setIO function called (%d)", req.fun);
}
return (resp.success = res);
}
bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& resp)
{
LOG_INFO("setPayload called");
// TODO check min and max payload?
return (resp.success = commander_.setPayload(req.payload));
}
public:
IOService(URCommander& commander)
: commander_(commander)
, io_service_(nh_.advertiseService("ur_driver/set_io", &IOService::setIO, this))
, payload_service_(nh_.advertiseService("ur_driver/set_payload", &IOService::setPayload, this))
{
}
};
} // namespace ur_driver

View File

@@ -1,91 +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.
*/
#pragma once
#include <ros/ros.h>
#include <std_srvs/Empty.h>
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_driver
{
enum class RobotState
{
Running,
Error,
EmergencyStopped,
ProtectiveStopped
};
enum class ActivationMode
{
Never,
Always,
OnStartup
};
class Service
{
public:
virtual void onRobotStateChange(RobotState state) = 0;
};
class ServiceStopper : public URStatePacketConsumer
{
private:
ros::NodeHandle nh_;
ros::ServiceServer enable_service_;
std::vector<Service*> services_;
RobotState last_state_;
ActivationMode activation_mode_;
void notify_all(RobotState state);
bool handle(SharedRobotModeData& data, bool error);
bool enableCallback(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& resp);
public:
ServiceStopper(std::vector<Service*> services);
virtual bool consume(RobotModeData_V1_X& data)
{
return handle(data, data.robot_mode != robot_mode_V1_X::ROBOT_RUNNING_MODE);
}
virtual bool consume(RobotModeData_V3_0__1& data)
{
return handle(data, data.robot_mode != robot_mode_V3_X::RUNNING);
}
virtual bool consume(RobotModeData_V3_2& data)
{
return handle(data, data.robot_mode != robot_mode_V3_X::RUNNING);
}
// unused
virtual bool consume(MasterBoardData_V1_X& data)
{
return true;
}
virtual bool consume(MasterBoardData_V3_0__1& data)
{
return true;
}
virtual bool consume(MasterBoardData_V3_2& data)
{
return true;
}
};
} // namespace ur_driver

View File

@@ -1,99 +0,0 @@
/*
* Copyright 2019, FZI Forschungszentrum Informatik (templating)
*
* 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.
*/
#pragma once
#include <array>
#include <iomanip>
#include <sstream>
#include "ur_rtde_driver/comm/stream.h"
#include "ur_rtde_driver/primary/package_header.h"
namespace ur_driver
{
class URCommander
{
private:
comm::URStream<primary_interface::PackageHeader>& stream_;
protected:
bool write(const std::string& s);
void formatArray(std::ostringstream& out, std::array<double, 6>& values);
public:
URCommander(comm::URStream<primary_interface::PackageHeader>& stream) : stream_(stream)
{
}
virtual bool speedj(std::array<double, 6>& speeds, double acceleration) = 0;
virtual bool setDigitalOut(uint8_t pin, bool value) = 0;
virtual bool setAnalogOut(uint8_t pin, double value) = 0;
// shared
bool uploadProg(const std::string& s);
bool stopj(double a = 10.0);
bool setToolVoltage(uint8_t voltage);
bool setFlag(uint8_t pin, bool value);
bool setPayload(double value);
};
class URCommander_V1_X : public URCommander
{
public:
URCommander_V1_X(comm::URStream<primary_interface::PackageHeader>& stream) : URCommander(stream)
{
}
virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
virtual bool setDigitalOut(uint8_t pin, bool value);
virtual bool setAnalogOut(uint8_t pin, double value);
};
class URCommander_V3_X : public URCommander
{
public:
URCommander_V3_X(comm::URStream<primary_interface::PackageHeader>& stream) : URCommander(stream)
{
}
virtual bool speedj(std::array<double, 6>& speeds, double acceleration) = 0;
virtual bool setDigitalOut(uint8_t pin, bool value);
virtual bool setAnalogOut(uint8_t pin, double value);
};
class URCommander_V3_1__2 : public URCommander_V3_X
{
public:
URCommander_V3_1__2(comm::URStream<primary_interface::PackageHeader>& stream) : URCommander_V3_X(stream)
{
}
virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
};
class URCommander_V3_3 : public URCommander_V3_X
{
public:
URCommander_V3_3(comm::URStream<primary_interface::PackageHeader>& stream) : URCommander_V3_X(stream)
{
}
virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
};
} // namespace ur_driver

View File

@@ -1,71 +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.
*/
#pragma once
#include "ur_rtde_driver/comm/pipeline.h"
#include "ur_rtde_driver/ur/master_board.h"
#include "ur_rtde_driver/ur/messages.h"
#include "ur_rtde_driver/ur/robot_mode.h"
#include "ur_rtde_driver/ur/rt_state.h"
#include "ur_rtde_driver/ur/state.h"
namespace ur_driver
{
class URRTPacketConsumer : public comm::IConsumer<RTPacket>
{
public:
virtual bool consume(std::shared_ptr<RTPacket> packet)
{
return packet->consumeWith(*this);
}
virtual bool consume(RTState_V1_6__7& state) = 0;
virtual bool consume(RTState_V1_8& state) = 0;
virtual bool consume(RTState_V3_0__1& state) = 0;
virtual bool consume(RTState_V3_2__3& state) = 0;
};
class URStatePacketConsumer : public comm::IConsumer<StatePacket>
{
public:
virtual bool consume(std::shared_ptr<StatePacket> packet)
{
return packet->consumeWith(*this);
}
virtual bool consume(MasterBoardData_V1_X& data) = 0;
virtual bool consume(MasterBoardData_V3_0__1& data) = 0;
virtual bool consume(MasterBoardData_V3_2& data) = 0;
virtual bool consume(RobotModeData_V1_X& data) = 0;
virtual bool consume(RobotModeData_V3_0__1& data) = 0;
virtual bool consume(RobotModeData_V3_2& data) = 0;
};
class URMessagePacketConsumer : public comm::IConsumer<MessagePacket>
{
public:
virtual bool consume(std::shared_ptr<MessagePacket> packet)
{
return packet->consumeWith(*this);
}
virtual bool consume(VersionMessage& message) = 0;
};
} // namespace ur_driver

View File

@@ -1,144 +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.
*/
#pragma once
#include <cstdlib>
#include "ur_rtde_driver/comm/parser.h"
#include "ur_rtde_driver/comm/stream.h"
#include "ur_rtde_driver/ur/consumer.h"
#include "ur_rtde_driver/ur/messages_parser.h"
#include "ur_rtde_driver/ur/producer.h"
#include "ur_rtde_driver/ur/rt_parser.h"
#include "ur_rtde_driver/ur/state_parser.h"
namespace ur_driver
{
static const int UR_PRIMARY_PORT = 30001;
class URFactory : private URMessagePacketConsumer
{
private:
comm::URStream stream_;
URMessageParser parser_;
uint8_t major_version_;
uint8_t minor_version_;
bool consume(VersionMessage& vm)
{
LOG_INFO("Got VersionMessage:");
LOG_INFO("project name: %s", vm.project_name.c_str());
LOG_INFO("version: %u.%u.%d", vm.major_version, vm.minor_version, vm.svn_version);
LOG_INFO("build date: %s", vm.build_date.c_str());
major_version_ = vm.major_version;
minor_version_ = vm.minor_version;
return true;
}
void setupConsumer()
{
}
void teardownConsumer()
{
}
void stopConsumer()
{
}
public:
URFactory(std::string& host) : stream_(host, UR_PRIMARY_PORT)
{
URProducer<MessagePacket> prod(stream_, parser_);
std::vector<std::unique_ptr<MessagePacket>> results;
prod.setupProducer();
if (!prod.tryGet(results) || results.size() == 0)
{
LOG_FATAL("No version message received, init failed!");
std::exit(EXIT_FAILURE);
}
for (auto const& p : results)
{
p->consumeWith(*this);
}
if (major_version_ == 0 && minor_version_ == 0)
{
LOG_FATAL("No version message received, init failed!");
std::exit(EXIT_FAILURE);
}
prod.teardownProducer();
}
bool isVersion3()
{
return major_version_ == 3;
}
std::unique_ptr<URCommander> getCommander(comm::URStream& stream)
{
if (major_version_ == 1)
return std::unique_ptr<URCommander>(new URCommander_V1_X(stream));
else if (minor_version_ < 3)
return std::unique_ptr<URCommander>(new URCommander_V3_1__2(stream));
else
return std::unique_ptr<URCommander>(new URCommander_V3_3(stream));
}
std::unique_ptr<comm::URParser<StatePacket>> getStateParser()
{
if (major_version_ == 1)
{
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V1_X);
}
else
{
if (minor_version_ < 3)
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V3_0__1);
else if (minor_version_ < 5)
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V3_2);
else
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V3_5);
}
}
std::unique_ptr<comm::URParser<RTPacket>> getRTParser()
{
if (major_version_ == 1)
{
if (minor_version_ < 8)
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V1_6__7);
else
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V1_8);
}
else
{
if (minor_version_ < 3)
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V3_0__1);
else
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V3_2__3);
}
}
};
} // namespace ur_driver

View File

@@ -1,72 +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.
*/
#pragma once
#include <inttypes.h>
#include <cstddef>
#include "ur_rtde_driver/bin_parser.h"
#include "ur_rtde_driver/comm/pipeline.h"
namespace ur_driver
{
enum class robot_message_type : uint8_t
{
ROBOT_MESSAGE_TEXT = 0,
ROBOT_MESSAGE_PROGRAM_LABEL = 1,
PROGRAM_STATE_MESSAGE_VARIABLE_UPDATE = 2,
ROBOT_MESSAGE_VERSION = 3,
ROBOT_MESSAGE_SAFETY_MODE = 5,
ROBOT_MESSAGE_ERROR_CODE = 6,
ROBOT_MESSAGE_KEY = 7,
ROBOT_MESSAGE_REQUEST_VALUE = 9,
ROBOT_MESSAGE_RUNTIME_EXCEPTION = 10
};
class URMessagePacketConsumer;
class MessagePacket
{
public:
MessagePacket(uint64_t timestamp, uint8_t source) : timestamp(timestamp), source(source)
{
}
virtual bool parseWith(BinParser& bp) = 0;
virtual bool consumeWith(URMessagePacketConsumer& consumer) = 0;
uint64_t timestamp;
uint8_t source;
};
class VersionMessage : public MessagePacket
{
public:
VersionMessage(uint64_t timestamp, uint8_t source) : MessagePacket(timestamp, source)
{
}
virtual bool parseWith(BinParser& bp);
virtual bool consumeWith(URMessagePacketConsumer& consumer);
std::string project_name;
uint8_t major_version;
uint8_t minor_version;
int32_t svn_version;
std::string build_date;
};
} // namespace ur_driver

View File

@@ -1,74 +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.
*/
#pragma once
#include <vector>
#include "ur_rtde_driver/bin_parser.h"
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/parser.h"
#include "ur_rtde_driver/comm/pipeline.h"
#include "ur_rtde_driver/ur/messages.h"
namespace ur_driver
{
class URMessageParser : public comm::URParser<MessagePacket>
{
public:
bool parse(BinParser& bp, std::vector<std::unique_ptr<MessagePacket>>& results)
{
int32_t packet_size;
message_type type;
bp.parse(packet_size);
bp.parse(type);
if (type != message_type::ROBOT_MESSAGE)
{
LOG_WARN("Invalid message type recieved: %u", static_cast<uint8_t>(type));
return false;
}
uint64_t timestamp;
uint8_t source;
robot_message_type message_type;
bp.parse(timestamp);
bp.parse(source);
bp.parse(message_type);
std::unique_ptr<MessagePacket> result;
bool parsed = false;
switch (message_type)
{
case robot_message_type::ROBOT_MESSAGE_VERSION:
{
VersionMessage* vm = new VersionMessage(timestamp, source);
parsed = vm->parseWith(bp);
result.reset(vm);
break;
}
default:
return false;
}
results.push_back(std::move(result));
return parsed;
}
};
} // namespace ur_driver

View File

@@ -1,139 +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.
*/
#pragma once
#include <inttypes.h>
#include <cstddef>
#include "ur_rtde_driver/comm/bin_parser.h"
#include "ur_rtde_driver/types.h"
#include "ur_rtde_driver/comm/ur/state.h"
namespace ur_driver
{
class SharedRobotModeData
{
public:
virtual bool parseWith(BinParser& bp);
uint64_t timestamp;
bool physical_robot_connected;
bool real_robot_enabled;
bool robot_power_on;
bool emergency_stopped;
bool protective_stopped; // AKA security_stopped
bool program_running;
bool program_paused;
static const size_t SIZE = sizeof(uint64_t) + sizeof(uint8_t) * 6;
};
enum class robot_mode_V1_X : uint8_t
{
ROBOT_RUNNING_MODE = 0,
ROBOT_FREEDRIVE_MODE = 1,
ROBOT_READY_MODE = 2,
ROBOT_INITIALIZING_MODE = 3,
ROBOT_SECURITY_STOPPED_MODE = 4,
ROBOT_EMERGENCY_STOPPED_MODE = 5,
ROBOT_FATAL_ERROR_MODE = 6,
ROBOT_NO_POWER_MODE = 7,
ROBOT_NOT_CONNECTED_MODE = 8,
ROBOT_SHUTDOWN_MODE = 9,
ROBOT_SAFEGUARD_STOP_MODE = 10
};
class RobotModeData_V1_X : public SharedRobotModeData, public StatePacket
{
public:
virtual bool parseWith(BinParser& bp);
virtual bool consumeWith(URStatePacketConsumer& consumer);
robot_mode_V1_X robot_mode;
double speed_fraction;
static const size_t SIZE = SharedRobotModeData::SIZE + sizeof(uint8_t) + sizeof(robot_mode_V1_X) + sizeof(double);
static_assert(RobotModeData_V1_X::SIZE == 24, "RobotModeData_V1_X has missmatched size");
};
enum class robot_mode_V3_X : uint8_t
{
DISCONNECTED = 0,
CONFIRM_SAFETY = 1,
BOOTING = 2,
POWER_OFF = 3,
POWER_ON = 4,
IDLE = 5,
BACKDRIVE = 6,
RUNNING = 7,
UPDATING_FIRMWARE = 8
};
enum class robot_control_mode_V3_X : uint8_t
{
POSITION = 0,
TEACH = 1,
FORCE = 2,
TORQUE = 3
};
class RobotModeData_V3_0__1 : public SharedRobotModeData, public StatePacket
{
public:
virtual bool parseWith(BinParser& bp);
virtual bool consumeWith(URStatePacketConsumer& consumer);
robot_mode_V3_X robot_mode;
robot_control_mode_V3_X control_mode;
double target_speed_fraction;
double speed_scaling;
static const size_t SIZE = SharedRobotModeData::SIZE + sizeof(uint8_t) + sizeof(robot_mode_V3_X) +
sizeof(robot_control_mode_V3_X) + sizeof(double) + sizeof(double);
static_assert(RobotModeData_V3_0__1::SIZE == 33, "RobotModeData_V3_0__1 has missmatched size");
};
class RobotModeData_V3_2 : public RobotModeData_V3_0__1
{
public:
virtual bool parseWith(BinParser& bp);
virtual bool consumeWith(URStatePacketConsumer& consumer);
double target_speed_fraction_limit;
static const size_t SIZE = RobotModeData_V3_0__1::SIZE + sizeof(double);
static_assert(RobotModeData_V3_2::SIZE == 41, "RobotModeData_V3_2 has missmatched size");
};
class RobotModeData_V3_5 : public RobotModeData_V3_2
{
public:
virtual bool parseWith(BinParser& bp);
virtual bool consumeWith(URStatePacketConsumer& consumer);
unsigned char unknown_internal_use;
static const size_t SIZE = RobotModeData_V3_2::SIZE + sizeof(unsigned char);
static_assert(RobotModeData_V3_5::SIZE == 42, "RobotModeData_V3_5 has missmatched size");
};
} // namespace ur_driver

View File

@@ -1,59 +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.
*/
#pragma once
#include <vector>
#include "ur_rtde_driver/bin_parser.h"
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/pipeline.h"
#include "ur_rtde_driver/comm/parser.h"
#include "ur_rtde_driver/ur/rt_state.h"
namespace ur_driver
{
template <typename T>
class URRTStateParser : public comm::URParser<RTPacket>
{
public:
bool parse(BinParser& bp, std::vector<std::unique_ptr<RTPacket>>& results)
{
int32_t packet_size = bp.peek<int32_t>();
if (!bp.checkSize(packet_size))
{
LOG_ERROR("Buffer len shorter than expected packet length");
return false;
}
bp.parse(packet_size); // consumes the peeked data
std::unique_ptr<RTPacket> packet(new T);
if (!packet->parseWith(bp))
return false;
results.push_back(std::move(packet));
return true;
}
};
typedef URRTStateParser<RTState_V1_6__7> URRTStateParser_V1_6__7;
typedef URRTStateParser<RTState_V1_8> URRTStateParser_V1_8;
typedef URRTStateParser<RTState_V3_0__1> URRTStateParser_V3_0__1;
typedef URRTStateParser<RTState_V3_2__3> URRTStateParser_V3_2__3;
} // namespace ur_driver

View File

@@ -1,64 +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.
*/
#pragma once
#include <inttypes.h>
#include <cstddef>
#include "ur_rtde_driver/bin_parser.h"
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/pipeline.h"
namespace ur_driver
{
enum class package_type : uint8_t
{
ROBOT_MODE_DATA = 0,
JOINT_DATA = 1,
TOOL_DATA = 2,
MASTERBOARD_DATA = 3,
CARTESIAN_INFO = 4,
KINEMATICS_INFO = 5,
CONFIGURATION_DATA = 6,
FORCE_MODE_DATA = 7,
ADDITIONAL_INFO = 8,
CALIBRATION_DATA = 9
};
enum class message_type : uint8_t
{
ROBOT_STATE = 16,
ROBOT_MESSAGE = 20,
PROGRAM_STATE_MESSAGE = 25
};
class URStatePacketConsumer;
class StatePacket
{
public:
StatePacket()
{
}
virtual ~StatePacket()
{
}
virtual bool parseWith(BinParser& bp) = 0;
virtual bool consumeWith(URStatePacketConsumer& consumer) = 0;
};
} // namespace ur_driver

View File

@@ -1,120 +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.
*/
#pragma once
#include <vector>
#include "ur_rtde_driver/bin_parser.h"
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/parser.h"
#include "ur_rtde_driver/comm/pipeline.h"
#include "ur_rtde_driver/ur/master_board.h"
#include "ur_rtde_driver/ur/robot_mode.h"
#include "ur_rtde_driver/ur/state.h"
namespace ur_driver
{
template <typename RMD, typename MBD>
class URStateParser : public comm::URParser<StatePacket>
{
private:
StatePacket* from_type(package_type type)
{
switch (type)
{
case package_type::ROBOT_MODE_DATA:
return new RMD;
case package_type::MASTERBOARD_DATA:
return new MBD;
default:
return nullptr;
}
}
public:
bool parse(BinParser& bp, std::vector<std::unique_ptr<StatePacket>>& results)
{
int32_t packet_size;
message_type type;
bp.parse(packet_size);
bp.parse(type);
if (type != message_type::ROBOT_STATE)
{
// quietly ignore the intial version message
if (type != message_type::ROBOT_MESSAGE)
{
LOG_WARN("Invalid state message type recieved: %u", static_cast<uint8_t>(type));
}
bp.consume();
return true;
}
while (!bp.empty())
{
if (!bp.checkSize(sizeof(uint32_t)))
{
LOG_ERROR("Failed to read sub-package length, there's likely a parsing error");
return false;
}
uint32_t sub_size = bp.peek<uint32_t>();
if (!bp.checkSize(static_cast<size_t>(sub_size)))
{
LOG_WARN("Invalid sub-package size of %" PRIu32 " received!", sub_size);
return false;
}
// deconstruction of a sub parser will increment the position of the parent parser
BinParser sbp(bp, sub_size);
sbp.consume(sizeof(sub_size));
package_type type;
sbp.parse(type);
std::unique_ptr<StatePacket> packet(from_type(type));
if (packet == nullptr)
{
sbp.consume();
continue;
}
if (!packet->parseWith(sbp))
{
LOG_ERROR("Sub-package parsing of type %d failed!", static_cast<int>(type));
return false;
}
results.push_back(std::move(packet));
if (!sbp.empty())
{
LOG_ERROR("Sub-package of type %d was not parsed completely!", static_cast<int>(type));
sbp.debug();
return false;
}
}
return true;
}
};
typedef URStateParser<RobotModeData_V1_X, MasterBoardData_V1_X> URStateParser_V1_X;
typedef URStateParser<RobotModeData_V3_0__1, MasterBoardData_V3_0__1> URStateParser_V3_0__1;
typedef URStateParser<RobotModeData_V3_2, MasterBoardData_V3_2> URStateParser_V3_2;
typedef URStateParser<RobotModeData_V3_5, MasterBoardData_V3_2> URStateParser_V3_5;
} // namespace ur_driver

View File

@@ -1,57 +0,0 @@
// this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
// -- BEGIN LICENSE BLOCK ----------------------------------------------
// -- END LICENSE BLOCK ------------------------------------------------
//----------------------------------------------------------------------
/*!\file
*
* \author Felix Mauch mauch@fzi.de
* \date 2018-12-11
*
*/
//----------------------------------------------------------------------
#include <ur_rtde_driver/comm/producer.h>
#include <ur_rtde_driver/comm/shell_consumer.h>
#include <ur_rtde_driver/comm/stream.h>
#include <ur_rtde_driver/comm/parser.h>
#include <ur_rtde_driver/comm/pipeline.h>
#include <ur_rtde_driver/primary/package_header.h>
#include <ur_rtde_driver/primary/primary_parser.h>
static const int UR_PRIMARY_PORT = 30001;
static const int UR_SECONDARY_PORT = 30002;
static const int UR_RT_PORT = 30003;
using namespace ur_driver;
using namespace primary_interface;
int main(int argc, char* argv[])
{
std::string ROBOT_IP = "192.168.56.101";
// std::string ROBOT_IP = "192.168.0.104";
comm::URStream<PackageHeader> stream(ROBOT_IP, UR_PRIMARY_PORT);
if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug))
{
ros::console::notifyLoggerLevelsChanged();
}
primary_interface::PrimaryParser parser;
comm::URProducer<PackageHeader> prod(stream, parser);
comm::ShellConsumer<PackageHeader> consumer;
comm::INotifier notifier;
comm::Pipeline<PackageHeader> pipeline(prod, consumer, "Pipeline", notifier);
LOG_INFO("Running now");
pipeline.run();
while (true)
{
sleep(1);
// LOG_INFO("Still running");
}
return 0;
}

View File

@@ -1,97 +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/ros/service_stopper.h"
namespace ur_driver
{
ServiceStopper::ServiceStopper(std::vector<Service*> services)
: enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this))
, services_(services)
, last_state_(RobotState::Error)
, activation_mode_(ActivationMode::Never)
{
std::string mode;
ros::param::param("~require_activation", mode, std::string("Never"));
if (mode == "Always")
{
activation_mode_ = ActivationMode::Always;
}
else if (mode == "OnStartup")
{
activation_mode_ = ActivationMode::OnStartup;
}
else
{
if (mode != "Never")
{
LOG_WARN("Found invalid value for param require_activation: '%s'\nShould be one of Never, OnStartup, Always",
mode.c_str());
mode = "Never";
}
notify_all(RobotState::Running);
}
LOG_INFO("Service 'ur_driver/robot_enable' activation mode: %s", mode.c_str());
}
bool ServiceStopper::enableCallback(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& resp)
{
// After the startup call OnStartup and Never behave the same
if (activation_mode_ == ActivationMode::OnStartup)
activation_mode_ = ActivationMode::Never;
notify_all(RobotState::Running);
return true;
}
void ServiceStopper::notify_all(RobotState state)
{
if (last_state_ == state)
return;
for (auto const service : services_)
{
service->onRobotStateChange(state);
}
last_state_ = state;
}
bool ServiceStopper::handle(SharedRobotModeData& data, bool error)
{
if (data.emergency_stopped)
{
notify_all(RobotState::EmergencyStopped);
}
else if (data.protective_stopped)
{
notify_all(RobotState::ProtectiveStopped);
}
else if (error)
{
notify_all(RobotState::Error);
}
else if (activation_mode_ == ActivationMode::Never)
{
// No error encountered, the user requested automatic reactivation
notify_all(RobotState::Running);
}
return true;
}
} // namespace ur_driver

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