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

Put everyting into ur_rtde_driver namespace

This commit is contained in:
Felix Mauch
2019-04-01 13:20:25 +02:00
parent 515dd41edc
commit 5840d4f406
53 changed files with 172 additions and 17 deletions

View File

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

View File

@@ -23,6 +23,8 @@
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver
{
class EventCounter : public URRTPacketConsumer
{
private:
@@ -99,4 +101,5 @@ public:
void stopConsumer()
{
}
};
};
} // namespace ur_rtde_driver

View File

@@ -25,6 +25,9 @@
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/queue/readerwriterqueue.h"
namespace ur_rtde_driver
{
// TODO: Remove these!!!
using namespace moodycamel;
using namespace std;
@@ -230,3 +233,4 @@ public:
notifier_.stopped(name_);
}
};
} // namespace ur_rtde_driver

View File

@@ -37,6 +37,8 @@
#include "ur_rtde_driver/ur/master_board.h"
#include "ur_rtde_driver/ur/state.h"
namespace ur_rtde_driver
{
class ActionServer : public Service, public URRTPacketConsumer
{
private:
@@ -91,3 +93,4 @@ public:
virtual bool consume(RTState_V3_0__1& state);
virtual bool consume(RTState_V3_2__3& state);
};
} // namespace ur_rtde_driver

View File

@@ -26,6 +26,8 @@
#include <cstddef>
#include <vector>
namespace ur_rtde_driver
{
struct TrajectoryPoint
{
std::array<double, 6> positions;
@@ -50,3 +52,4 @@ public:
virtual void stop() = 0;
virtual ~ActionTrajectoryFollowerInterface(){};
};
} // namespace ur_rtde_driver

View File

@@ -31,6 +31,8 @@
#include "ur_rtde_driver/ur/consumer.h"
#include "ur_rtde_driver/ur/rt_state.h"
namespace ur_rtde_driver
{
class ROSController : private hardware_interface::RobotHW, public URRTPacketConsumer, public Service
{
private:
@@ -108,3 +110,4 @@ public:
virtual void onRobotStateChange(RobotState state);
};
} // namespace ur_rtde_driver

View File

@@ -26,6 +26,8 @@
#include "ur_rtde_driver/ur/commander.h"
#include "ur_rtde_driver/ur/rt_state.h"
namespace ur_rtde_driver
{
class HardwareInterface
{
public:
@@ -99,3 +101,4 @@ public:
typedef hardware_interface::PositionJointInterface parent_type;
static const std::string INTERFACE_NAME;
};
} // namespace ur_rtde_driver

View File

@@ -28,6 +28,8 @@
#include "ur_rtde_driver/log.h"
#include "ur_rtde_driver/ur/commander.h"
namespace ur_rtde_driver
{
class IOService
{
private:
@@ -76,4 +78,5 @@ public:
, payload_service_(nh_.advertiseService("ur_driver/set_payload", &IOService::setPayload, this))
{
}
};
};
} // namespace ur_rtde_driver

View File

@@ -29,6 +29,8 @@
#include "ur_rtde_driver/ur/commander.h"
#include "ur_rtde_driver/ur/server.h"
namespace ur_rtde_driver
{
class LowBandwidthTrajectoryFollower : public ActionTrajectoryFollowerInterface
{
private:
@@ -54,3 +56,4 @@ public:
virtual ~LowBandwidthTrajectoryFollower(){};
};
} // namespace ur_rtde_driver

View File

@@ -26,6 +26,8 @@
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver
{
using namespace ros;
class MBPublisher : public URStatePacketConsumer
@@ -77,3 +79,4 @@ public:
{
}
};
} // namespace ur_rtde_driver

View File

@@ -31,6 +31,8 @@
#include "ur_rtde_driver/ur/consumer.h"
namespace ur_rtde_driver
{
using namespace ros;
using namespace tf;
@@ -90,3 +92,4 @@ public:
{
}
};
} // namespace ur_rtde_driver

View File

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

View File

@@ -33,6 +33,8 @@
#include "ur_rtde_driver/ur/commander.h"
#include "ur_rtde_driver/ur/server.h"
namespace ur_rtde_driver
{
class TrajectoryFollower : public ActionTrajectoryFollowerInterface
{
private:
@@ -65,3 +67,4 @@ public:
virtual ~TrajectoryFollower(){};
};
} // namespace ur_rtde_driver

View File

@@ -26,6 +26,8 @@
#include "ur_rtde_driver/ros/service_stopper.h"
#include "ur_rtde_driver/ur/commander.h"
namespace ur_rtde_driver
{
class URScriptHandler : public Service
{
private:
@@ -39,3 +41,4 @@ public:
void urscriptInterface(const std_msgs::String::ConstPtr& msg);
void onRobotStateChange(RobotState state);
};
} // namespace ur_rtde_driver

View File

@@ -24,6 +24,8 @@
#include <mutex>
#include <string>
namespace ur_rtde_driver
{
enum class SocketState
{
Invalid,
@@ -70,3 +72,4 @@ public:
void close();
};
} // namespace ur_rtde_driver

View File

@@ -26,6 +26,8 @@
#include <random>
#include "ur_rtde_driver/bin_parser.h"
namespace ur_rtde_driver
{
class RandomDataTest
{
private:
@@ -77,4 +79,5 @@ public:
{
bp_.consume(n);
}
};
};
} // namespace ur_rtde_driver

View File

@@ -20,6 +20,8 @@
#include <inttypes.h>
namespace ur_rtde_driver
{
struct double3_t
{
double x, y, z;
@@ -39,4 +41,5 @@ inline bool operator==(const double3_t& lhs, const double3_t& rhs)
inline bool operator==(const cartesian_coord_t& lhs, const cartesian_coord_t& rhs)
{
return lhs.position == rhs.position && lhs.rotation == rhs.rotation;
}
}
} // namespace ur_rtde_driver

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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