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

@@ -22,7 +22,7 @@
#include <sstream>
#include "ur_rtde_driver/comm/stream.h"
namespace ur_rtde_driver
namespace ur_driver
{
class URCommander
{
@@ -93,4 +93,4 @@ public:
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/state.h"
namespace ur_rtde_driver
namespace ur_driver
{
class URRTPacketConsumer : public comm::IConsumer<RTPacket>
{
@@ -68,4 +68,4 @@ public:
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/state_parser.h"
namespace ur_rtde_driver
namespace ur_driver
{
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/ur/state.h"
namespace ur_rtde_driver
namespace ur_driver
{
class SharedMasterBoardData
{
@@ -110,4 +110,4 @@ public:
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/comm/pipeline.h"
namespace ur_rtde_driver
namespace ur_driver
{
enum class robot_message_type : uint8_t
{
@@ -69,4 +69,4 @@ public:
int32_t svn_version;
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/ur/messages.h"
namespace ur_rtde_driver
namespace ur_driver
{
class URMessageParser : public comm::URParser<MessagePacket>
{
@@ -71,4 +71,4 @@ public:
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/stream.h"
namespace ur_rtde_driver
namespace ur_driver
{
template <typename T>
class URProducer : public comm::IProducer<T>
@@ -83,4 +83,4 @@ public:
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/ur/state.h"
namespace ur_rtde_driver
namespace ur_driver
{
class SharedRobotModeData
{
@@ -136,4 +136,4 @@ public:
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/ur/rt_state.h"
namespace ur_rtde_driver
namespace ur_driver
{
template <typename T>
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_V3_0__1> URRTStateParser_V3_0__1;
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/types.h"
namespace ur_rtde_driver
namespace ur_driver
{
class URRTPacketConsumer;
@@ -137,4 +137,4 @@ public:
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 "ur_rtde_driver/comm/tcp_socket.h"
namespace ur_rtde_driver
namespace ur_driver
{
#define MAX_SERVER_BUF_LEN 50
@@ -49,4 +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
} // namespace ur_driver

View File

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/pipeline.h"
namespace ur_rtde_driver
namespace ur_driver
{
enum class package_type : uint8_t
{
@@ -61,4 +61,4 @@ public:
virtual bool parseWith(BinParser& bp) = 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/state.h"
namespace ur_rtde_driver
namespace ur_driver
{
template <typename RMD, typename MBD>
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_2, MasterBoardData_V3_2> URStateParser_V3_2;
typedef URStateParser<RobotModeData_V3_5, MasterBoardData_V3_2> URStateParser_V3_5;
} // namespace ur_rtde_driver
} // namespace ur_driver