From 31746259cf65868d016169a6bb1c2b8846539f12 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 1 Apr 2019 14:54:39 +0200 Subject: [PATCH] put communication-related classes to namespace --- CMakeLists.txt | 5 ++-- include/ur_rtde_driver/{ur => comm}/parser.h | 8 +++-- include/ur_rtde_driver/{ => comm}/pipeline.h | 24 ++++++++------- include/ur_rtde_driver/{ur => comm}/stream.h | 5 +++- .../ur_rtde_driver/{ => comm}/tcp_socket.h | 3 ++ include/ur_rtde_driver/ur/commander.h | 14 ++++----- include/ur_rtde_driver/ur/consumer.h | 14 ++++----- include/ur_rtde_driver/ur/factory.h | 30 +++++++++---------- include/ur_rtde_driver/ur/messages.h | 2 +- include/ur_rtde_driver/ur/messages_parser.h | 8 ++--- include/ur_rtde_driver/ur/producer.h | 16 +++++----- include/ur_rtde_driver/ur/rt_parser.h | 6 ++-- include/ur_rtde_driver/ur/rt_state.h | 2 +- include/ur_rtde_driver/ur/server.h | 6 ++-- include/ur_rtde_driver/ur/state.h | 2 +- include/ur_rtde_driver/ur/state_parser.h | 6 ++-- src/{ur => comm}/stream.cpp | 5 +++- src/{ => comm}/tcp_socket.cpp | 5 +++- src/ros/action_server.cpp | 2 +- src/ros_main.cpp | 30 +++++++++---------- src/ur/server.cpp | 4 +-- 21 files changed, 108 insertions(+), 89 deletions(-) rename include/ur_rtde_driver/{ur => comm}/parser.h (87%) rename include/ur_rtde_driver/{ => comm}/pipeline.h (89%) rename include/ur_rtde_driver/{ur => comm}/stream.h (95%) rename include/ur_rtde_driver/{ => comm}/tcp_socket.h (97%) rename src/{ur => comm}/stream.cpp (95%) rename src/{ => comm}/tcp_socket.cpp (98%) diff --git a/CMakeLists.txt b/CMakeLists.txt index cb8e077..5cb31fe 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -78,6 +78,8 @@ target_link_libraries(ur_rtde_hardware_interface ${catkin_LIBRARIES}) set(${PROJECT_NAME}_SOURCES + src/comm/stream.cpp + src/comm/tcp_socket.cpp src/ros/action_server.cpp src/ros/lowbandwidth_trajectory_follower.cpp src/ros/mb_publisher.cpp @@ -85,14 +87,13 @@ set(${PROJECT_NAME}_SOURCES src/ros/service_stopper.cpp src/ros/trajectory_follower.cpp src/ros/urscript_handler.cpp - src/tcp_socket.cpp src/ur/commander.cpp src/ur/master_board.cpp src/ur/messages.cpp src/ur/robot_mode.cpp src/ur/rt_state.cpp src/ur/server.cpp - src/ur/stream.cpp) +) add_executable(ur_rtde_driver ${${PROJECT_NAME}_SOURCES} src/ros_main.cpp) add_dependencies(ur_rtde_driver ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) diff --git a/include/ur_rtde_driver/ur/parser.h b/include/ur_rtde_driver/comm/parser.h similarity index 87% rename from include/ur_rtde_driver/ur/parser.h rename to include/ur_rtde_driver/comm/parser.h index d175658..db3c0aa 100644 --- a/include/ur_rtde_driver/ur/parser.h +++ b/include/ur_rtde_driver/comm/parser.h @@ -19,14 +19,18 @@ #pragma once #include #include "ur_rtde_driver/bin_parser.h" -#include "ur_rtde_driver/pipeline.h" +#include "ur_rtde_driver/comm/pipeline.h" namespace ur_rtde_driver { +namespace comm +{ template class URParser { public: virtual bool parse(BinParser& bp, std::vector>& results) = 0; -}; +}; // namespace commtemplateclassURParser + +} // namespace comm } // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/pipeline.h b/include/ur_rtde_driver/comm/pipeline.h similarity index 89% rename from include/ur_rtde_driver/pipeline.h rename to include/ur_rtde_driver/comm/pipeline.h index ef7d950..3e7cf30 100644 --- a/include/ur_rtde_driver/pipeline.h +++ b/include/ur_rtde_driver/comm/pipeline.h @@ -27,9 +27,10 @@ namespace ur_rtde_driver { +namespace comm +{ // TODO: Remove these!!! using namespace moodycamel; -using namespace std; template class IConsumer @@ -48,7 +49,7 @@ public: { } - virtual bool consume(shared_ptr product) = 0; + virtual bool consume(std::shared_ptr product) = 0; }; template @@ -91,7 +92,7 @@ public: } } - bool consume(shared_ptr product) + bool consume(std::shared_ptr product) { bool res = true; for (auto& con : consumers_) @@ -117,7 +118,7 @@ public: { } - virtual bool tryGet(std::vector>& products) = 0; + virtual bool tryGet(std::vector>& products) = 0; }; class INotifier @@ -141,14 +142,14 @@ private: IConsumer& consumer_; std::string name_; INotifier& notifier_; - BlockingReaderWriterQueue> queue_; - atomic running_; - thread pThread_, cThread_; + BlockingReaderWriterQueue> queue_; + std::atomic running_; + std::thread pThread_, cThread_; void run_producer() { producer_.setupProducer(); - std::vector> products; + std::vector> products; while (running_) { if (!producer_.tryGet(products)) @@ -176,7 +177,7 @@ private: void run_consumer() { consumer_.setupConsumer(); - unique_ptr product; + std::unique_ptr product; while (running_) { // timeout was chosen because we should receive messages @@ -211,8 +212,8 @@ public: return; running_ = true; - pThread_ = thread(&Pipeline::run_producer, this); - cThread_ = thread(&Pipeline::run_consumer, this); + pThread_ = std::thread(&Pipeline::run_producer, this); + cThread_ = std::thread(&Pipeline::run_consumer, this); notifier_.started(name_); } @@ -233,4 +234,5 @@ public: notifier_.stopped(name_); } }; +} // namespace comm } // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/stream.h b/include/ur_rtde_driver/comm/stream.h similarity index 95% rename from include/ur_rtde_driver/ur/stream.h rename to include/ur_rtde_driver/comm/stream.h index 0e5bcf5..b70560b 100644 --- a/include/ur_rtde_driver/ur/stream.h +++ b/include/ur_rtde_driver/comm/stream.h @@ -24,10 +24,12 @@ #include #include #include "ur_rtde_driver/log.h" -#include "ur_rtde_driver/tcp_socket.h" +#include "ur_rtde_driver/comm/tcp_socket.h" namespace ur_rtde_driver { +namespace comm +{ class URStream : public TCPSocket { private: @@ -64,4 +66,5 @@ public: 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 comm } // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/tcp_socket.h b/include/ur_rtde_driver/comm/tcp_socket.h similarity index 97% rename from include/ur_rtde_driver/tcp_socket.h rename to include/ur_rtde_driver/comm/tcp_socket.h index 459de96..acf85dc 100644 --- a/include/ur_rtde_driver/tcp_socket.h +++ b/include/ur_rtde_driver/comm/tcp_socket.h @@ -26,6 +26,8 @@ namespace ur_rtde_driver { +namespace comm +{ enum class SocketState { Invalid, @@ -72,4 +74,5 @@ public: void close(); }; +} // namespace comm } // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/commander.h b/include/ur_rtde_driver/ur/commander.h index e7f20c5..c316d78 100644 --- a/include/ur_rtde_driver/ur/commander.h +++ b/include/ur_rtde_driver/ur/commander.h @@ -20,21 +20,21 @@ #include #include #include -#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& 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) { } diff --git a/include/ur_rtde_driver/ur/consumer.h b/include/ur_rtde_driver/ur/consumer.h index 6cfd65b..b3bd249 100644 --- a/include/ur_rtde_driver/ur/consumer.h +++ b/include/ur_rtde_driver/ur/consumer.h @@ -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 +class URRTPacketConsumer : public comm::IConsumer { public: - virtual bool consume(shared_ptr packet) + virtual bool consume(std::shared_ptr packet) { return packet->consumeWith(*this); } @@ -41,10 +41,10 @@ public: virtual bool consume(RTState_V3_2__3& state) = 0; }; -class URStatePacketConsumer : public IConsumer +class URStatePacketConsumer : public comm::IConsumer { public: - virtual bool consume(shared_ptr packet) + virtual bool consume(std::shared_ptr packet) { return packet->consumeWith(*this); } @@ -58,10 +58,10 @@ public: virtual bool consume(RobotModeData_V3_2& data) = 0; }; -class URMessagePacketConsumer : public IConsumer +class URMessagePacketConsumer : public comm::IConsumer { public: - virtual bool consume(shared_ptr packet) + virtual bool consume(std::shared_ptr packet) { return packet->consumeWith(*this); } diff --git a/include/ur_rtde_driver/ur/factory.h b/include/ur_rtde_driver/ur/factory.h index ea33f16..ca52b02 100644 --- a/include/ur_rtde_driver/ur/factory.h +++ b/include/ur_rtde_driver/ur/factory.h @@ -19,13 +19,13 @@ #pragma once #include +#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 prod(stream_, parser_); - std::vector> results; + std::vector> results; prod.setupProducer(); @@ -96,7 +96,7 @@ public: return major_version_ == 3; } - std::unique_ptr getCommander(URStream& stream) + std::unique_ptr getCommander(comm::URStream& stream) { if (major_version_ == 1) return std::unique_ptr(new URCommander_V1_X(stream)); @@ -106,38 +106,38 @@ public: return std::unique_ptr(new URCommander_V3_3(stream)); } - std::unique_ptr> getStateParser() + std::unique_ptr> getStateParser() { if (major_version_ == 1) { - return std::unique_ptr>(new URStateParser_V1_X); + return std::unique_ptr>(new URStateParser_V1_X); } else { if (minor_version_ < 3) - return std::unique_ptr>(new URStateParser_V3_0__1); + return std::unique_ptr>(new URStateParser_V3_0__1); else if (minor_version_ < 5) - return std::unique_ptr>(new URStateParser_V3_2); + return std::unique_ptr>(new URStateParser_V3_2); else - return std::unique_ptr>(new URStateParser_V3_5); + return std::unique_ptr>(new URStateParser_V3_5); } } - std::unique_ptr> getRTParser() + std::unique_ptr> getRTParser() { if (major_version_ == 1) { if (minor_version_ < 8) - return std::unique_ptr>(new URRTStateParser_V1_6__7); + return std::unique_ptr>(new URRTStateParser_V1_6__7); else - return std::unique_ptr>(new URRTStateParser_V1_8); + return std::unique_ptr>(new URRTStateParser_V1_8); } else { if (minor_version_ < 3) - return std::unique_ptr>(new URRTStateParser_V3_0__1); + return std::unique_ptr>(new URRTStateParser_V3_0__1); else - return std::unique_ptr>(new URRTStateParser_V3_2__3); + return std::unique_ptr>(new URRTStateParser_V3_2__3); } } }; diff --git a/include/ur_rtde_driver/ur/messages.h b/include/ur_rtde_driver/ur/messages.h index ac5ec76..025a206 100644 --- a/include/ur_rtde_driver/ur/messages.h +++ b/include/ur_rtde_driver/ur/messages.h @@ -21,7 +21,7 @@ #include #include #include "ur_rtde_driver/bin_parser.h" -#include "ur_rtde_driver/pipeline.h" +#include "ur_rtde_driver/comm/pipeline.h" namespace ur_rtde_driver { diff --git a/include/ur_rtde_driver/ur/messages_parser.h b/include/ur_rtde_driver/ur/messages_parser.h index 00c9e8a..278d8d0 100644 --- a/include/ur_rtde_driver/ur/messages_parser.h +++ b/include/ur_rtde_driver/ur/messages_parser.h @@ -20,16 +20,16 @@ #include #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 +class URMessageParser : public comm::URParser { public: - bool parse(BinParser& bp, std::vector>& results) + bool parse(BinParser& bp, std::vector>& results) { int32_t packet_size; message_type type; diff --git a/include/ur_rtde_driver/ur/producer.h b/include/ur_rtde_driver/ur/producer.h index a0af94a..e4626d5 100644 --- a/include/ur_rtde_driver/ur/producer.h +++ b/include/ur_rtde_driver/ur/producer.h @@ -18,22 +18,22 @@ #pragma once #include -#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 -class URProducer : public IProducer +class URProducer : public comm::IProducer { private: - URStream& stream_; - URParser& parser_; + comm::URStream& stream_; + comm::URParser& parser_; std::chrono::seconds timeout_; public: - URProducer(URStream& stream, URParser& parser) : stream_(stream), parser_(parser), timeout_(1) + URProducer(comm::URStream& stream, comm::URParser& parser) : stream_(stream), parser_(parser), timeout_(1) { } @@ -50,7 +50,7 @@ public: stream_.disconnect(); } - bool tryGet(std::vector>& products) + bool tryGet(std::vector>& products) { // 4KB should be enough to hold any packet received from UR uint8_t buf[4096]; diff --git a/include/ur_rtde_driver/ur/rt_parser.h b/include/ur_rtde_driver/ur/rt_parser.h index 068489f..f66dd32 100644 --- a/include/ur_rtde_driver/ur/rt_parser.h +++ b/include/ur_rtde_driver/ur/rt_parser.h @@ -20,14 +20,14 @@ #include #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 -class URRTStateParser : public URParser +class URRTStateParser : public comm::URParser { public: bool parse(BinParser& bp, std::vector>& results) diff --git a/include/ur_rtde_driver/ur/rt_state.h b/include/ur_rtde_driver/ur/rt_state.h index 4bfdede..bd50956 100644 --- a/include/ur_rtde_driver/ur/rt_state.h +++ b/include/ur_rtde_driver/ur/rt_state.h @@ -21,7 +21,7 @@ #include #include #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 diff --git a/include/ur_rtde_driver/ur/server.h b/include/ur_rtde_driver/ur/server.h index 1484da0..2d9c3a0 100644 --- a/include/ur_rtde_driver/ur/server.h +++ b/include/ur_rtde_driver/ur/server.h @@ -24,17 +24,17 @@ #include #include #include -#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); diff --git a/include/ur_rtde_driver/ur/state.h b/include/ur_rtde_driver/ur/state.h index fdbe24d..cec1e52 100644 --- a/include/ur_rtde_driver/ur/state.h +++ b/include/ur_rtde_driver/ur/state.h @@ -22,7 +22,7 @@ #include #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 { diff --git a/include/ur_rtde_driver/ur/state_parser.h b/include/ur_rtde_driver/ur/state_parser.h index 53bfc4b..40e00c2 100644 --- a/include/ur_rtde_driver/ur/state_parser.h +++ b/include/ur_rtde_driver/ur/state_parser.h @@ -20,16 +20,16 @@ #include #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 -class URStateParser : public URParser +class URStateParser : public comm::URParser { private: StatePacket* from_type(package_type type) diff --git a/src/ur/stream.cpp b/src/comm/stream.cpp similarity index 95% rename from src/ur/stream.cpp rename to src/comm/stream.cpp index 74c1759..a3536af 100644 --- a/src/ur/stream.cpp +++ b/src/comm/stream.cpp @@ -22,10 +22,12 @@ #include #include "ur_rtde_driver/log.h" -#include "ur_rtde_driver/ur/stream.h" +#include "ur_rtde_driver/comm/stream.h" namespace ur_rtde_driver { +namespace comm +{ bool URStream::write(const uint8_t* buf, size_t buf_len, size_t& written) { std::lock_guard lock(write_mutex_); @@ -62,4 +64,5 @@ bool URStream::read(uint8_t* buf, size_t buf_len, size_t& total) return remainder == 0; } +} // namespace comm } // namespace ur_rtde_driver diff --git a/src/tcp_socket.cpp b/src/comm/tcp_socket.cpp similarity index 98% rename from src/tcp_socket.cpp rename to src/comm/tcp_socket.cpp index a8b20a2..b9c9c77 100644 --- a/src/tcp_socket.cpp +++ b/src/comm/tcp_socket.cpp @@ -25,10 +25,12 @@ #include #include "ur_rtde_driver/log.h" -#include "ur_rtde_driver/tcp_socket.h" +#include "ur_rtde_driver/comm/tcp_socket.h" namespace ur_rtde_driver { +namespace comm +{ TCPSocket::TCPSocket() : socket_fd_(-1), state_(SocketState::Invalid) { } @@ -186,4 +188,5 @@ bool TCPSocket::write(const uint8_t* buf, size_t buf_len, size_t& written) return true; } +} // namespace comm } // namespace ur_rtde_driver diff --git a/src/ros/action_server.cpp b/src/ros/action_server.cpp index 1265470..5f9a495 100644 --- a/src/ros/action_server.cpp +++ b/src/ros/action_server.cpp @@ -45,7 +45,7 @@ void ActionServer::start() LOG_INFO("Starting ActionServer"); running_ = true; - tj_thread_ = thread(&ActionServer::trajectoryThread, this); + tj_thread_ = std::thread(&ActionServer::trajectoryThread, this); as_.start(); } diff --git a/src/ros_main.cpp b/src/ros_main.cpp index afde87d..1dda334 100644 --- a/src/ros_main.cpp +++ b/src/ros_main.cpp @@ -25,7 +25,8 @@ #include #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/ros/action_server.h" #include "ur_rtde_driver/ros/controller.h" #include "ur_rtde_driver/ros/io_service.h" @@ -38,7 +39,6 @@ #include "ur_rtde_driver/ur/commander.h" #include "ur_rtde_driver/ur/factory.h" #include "ur_rtde_driver/ur/messages.h" -#include "ur_rtde_driver/ur/parser.h" #include "ur_rtde_driver/ur/producer.h" #include "ur_rtde_driver/ur/rt_state.h" #include "ur_rtde_driver/ur/state.h" @@ -81,7 +81,7 @@ public: bool shutdown_on_disconnect; }; -class IgnorePipelineStoppedNotifier : public INotifier +class IgnorePipelineStoppedNotifier : public comm::INotifier { public: void started(std::string name) @@ -94,7 +94,7 @@ public: } }; -class ShutdownOnPipelineStoppedNotifier : public INotifier +class ShutdownOnPipelineStoppedNotifier : public comm::INotifier { public: void started(std::string name) @@ -132,7 +132,7 @@ bool parse_args(ProgArgs& args) std::string getLocalIPAccessibleFromHost(std::string& host) { - URStream stream(host, UR_RT_PORT); + comm::URStream stream(host, UR_RT_PORT); return stream.connect() ? stream.getIP() : std::string(); } @@ -153,17 +153,17 @@ int main(int argc, char** argv) std::string local_ip(getLocalIPAccessibleFromHost(args.host)); URFactory factory(args.host); - vector services; + std::vector services; // RT packets auto rt_parser = factory.getRTParser(); - URStream rt_stream(args.host, UR_RT_PORT); + comm::URStream rt_stream(args.host, UR_RT_PORT); URProducer rt_prod(rt_stream, *rt_parser); RTPublisher rt_pub(args.prefix, args.base_frame, args.tool_frame, args.use_ros_control); auto rt_commander = factory.getCommander(rt_stream); - vector*> rt_vec{ &rt_pub }; + std::vector*> rt_vec{ &rt_pub }; - INotifier* notifier(nullptr); + comm::INotifier* notifier(nullptr); ROSController* controller(nullptr); ActionServer* action_server(nullptr); if (args.use_ros_control) @@ -208,20 +208,20 @@ int main(int argc, char** argv) notifier = new IgnorePipelineStoppedNotifier(); } - MultiConsumer rt_cons(rt_vec); - Pipeline rt_pl(rt_prod, rt_cons, "RTPacket", *notifier); + comm::MultiConsumer rt_cons(rt_vec); + comm::Pipeline rt_pl(rt_prod, rt_cons, "RTPacket", *notifier); // Message packets auto state_parser = factory.getStateParser(); - URStream state_stream(args.host, UR_SECONDARY_PORT); + comm::URStream state_stream(args.host, UR_SECONDARY_PORT); URProducer state_prod(state_stream, *state_parser); MBPublisher state_pub; ServiceStopper service_stopper(services); - vector*> state_vec{ &state_pub, &service_stopper }; - MultiConsumer state_cons(state_vec); - Pipeline state_pl(state_prod, state_cons, "StatePacket", *notifier); + std::vector*> state_vec{ &state_pub, &service_stopper }; + comm::MultiConsumer state_cons(state_vec); + comm::Pipeline state_pl(state_prod, state_cons, "StatePacket", *notifier); LOG_INFO("Starting main loop"); diff --git a/src/ur/server.cpp b/src/ur/server.cpp index b8e5c20..9e21865 100644 --- a/src/ur/server.cpp +++ b/src/ur/server.cpp @@ -76,7 +76,7 @@ bool URServer::bind() bool URServer::accept() { - if (TCPSocket::getState() != SocketState::Connected || client_.getSocketFD() > 0) + if (TCPSocket::getState() != comm::SocketState::Connected || client_.getSocketFD() > 0) return false; struct sockaddr addr; @@ -98,7 +98,7 @@ bool URServer::accept() void URServer::disconnectClient() { - if (client_.getState() != SocketState::Connected) + if (client_.getState() != comm::SocketState::Connected) return; client_.close();