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

use namespace ur_driver instead of ur_rtde_driver

This commit is contained in:
Felix Mauch
2019-04-08 13:51:33 +02:00
parent 3c61cbeb35
commit 1c205556a1
36 changed files with 68 additions and 68 deletions

View File

@@ -29,7 +29,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/types.h" #include "ur_rtde_driver/types.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class BinParser class BinParser
{ {
@@ -203,4 +203,4 @@ public:
LOG_DEBUG("BinParser: %p - %p (%zu bytes)", buf_pos_, buf_end_, buf_end_ - buf_pos_); LOG_DEBUG("BinParser: %p - %p (%zu bytes)", buf_pos_, buf_end_, buf_end_ - buf_pos_);
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -44,5 +44,5 @@ private:
HeaderT header_; HeaderT header_;
}; };
} // namespace comm } // namespace comm
} // namespace ur_rtde_driver } // namespace ur_driver
#endif // ifndef UR_RTDE_DRIVER_PACKAGE_H_INCLUDED #endif // ifndef UR_RTDE_DRIVER_PACKAGE_H_INCLUDED

View File

@@ -21,7 +21,7 @@
#include "ur_rtde_driver/bin_parser.h" #include "ur_rtde_driver/bin_parser.h"
#include "ur_rtde_driver/comm/pipeline.h" #include "ur_rtde_driver/comm/pipeline.h"
namespace ur_rtde_driver namespace ur_driver
{ {
namespace comm namespace comm
{ {
@@ -33,4 +33,4 @@ public:
}; // namespace commtemplate<typenameT>classURParser }; // namespace commtemplate<typenameT>classURParser
} // namespace comm } // namespace comm
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -25,7 +25,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/queue/readerwriterqueue.h" #include "ur_rtde_driver/queue/readerwriterqueue.h"
namespace ur_rtde_driver namespace ur_driver
{ {
namespace comm namespace comm
{ {
@@ -235,4 +235,4 @@ public:
} }
}; };
} // namespace comm } // namespace comm
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -26,7 +26,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/tcp_socket.h" #include "ur_rtde_driver/comm/tcp_socket.h"
namespace ur_rtde_driver namespace ur_driver
{ {
namespace comm namespace comm
{ {
@@ -67,4 +67,4 @@ public:
bool write(const uint8_t* buf, size_t buf_len, size_t& written); bool write(const uint8_t* buf, size_t buf_len, size_t& written);
}; };
} // namespace comm } // namespace comm
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include <mutex> #include <mutex>
#include <string> #include <string>
namespace ur_rtde_driver namespace ur_driver
{ {
namespace comm namespace comm
{ {
@@ -75,4 +75,4 @@ public:
void close(); void close();
}; };
} // namespace comm } // namespace comm
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -23,7 +23,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/consumer.h" #include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class EventCounter : public URRTPacketConsumer class EventCounter : public URRTPacketConsumer
{ {
@@ -102,4 +102,4 @@ public:
{ {
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -28,7 +28,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/commander.h" #include "ur_rtde_driver/ur/commander.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class IOService class IOService
{ {
@@ -79,4 +79,4 @@ public:
{ {
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -22,7 +22,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/consumer.h" #include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver namespace ur_driver
{ {
enum class RobotState enum class RobotState
{ {
@@ -88,4 +88,4 @@ public:
return true; return true;
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -26,7 +26,7 @@
#include <random> #include <random>
#include "ur_rtde_driver/bin_parser.h" #include "ur_rtde_driver/bin_parser.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class RandomDataTest class RandomDataTest
{ {
@@ -80,4 +80,4 @@ public:
bp_.consume(n); bp_.consume(n);
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -20,7 +20,7 @@
#include <inttypes.h> #include <inttypes.h>
namespace ur_rtde_driver namespace ur_driver
{ {
struct double3_t struct double3_t
{ {
@@ -42,4 +42,4 @@ inline bool operator==(const cartesian_coord_t& lhs, const cartesian_coord_t& rh
{ {
return lhs.position == rhs.position && lhs.rotation == rhs.rotation; return lhs.position == rhs.position && lhs.rotation == rhs.rotation;
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -22,7 +22,7 @@
#include <sstream> #include <sstream>
#include "ur_rtde_driver/comm/stream.h" #include "ur_rtde_driver/comm/stream.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class URCommander class URCommander
{ {
@@ -93,4 +93,4 @@ public:
virtual bool speedj(std::array<double, 6>& speeds, double acceleration); virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -25,7 +25,7 @@
#include "ur_rtde_driver/ur/rt_state.h" #include "ur_rtde_driver/ur/rt_state.h"
#include "ur_rtde_driver/ur/state.h" #include "ur_rtde_driver/ur/state.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class URRTPacketConsumer : public comm::IConsumer<RTPacket> class URRTPacketConsumer : public comm::IConsumer<RTPacket>
{ {
@@ -68,4 +68,4 @@ public:
virtual bool consume(VersionMessage& message) = 0; virtual bool consume(VersionMessage& message) = 0;
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -27,7 +27,7 @@
#include "ur_rtde_driver/ur/rt_parser.h" #include "ur_rtde_driver/ur/rt_parser.h"
#include "ur_rtde_driver/ur/state_parser.h" #include "ur_rtde_driver/ur/state_parser.h"
namespace ur_rtde_driver namespace ur_driver
{ {
static const int UR_PRIMARY_PORT = 30001; static const int UR_PRIMARY_PORT = 30001;
@@ -141,4 +141,4 @@ public:
} }
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -25,7 +25,7 @@
#include "ur_rtde_driver/types.h" #include "ur_rtde_driver/types.h"
#include "ur_rtde_driver/ur/state.h" #include "ur_rtde_driver/ur/state.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class SharedMasterBoardData class SharedMasterBoardData
{ {
@@ -110,4 +110,4 @@ public:
static const size_t SIZE = MasterBoardData_V3_0__1::SIZE + sizeof(uint8_t) * 2; static const size_t SIZE = MasterBoardData_V3_0__1::SIZE + sizeof(uint8_t) * 2;
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -23,7 +23,7 @@
#include "ur_rtde_driver/bin_parser.h" #include "ur_rtde_driver/bin_parser.h"
#include "ur_rtde_driver/comm/pipeline.h" #include "ur_rtde_driver/comm/pipeline.h"
namespace ur_rtde_driver namespace ur_driver
{ {
enum class robot_message_type : uint8_t enum class robot_message_type : uint8_t
{ {
@@ -69,4 +69,4 @@ public:
int32_t svn_version; int32_t svn_version;
std::string build_date; std::string build_date;
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/comm/pipeline.h" #include "ur_rtde_driver/comm/pipeline.h"
#include "ur_rtde_driver/ur/messages.h" #include "ur_rtde_driver/ur/messages.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class URMessageParser : public comm::URParser<MessagePacket> class URMessageParser : public comm::URParser<MessagePacket>
{ {
@@ -71,4 +71,4 @@ public:
return parsed; return parsed;
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -22,7 +22,7 @@
#include "ur_rtde_driver/comm/parser.h" #include "ur_rtde_driver/comm/parser.h"
#include "ur_rtde_driver/comm/stream.h" #include "ur_rtde_driver/comm/stream.h"
namespace ur_rtde_driver namespace ur_driver
{ {
template <typename T> template <typename T>
class URProducer : public comm::IProducer<T> class URProducer : public comm::IProducer<T>
@@ -83,4 +83,4 @@ public:
return parser_.parse(bp, products); return parser_.parse(bp, products);
} }
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/types.h" #include "ur_rtde_driver/types.h"
#include "ur_rtde_driver/ur/state.h" #include "ur_rtde_driver/ur/state.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class SharedRobotModeData class SharedRobotModeData
{ {
@@ -136,4 +136,4 @@ public:
static_assert(RobotModeData_V3_5::SIZE == 42, "RobotModeData_V3_5 has missmatched size"); static_assert(RobotModeData_V3_5::SIZE == 42, "RobotModeData_V3_5 has missmatched size");
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/comm/parser.h" #include "ur_rtde_driver/comm/parser.h"
#include "ur_rtde_driver/ur/rt_state.h" #include "ur_rtde_driver/ur/rt_state.h"
namespace ur_rtde_driver namespace ur_driver
{ {
template <typename T> template <typename T>
class URRTStateParser : public comm::URParser<RTPacket> class URRTStateParser : public comm::URParser<RTPacket>
@@ -56,4 +56,4 @@ typedef URRTStateParser<RTState_V1_6__7> URRTStateParser_V1_6__7;
typedef URRTStateParser<RTState_V1_8> URRTStateParser_V1_8; typedef URRTStateParser<RTState_V1_8> URRTStateParser_V1_8;
typedef URRTStateParser<RTState_V3_0__1> URRTStateParser_V3_0__1; typedef URRTStateParser<RTState_V3_0__1> URRTStateParser_V3_0__1;
typedef URRTStateParser<RTState_V3_2__3> URRTStateParser_V3_2__3; typedef URRTStateParser<RTState_V3_2__3> URRTStateParser_V3_2__3;
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/comm/pipeline.h" #include "ur_rtde_driver/comm/pipeline.h"
#include "ur_rtde_driver/types.h" #include "ur_rtde_driver/types.h"
namespace ur_rtde_driver namespace ur_driver
{ {
class URRTPacketConsumer; class URRTPacketConsumer;
@@ -137,4 +137,4 @@ public:
static_assert(RTState_V3_2__3::SIZE == 936, "RTState_V3_2__3 has mismatched size!"); static_assert(RTState_V3_2__3::SIZE == 936, "RTState_V3_2__3 has mismatched size!");
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -26,7 +26,7 @@
#include <string> #include <string>
#include "ur_rtde_driver/comm/tcp_socket.h" #include "ur_rtde_driver/comm/tcp_socket.h"
namespace ur_rtde_driver namespace ur_driver
{ {
#define MAX_SERVER_BUF_LEN 50 #define MAX_SERVER_BUF_LEN 50
@@ -49,4 +49,4 @@ public:
bool readLine(char* buffer, size_t buf_len); bool readLine(char* buffer, size_t buf_len);
bool write(const uint8_t* buf, size_t buf_len, size_t& written); bool write(const uint8_t* buf, size_t buf_len, size_t& written);
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/pipeline.h" #include "ur_rtde_driver/comm/pipeline.h"
namespace ur_rtde_driver namespace ur_driver
{ {
enum class package_type : uint8_t enum class package_type : uint8_t
{ {
@@ -61,4 +61,4 @@ public:
virtual bool parseWith(BinParser& bp) = 0; virtual bool parseWith(BinParser& bp) = 0;
virtual bool consumeWith(URStatePacketConsumer& consumer) = 0; virtual bool consumeWith(URStatePacketConsumer& consumer) = 0;
}; };
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -26,7 +26,7 @@
#include "ur_rtde_driver/ur/robot_mode.h" #include "ur_rtde_driver/ur/robot_mode.h"
#include "ur_rtde_driver/ur/state.h" #include "ur_rtde_driver/ur/state.h"
namespace ur_rtde_driver namespace ur_driver
{ {
template <typename RMD, typename MBD> template <typename RMD, typename MBD>
class URStateParser : public comm::URParser<StatePacket> class URStateParser : public comm::URParser<StatePacket>
@@ -117,4 +117,4 @@ typedef URStateParser<RobotModeData_V1_X, MasterBoardData_V1_X> URStateParser_V1
typedef URStateParser<RobotModeData_V3_0__1, MasterBoardData_V3_0__1> URStateParser_V3_0__1; 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_2, MasterBoardData_V3_2> URStateParser_V3_2;
typedef URStateParser<RobotModeData_V3_5, MasterBoardData_V3_2> URStateParser_V3_5; typedef URStateParser<RobotModeData_V3_5, MasterBoardData_V3_2> URStateParser_V3_5;
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/stream.h" #include "ur_rtde_driver/comm/stream.h"
namespace ur_rtde_driver namespace ur_driver
{ {
namespace comm namespace comm
{ {
@@ -65,4 +65,4 @@ bool URStream::read(uint8_t* buf, size_t buf_len, size_t& total)
return remainder == 0; return remainder == 0;
} }
} // namespace comm } // namespace comm
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -27,7 +27,7 @@
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/tcp_socket.h" #include "ur_rtde_driver/comm/tcp_socket.h"
namespace ur_rtde_driver namespace ur_driver
{ {
namespace comm namespace comm
{ {
@@ -189,4 +189,4 @@ bool TCPSocket::write(const uint8_t* buf, size_t buf_len, size_t& written)
return true; return true;
} }
} // namespace comm } // namespace comm
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -18,7 +18,7 @@
#include "ur_rtde_driver/ros/service_stopper.h" #include "ur_rtde_driver/ros/service_stopper.h"
namespace ur_rtde_driver namespace ur_driver
{ {
ServiceStopper::ServiceStopper(std::vector<Service*> services) ServiceStopper::ServiceStopper(std::vector<Service*> services)
: enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this)) : enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this))
@@ -94,4 +94,4 @@ bool ServiceStopper::handle(SharedRobotModeData& data, bool error)
return true; return true;
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -19,7 +19,7 @@
#include "ur_rtde_driver/ur/commander.h" #include "ur_rtde_driver/ur/commander.h"
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
namespace ur_rtde_driver namespace ur_driver
{ {
bool URCommander::write(const std::string& s) bool URCommander::write(const std::string& s)
{ {
@@ -170,4 +170,4 @@ bool URCommander_V3_3::speedj(std::array<double, 6>& speeds, double acceleration
std::string s(out.str()); std::string s(out.str());
return write(s); return write(s);
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -19,7 +19,7 @@
#include "ur_rtde_driver/ur/master_board.h" #include "ur_rtde_driver/ur/master_board.h"
#include "ur_rtde_driver/ur/consumer.h" #include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver namespace ur_driver
{ {
bool SharedMasterBoardData::parseWith(BinParser& bp) bool SharedMasterBoardData::parseWith(BinParser& bp)
{ {
@@ -121,4 +121,4 @@ bool MasterBoardData_V3_2::consumeWith(URStatePacketConsumer& consumer)
{ {
return consumer.consume(*this); return consumer.consume(*this);
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -19,7 +19,7 @@
#include "ur_rtde_driver/ur/messages.h" #include "ur_rtde_driver/ur/messages.h"
#include "ur_rtde_driver/ur/consumer.h" #include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver namespace ur_driver
{ {
bool VersionMessage::parseWith(BinParser& bp) bool VersionMessage::parseWith(BinParser& bp)
{ {
@@ -37,4 +37,4 @@ bool VersionMessage::consumeWith(URMessagePacketConsumer& consumer)
{ {
return consumer.consume(*this); return consumer.consume(*this);
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -19,7 +19,7 @@
#include "ur_rtde_driver/ur/robot_mode.h" #include "ur_rtde_driver/ur/robot_mode.h"
#include "ur_rtde_driver/ur/consumer.h" #include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver namespace ur_driver
{ {
bool SharedRobotModeData::parseWith(BinParser& bp) bool SharedRobotModeData::parseWith(BinParser& bp)
{ {
@@ -102,4 +102,4 @@ bool RobotModeData_V3_5::consumeWith(URStatePacketConsumer& consumer)
{ {
return consumer.consume(*this); return consumer.consume(*this);
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -19,7 +19,7 @@
#include "ur_rtde_driver/ur/rt_state.h" #include "ur_rtde_driver/ur/rt_state.h"
#include "ur_rtde_driver/ur/consumer.h" #include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver namespace ur_driver
{ {
void RTShared::parse_shared1(BinParser& bp) void RTShared::parse_shared1(BinParser& bp)
{ {
@@ -135,4 +135,4 @@ bool RTState_V3_2__3::consumeWith(URRTPacketConsumer& consumer)
{ {
return consumer.consume(*this); return consumer.consume(*this);
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -25,7 +25,7 @@
#include <cstring> #include <cstring>
#include "ur_rtde_driver/log.h" #include "ur_rtde_driver/log.h"
namespace ur_rtde_driver namespace ur_driver
{ {
URServer::URServer(int port) : port_(port) URServer::URServer(int port) : port_(port)
{ {
@@ -151,4 +151,4 @@ bool URServer::readLine(char* buffer, size_t buf_len)
*current_pointer = '\0'; *current_pointer = '\0';
return true; return true;
} }
} // namespace ur_rtde_driver } // namespace ur_driver

View File

@@ -22,7 +22,7 @@
#include "ur_rtde_driver/test/utils.h" #include "ur_rtde_driver/test/utils.h"
#include "ur_rtde_driver/types.h" #include "ur_rtde_driver/types.h"
using namespace ur_rtde_driver; using namespace ur_driver;
TEST(MasterBoardData_V1_X, testRandomDataParsing) TEST(MasterBoardData_V1_X, testRandomDataParsing)
{ {

View File

@@ -22,7 +22,7 @@
#include "ur_rtde_driver/test/utils.h" #include "ur_rtde_driver/test/utils.h"
#include "ur_rtde_driver/types.h" #include "ur_rtde_driver/types.h"
using namespace ur_rtde_driver; using namespace ur_driver;
TEST(RobotModeData_V1_X, testRandomDataParsing) TEST(RobotModeData_V1_X, testRandomDataParsing)
{ {
RandomDataTest rdt(24); RandomDataTest rdt(24);

View File

@@ -22,7 +22,7 @@
#include "ur_rtde_driver/test/utils.h" #include "ur_rtde_driver/test/utils.h"
#include "ur_rtde_driver/types.h" #include "ur_rtde_driver/types.h"
using namespace ur_rtde_driver; using namespace ur_driver;
TEST(RTState_V1_6__7, testRandomDataParsing) TEST(RTState_V1_6__7, testRandomDataParsing)
{ {