mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 11:00:47 +02:00
Put everyting into ur_rtde_driver namespace
This commit is contained in:
@@ -22,6 +22,8 @@
|
||||
#include <sstream>
|
||||
#include "ur_rtde_driver/ur/stream.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URCommander
|
||||
{
|
||||
private:
|
||||
@@ -91,3 +93,4 @@ public:
|
||||
|
||||
virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -25,6 +25,8 @@
|
||||
#include "ur_rtde_driver/ur/rt_state.h"
|
||||
#include "ur_rtde_driver/ur/state.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URRTPacketConsumer : public IConsumer<RTPacket>
|
||||
{
|
||||
public:
|
||||
@@ -65,4 +67,5 @@ public:
|
||||
}
|
||||
|
||||
virtual bool consume(VersionMessage& message) = 0;
|
||||
};
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -27,6 +27,8 @@
|
||||
#include "ur_rtde_driver/ur/state_parser.h"
|
||||
#include "ur_rtde_driver/ur/stream.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
static const int UR_PRIMARY_PORT = 30001;
|
||||
|
||||
class URFactory : private URMessagePacketConsumer
|
||||
@@ -138,4 +140,5 @@ public:
|
||||
return std::unique_ptr<URParser<RTPacket>>(new URRTStateParser_V3_2__3);
|
||||
}
|
||||
}
|
||||
};
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -25,6 +25,8 @@
|
||||
#include "ur_rtde_driver/types.h"
|
||||
#include "ur_rtde_driver/ur/state.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class SharedMasterBoardData
|
||||
{
|
||||
public:
|
||||
@@ -108,3 +110,4 @@ public:
|
||||
|
||||
static const size_t SIZE = MasterBoardData_V3_0__1::SIZE + sizeof(uint8_t) * 2;
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -23,6 +23,8 @@
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
enum class robot_message_type : uint8_t
|
||||
{
|
||||
ROBOT_MESSAGE_TEXT = 0,
|
||||
@@ -66,4 +68,5 @@ public:
|
||||
uint8_t minor_version;
|
||||
int32_t svn_version;
|
||||
std::string build_date;
|
||||
};
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -24,6 +24,8 @@
|
||||
#include "ur_rtde_driver/ur/messages.h"
|
||||
#include "ur_rtde_driver/ur/parser.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URMessageParser : public URParser<MessagePacket>
|
||||
{
|
||||
public:
|
||||
@@ -68,4 +70,5 @@ public:
|
||||
results.push_back(std::move(result));
|
||||
return parsed;
|
||||
}
|
||||
};
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -21,9 +21,12 @@
|
||||
#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
|
||||
|
||||
@@ -22,6 +22,8 @@
|
||||
#include "ur_rtde_driver/ur/parser.h"
|
||||
#include "ur_rtde_driver/ur/stream.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
template <typename T>
|
||||
class URProducer : public IProducer<T>
|
||||
{
|
||||
@@ -80,4 +82,5 @@ public:
|
||||
BinParser bp(buf, read);
|
||||
return parser_.parse(bp, products);
|
||||
}
|
||||
};
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -24,6 +24,8 @@
|
||||
#include "ur_rtde_driver/types.h"
|
||||
#include "ur_rtde_driver/ur/state.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class SharedRobotModeData
|
||||
{
|
||||
public:
|
||||
@@ -134,3 +136,4 @@ public:
|
||||
|
||||
static_assert(RobotModeData_V3_5::SIZE == 42, "RobotModeData_V3_5 has missmatched size");
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -24,6 +24,8 @@
|
||||
#include "ur_rtde_driver/ur/parser.h"
|
||||
#include "ur_rtde_driver/ur/rt_state.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
template <typename T>
|
||||
class URRTStateParser : public URParser<RTPacket>
|
||||
{
|
||||
@@ -53,4 +55,5 @@ public:
|
||||
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;
|
||||
typedef URRTStateParser<RTState_V3_2__3> URRTStateParser_V3_2__3;
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -24,6 +24,8 @@
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/types.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URRTPacketConsumer;
|
||||
|
||||
class RTPacket
|
||||
@@ -134,4 +136,5 @@ public:
|
||||
static const size_t SIZE = RTState_V3_0__1::SIZE + sizeof(uint64_t) + sizeof(double);
|
||||
|
||||
static_assert(RTState_V3_2__3::SIZE == 936, "RTState_V3_2__3 has mismatched size!");
|
||||
};
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -26,6 +26,8 @@
|
||||
#include <string>
|
||||
#include "ur_rtde_driver/tcp_socket.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
#define MAX_SERVER_BUF_LEN 50
|
||||
|
||||
class URServer : private TCPSocket
|
||||
@@ -47,3 +49,4 @@ public:
|
||||
bool readLine(char* buffer, size_t buf_len);
|
||||
bool write(const uint8_t* buf, size_t buf_len, size_t& written);
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -24,6 +24,8 @@
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
enum class package_type : uint8_t
|
||||
{
|
||||
ROBOT_MODE_DATA = 0,
|
||||
@@ -59,3 +61,4 @@ public:
|
||||
virtual bool parseWith(BinParser& bp) = 0;
|
||||
virtual bool consumeWith(URStatePacketConsumer& consumer) = 0;
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -26,6 +26,8 @@
|
||||
#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>
|
||||
{
|
||||
@@ -115,3 +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_2, MasterBoardData_V3_2> URStateParser_V3_2;
|
||||
typedef URStateParser<RobotModeData_V3_5, MasterBoardData_V3_2> URStateParser_V3_5;
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -26,6 +26,8 @@
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/tcp_socket.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URStream : public TCPSocket
|
||||
{
|
||||
private:
|
||||
@@ -61,4 +63,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 ur_rtde_driver
|
||||
|
||||
Reference in New Issue
Block a user