1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-12 11:00:47 +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

@@ -24,7 +24,7 @@
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/comm/stream.h"
namespace ur_rtde_driver
namespace ur_driver
{
namespace comm
{
@@ -65,4 +65,4 @@ bool URStream::read(uint8_t* buf, size_t buf_len, size_t& total)
return remainder == 0;
}
} // 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/comm/tcp_socket.h"
namespace ur_rtde_driver
namespace ur_driver
{
namespace comm
{
@@ -189,4 +189,4 @@ bool TCPSocket::write(const uint8_t* buf, size_t buf_len, size_t& written)
return true;
}
} // namespace comm
} // namespace ur_rtde_driver
} // namespace ur_driver

View File

@@ -18,7 +18,7 @@
#include "ur_rtde_driver/ros/service_stopper.h"
namespace ur_rtde_driver
namespace ur_driver
{
ServiceStopper::ServiceStopper(std::vector<Service*> services)
: enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this))
@@ -94,4 +94,4 @@ bool ServiceStopper::handle(SharedRobotModeData& data, bool error)
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/log.h"
namespace ur_rtde_driver
namespace ur_driver
{
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());
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/consumer.h"
namespace ur_rtde_driver
namespace ur_driver
{
bool SharedMasterBoardData::parseWith(BinParser& bp)
{
@@ -121,4 +121,4 @@ bool MasterBoardData_V3_2::consumeWith(URStatePacketConsumer& consumer)
{
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/consumer.h"
namespace ur_rtde_driver
namespace ur_driver
{
bool VersionMessage::parseWith(BinParser& bp)
{
@@ -37,4 +37,4 @@ bool VersionMessage::consumeWith(URMessagePacketConsumer& consumer)
{
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/consumer.h"
namespace ur_rtde_driver
namespace ur_driver
{
bool SharedRobotModeData::parseWith(BinParser& bp)
{
@@ -102,4 +102,4 @@ bool RobotModeData_V3_5::consumeWith(URStatePacketConsumer& consumer)
{
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/consumer.h"
namespace ur_rtde_driver
namespace ur_driver
{
void RTShared::parse_shared1(BinParser& bp)
{
@@ -135,4 +135,4 @@ bool RTState_V3_2__3::consumeWith(URRTPacketConsumer& consumer)
{
return consumer.consume(*this);
}
} // namespace ur_rtde_driver
} // namespace ur_driver

View File

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