mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 19:10:47 +02:00
put communication-related classes to namespace
This commit is contained in:
@@ -20,21 +20,21 @@
|
||||
#include <array>
|
||||
#include <iomanip>
|
||||
#include <sstream>
|
||||
#include "ur_rtde_driver/ur/stream.h"
|
||||
#include "ur_rtde_driver/comm/stream.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URCommander
|
||||
{
|
||||
private:
|
||||
URStream& stream_;
|
||||
comm::URStream& stream_;
|
||||
|
||||
protected:
|
||||
bool write(const std::string& s);
|
||||
void formatArray(std::ostringstream& out, std::array<double, 6>& values);
|
||||
|
||||
public:
|
||||
URCommander(URStream& stream) : stream_(stream)
|
||||
URCommander(comm::URStream& stream) : stream_(stream)
|
||||
{
|
||||
}
|
||||
|
||||
@@ -53,7 +53,7 @@ public:
|
||||
class URCommander_V1_X : public URCommander
|
||||
{
|
||||
public:
|
||||
URCommander_V1_X(URStream& stream) : URCommander(stream)
|
||||
URCommander_V1_X(comm::URStream& stream) : URCommander(stream)
|
||||
{
|
||||
}
|
||||
|
||||
@@ -65,7 +65,7 @@ public:
|
||||
class URCommander_V3_X : public URCommander
|
||||
{
|
||||
public:
|
||||
URCommander_V3_X(URStream& stream) : URCommander(stream)
|
||||
URCommander_V3_X(comm::URStream& stream) : URCommander(stream)
|
||||
{
|
||||
}
|
||||
|
||||
@@ -77,7 +77,7 @@ public:
|
||||
class URCommander_V3_1__2 : public URCommander_V3_X
|
||||
{
|
||||
public:
|
||||
URCommander_V3_1__2(URStream& stream) : URCommander_V3_X(stream)
|
||||
URCommander_V3_1__2(comm::URStream& stream) : URCommander_V3_X(stream)
|
||||
{
|
||||
}
|
||||
|
||||
@@ -87,7 +87,7 @@ public:
|
||||
class URCommander_V3_3 : public URCommander_V3_X
|
||||
{
|
||||
public:
|
||||
URCommander_V3_3(URStream& stream) : URCommander_V3_X(stream)
|
||||
URCommander_V3_3(comm::URStream& stream) : URCommander_V3_X(stream)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -18,7 +18,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#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"
|
||||
@@ -27,10 +27,10 @@
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URRTPacketConsumer : public IConsumer<RTPacket>
|
||||
class URRTPacketConsumer : public comm::IConsumer<RTPacket>
|
||||
{
|
||||
public:
|
||||
virtual bool consume(shared_ptr<RTPacket> packet)
|
||||
virtual bool consume(std::shared_ptr<RTPacket> packet)
|
||||
{
|
||||
return packet->consumeWith(*this);
|
||||
}
|
||||
@@ -41,10 +41,10 @@ public:
|
||||
virtual bool consume(RTState_V3_2__3& state) = 0;
|
||||
};
|
||||
|
||||
class URStatePacketConsumer : public IConsumer<StatePacket>
|
||||
class URStatePacketConsumer : public comm::IConsumer<StatePacket>
|
||||
{
|
||||
public:
|
||||
virtual bool consume(shared_ptr<StatePacket> packet)
|
||||
virtual bool consume(std::shared_ptr<StatePacket> packet)
|
||||
{
|
||||
return packet->consumeWith(*this);
|
||||
}
|
||||
@@ -58,10 +58,10 @@ public:
|
||||
virtual bool consume(RobotModeData_V3_2& data) = 0;
|
||||
};
|
||||
|
||||
class URMessagePacketConsumer : public IConsumer<MessagePacket>
|
||||
class URMessagePacketConsumer : public comm::IConsumer<MessagePacket>
|
||||
{
|
||||
public:
|
||||
virtual bool consume(shared_ptr<MessagePacket> packet)
|
||||
virtual bool consume(std::shared_ptr<MessagePacket> packet)
|
||||
{
|
||||
return packet->consumeWith(*this);
|
||||
}
|
||||
|
||||
@@ -19,13 +19,13 @@
|
||||
#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/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"
|
||||
#include "ur_rtde_driver/ur/stream.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
@@ -34,7 +34,7 @@ static const int UR_PRIMARY_PORT = 30001;
|
||||
class URFactory : private URMessagePacketConsumer
|
||||
{
|
||||
private:
|
||||
URStream stream_;
|
||||
comm::URStream stream_;
|
||||
URMessageParser parser_;
|
||||
|
||||
uint8_t major_version_;
|
||||
@@ -67,7 +67,7 @@ public:
|
||||
URFactory(std::string& host) : stream_(host, UR_PRIMARY_PORT)
|
||||
{
|
||||
URProducer<MessagePacket> prod(stream_, parser_);
|
||||
std::vector<unique_ptr<MessagePacket>> results;
|
||||
std::vector<std::unique_ptr<MessagePacket>> results;
|
||||
|
||||
prod.setupProducer();
|
||||
|
||||
@@ -96,7 +96,7 @@ public:
|
||||
return major_version_ == 3;
|
||||
}
|
||||
|
||||
std::unique_ptr<URCommander> getCommander(URStream& stream)
|
||||
std::unique_ptr<URCommander> getCommander(comm::URStream& stream)
|
||||
{
|
||||
if (major_version_ == 1)
|
||||
return std::unique_ptr<URCommander>(new URCommander_V1_X(stream));
|
||||
@@ -106,38 +106,38 @@ public:
|
||||
return std::unique_ptr<URCommander>(new URCommander_V3_3(stream));
|
||||
}
|
||||
|
||||
std::unique_ptr<URParser<StatePacket>> getStateParser()
|
||||
std::unique_ptr<comm::URParser<StatePacket>> getStateParser()
|
||||
{
|
||||
if (major_version_ == 1)
|
||||
{
|
||||
return std::unique_ptr<URParser<StatePacket>>(new URStateParser_V1_X);
|
||||
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V1_X);
|
||||
}
|
||||
else
|
||||
{
|
||||
if (minor_version_ < 3)
|
||||
return std::unique_ptr<URParser<StatePacket>>(new URStateParser_V3_0__1);
|
||||
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V3_0__1);
|
||||
else if (minor_version_ < 5)
|
||||
return std::unique_ptr<URParser<StatePacket>>(new URStateParser_V3_2);
|
||||
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V3_2);
|
||||
else
|
||||
return std::unique_ptr<URParser<StatePacket>>(new URStateParser_V3_5);
|
||||
return std::unique_ptr<comm::URParser<StatePacket>>(new URStateParser_V3_5);
|
||||
}
|
||||
}
|
||||
|
||||
std::unique_ptr<URParser<RTPacket>> getRTParser()
|
||||
std::unique_ptr<comm::URParser<RTPacket>> getRTParser()
|
||||
{
|
||||
if (major_version_ == 1)
|
||||
{
|
||||
if (minor_version_ < 8)
|
||||
return std::unique_ptr<URParser<RTPacket>>(new URRTStateParser_V1_6__7);
|
||||
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V1_6__7);
|
||||
else
|
||||
return std::unique_ptr<URParser<RTPacket>>(new URRTStateParser_V1_8);
|
||||
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V1_8);
|
||||
}
|
||||
else
|
||||
{
|
||||
if (minor_version_ < 3)
|
||||
return std::unique_ptr<URParser<RTPacket>>(new URRTStateParser_V3_0__1);
|
||||
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V3_0__1);
|
||||
else
|
||||
return std::unique_ptr<URParser<RTPacket>>(new URRTStateParser_V3_2__3);
|
||||
return std::unique_ptr<comm::URParser<RTPacket>>(new URRTStateParser_V3_2__3);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
@@ -21,7 +21,7 @@
|
||||
#include <inttypes.h>
|
||||
#include <cstddef>
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/comm/pipeline.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
|
||||
@@ -20,16 +20,16 @@
|
||||
#include <vector>
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/comm/parser.h"
|
||||
#include "ur_rtde_driver/comm/pipeline.h"
|
||||
#include "ur_rtde_driver/ur/messages.h"
|
||||
#include "ur_rtde_driver/ur/parser.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URMessageParser : public URParser<MessagePacket>
|
||||
class URMessageParser : public comm::URParser<MessagePacket>
|
||||
{
|
||||
public:
|
||||
bool parse(BinParser& bp, std::vector<unique_ptr<MessagePacket>>& results)
|
||||
bool parse(BinParser& bp, std::vector<std::unique_ptr<MessagePacket>>& results)
|
||||
{
|
||||
int32_t packet_size;
|
||||
message_type type;
|
||||
|
||||
@@ -1,32 +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/pipeline.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
template <typename T>
|
||||
class URParser
|
||||
{
|
||||
public:
|
||||
virtual bool parse(BinParser& bp, std::vector<std::unique_ptr<T>>& results) = 0;
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
@@ -18,22 +18,22 @@
|
||||
|
||||
#pragma once
|
||||
#include <chrono>
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/ur/parser.h"
|
||||
#include "ur_rtde_driver/ur/stream.h"
|
||||
#include "ur_rtde_driver/comm/pipeline.h"
|
||||
#include "ur_rtde_driver/comm/parser.h"
|
||||
#include "ur_rtde_driver/comm/stream.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
template <typename T>
|
||||
class URProducer : public IProducer<T>
|
||||
class URProducer : public comm::IProducer<T>
|
||||
{
|
||||
private:
|
||||
URStream& stream_;
|
||||
URParser<T>& parser_;
|
||||
comm::URStream& stream_;
|
||||
comm::URParser<T>& parser_;
|
||||
std::chrono::seconds timeout_;
|
||||
|
||||
public:
|
||||
URProducer(URStream& stream, URParser<T>& parser) : stream_(stream), parser_(parser), timeout_(1)
|
||||
URProducer(comm::URStream& stream, comm::URParser<T>& parser) : stream_(stream), parser_(parser), timeout_(1)
|
||||
{
|
||||
}
|
||||
|
||||
@@ -50,7 +50,7 @@ public:
|
||||
stream_.disconnect();
|
||||
}
|
||||
|
||||
bool tryGet(std::vector<unique_ptr<T>>& products)
|
||||
bool tryGet(std::vector<std::unique_ptr<T>>& products)
|
||||
{
|
||||
// 4KB should be enough to hold any packet received from UR
|
||||
uint8_t buf[4096];
|
||||
|
||||
@@ -20,14 +20,14 @@
|
||||
#include <vector>
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/ur/parser.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_rtde_driver
|
||||
{
|
||||
template <typename T>
|
||||
class URRTStateParser : public URParser<RTPacket>
|
||||
class URRTStateParser : public comm::URParser<RTPacket>
|
||||
{
|
||||
public:
|
||||
bool parse(BinParser& bp, std::vector<std::unique_ptr<RTPacket>>& results)
|
||||
|
||||
@@ -21,7 +21,7 @@
|
||||
#include <inttypes.h>
|
||||
#include <cstddef>
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/comm/pipeline.h"
|
||||
#include "ur_rtde_driver/types.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
|
||||
@@ -24,17 +24,17 @@
|
||||
#include <cstdlib>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include "ur_rtde_driver/tcp_socket.h"
|
||||
#include "ur_rtde_driver/comm/tcp_socket.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
#define MAX_SERVER_BUF_LEN 50
|
||||
|
||||
class URServer : private TCPSocket
|
||||
class URServer : private comm::TCPSocket
|
||||
{
|
||||
private:
|
||||
int port_;
|
||||
TCPSocket client_;
|
||||
comm::TCPSocket client_;
|
||||
|
||||
protected:
|
||||
virtual bool open(int socket_fd, struct sockaddr* address, size_t address_len);
|
||||
|
||||
@@ -22,7 +22,7 @@
|
||||
#include <cstddef>
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/comm/pipeline.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
|
||||
@@ -20,16 +20,16 @@
|
||||
#include <vector>
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/pipeline.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/parser.h"
|
||||
#include "ur_rtde_driver/ur/robot_mode.h"
|
||||
#include "ur_rtde_driver/ur/state.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
template <typename RMD, typename MBD>
|
||||
class URStateParser : public URParser<StatePacket>
|
||||
class URStateParser : public comm::URParser<StatePacket>
|
||||
{
|
||||
private:
|
||||
StatePacket* from_type(package_type type)
|
||||
|
||||
@@ -1,67 +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 <netdb.h>
|
||||
#include <sys/socket.h>
|
||||
#include <sys/types.h>
|
||||
#include <atomic>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/tcp_socket.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URStream : public TCPSocket
|
||||
{
|
||||
private:
|
||||
std::string host_;
|
||||
int port_;
|
||||
std::mutex write_mutex_, read_mutex_;
|
||||
|
||||
protected:
|
||||
virtual bool open(int socket_fd, struct sockaddr* address, size_t address_len)
|
||||
{
|
||||
return ::connect(socket_fd, address, address_len) == 0;
|
||||
}
|
||||
|
||||
public:
|
||||
URStream(std::string& host, int port) : host_(host), port_(port)
|
||||
{
|
||||
}
|
||||
|
||||
bool connect()
|
||||
{
|
||||
return TCPSocket::setup(host_, port_);
|
||||
}
|
||||
void disconnect()
|
||||
{
|
||||
LOG_INFO("Disconnecting from %s:%d", host_.c_str(), port_);
|
||||
TCPSocket::close();
|
||||
}
|
||||
|
||||
bool closed()
|
||||
{
|
||||
return getState() == SocketState::Closed;
|
||||
}
|
||||
|
||||
bool read(uint8_t* buf, size_t buf_len, size_t& read);
|
||||
bool write(const uint8_t* buf, size_t buf_len, size_t& written);
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
Reference in New Issue
Block a user