mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-13 11:30:47 +02:00
Put everyting into ur_rtde_driver namespace
This commit is contained in:
@@ -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
|
||||
|
||||
@@ -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:
|
||||
@@ -100,3 +102,4 @@ public:
|
||||
{
|
||||
}
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -28,6 +28,8 @@
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/ur/commander.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class IOService
|
||||
{
|
||||
private:
|
||||
@@ -77,3 +79,4 @@ public:
|
||||
{
|
||||
}
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -26,6 +26,8 @@
|
||||
#include <random>
|
||||
#include "ur_rtde_driver/bin_parser.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class RandomDataTest
|
||||
{
|
||||
private:
|
||||
@@ -78,3 +80,4 @@ public:
|
||||
bp_.consume(n);
|
||||
}
|
||||
};
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -20,6 +20,8 @@
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
struct double3_t
|
||||
{
|
||||
double x, y, z;
|
||||
@@ -40,3 +42,4 @@ inline bool operator==(const cartesian_coord_t& lhs, const cartesian_coord_t& rh
|
||||
{
|
||||
return lhs.position == rhs.position && lhs.rotation == rhs.rotation;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -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:
|
||||
@@ -66,3 +68,4 @@ 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
|
||||
@@ -139,3 +141,4 @@ public:
|
||||
}
|
||||
}
|
||||
};
|
||||
} // 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,
|
||||
@@ -67,3 +69,4 @@ public:
|
||||
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:
|
||||
@@ -69,3 +71,4 @@ public:
|
||||
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>
|
||||
{
|
||||
@@ -81,3 +83,4 @@ public:
|
||||
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>
|
||||
{
|
||||
@@ -54,3 +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
|
||||
|
||||
@@ -24,6 +24,8 @@
|
||||
#include "ur_rtde_driver/pipeline.h"
|
||||
#include "ur_rtde_driver/types.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
class URRTPacketConsumer;
|
||||
|
||||
class RTPacket
|
||||
@@ -135,3 +137,4 @@ public:
|
||||
|
||||
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:
|
||||
@@ -62,3 +64,4 @@ 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
|
||||
|
||||
@@ -21,6 +21,8 @@
|
||||
#include "ur_rtde_driver/ros/action_server.h"
|
||||
#include <cmath>
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
ActionServer::ActionServer(ActionTrajectoryFollowerInterface& follower, std::vector<std::string>& joint_names,
|
||||
double max_velocity)
|
||||
: as_(nh_, "follow_joint_trajectory", boost::bind(&ActionServer::onGoal, this, _1),
|
||||
@@ -367,3 +369,4 @@ void ActionServer::trajectoryThread()
|
||||
lk.unlock();
|
||||
}
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -18,6 +18,8 @@
|
||||
|
||||
#include "ur_rtde_driver/ros/controller.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
ROSController::ROSController(URCommander& commander, TrajectoryFollower& follower,
|
||||
std::vector<std::string>& joint_names, double max_vel_change, std::string tcp_link)
|
||||
: controller_(this, nh_)
|
||||
@@ -147,3 +149,4 @@ void ROSController::onRobotStateChange(RobotState state)
|
||||
service_enabled_ = next;
|
||||
service_cooldown_ = 125;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include "ur_rtde_driver/ros/hardware_interface.h"
|
||||
#include "ur_rtde_driver/log.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
const std::string JointInterface::INTERFACE_NAME = "hardware_interface::JointStateInterface";
|
||||
JointInterface::JointInterface(std::vector<std::string>& joint_names)
|
||||
{
|
||||
@@ -104,3 +106,4 @@ void PositionInterface::stop()
|
||||
{
|
||||
follower_.stop();
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include <ros/ros.h>
|
||||
#include <cmath>
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
static const std::array<double, 6> EMPTY_VALUES = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
|
||||
|
||||
static const std::string TIME_INTERVAL("{{TIME_INTERVAL}}");
|
||||
@@ -402,3 +404,4 @@ void LowBandwidthTrajectoryFollower::stop()
|
||||
server_.disconnectClient();
|
||||
running_ = false;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -18,6 +18,8 @@
|
||||
|
||||
#include "ur_rtde_driver/ros/mb_publisher.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
inline void appendAnalog(std::vector<ur_msgs::Analog>& vec, double val, uint8_t pin)
|
||||
{
|
||||
ur_msgs::Analog ana;
|
||||
@@ -130,3 +132,4 @@ bool MBPublisher::consume(RobotModeData_V3_2& data)
|
||||
publishRobotStatus(data);
|
||||
return true;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -18,6 +18,8 @@
|
||||
|
||||
#include "ur_rtde_driver/ros/rt_publisher.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
bool RTPublisher::publishJoints(RTShared& packet, Time& t)
|
||||
{
|
||||
sensor_msgs::JointState joint_msg;
|
||||
@@ -134,3 +136,4 @@ bool RTPublisher::consume(RTState_V3_2__3& state)
|
||||
{
|
||||
return publish(state);
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -18,6 +18,8 @@
|
||||
|
||||
#include "ur_rtde_driver/ros/service_stopper.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
ServiceStopper::ServiceStopper(std::vector<Service*> services)
|
||||
: enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this))
|
||||
, services_(services)
|
||||
@@ -92,3 +94,4 @@ bool ServiceStopper::handle(SharedRobotModeData& data, bool error)
|
||||
|
||||
return true;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -83,6 +83,8 @@ def driverProg():
|
||||
end
|
||||
)";
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
TrajectoryFollower::TrajectoryFollower(URCommander& commander, std::string& reverse_ip, int reverse_port,
|
||||
bool version_3)
|
||||
: running_(false)
|
||||
@@ -259,3 +261,4 @@ void TrajectoryFollower::stop()
|
||||
server_.disconnectClient();
|
||||
running_ = false;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include "ur_rtde_driver/ros/urscript_handler.h"
|
||||
#include "ur_rtde_driver/log.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
URScriptHandler::URScriptHandler(URCommander& commander) : commander_(commander), state_(RobotState::Error)
|
||||
{
|
||||
LOG_INFO("Initializing ur_driver/URScript subscriber");
|
||||
@@ -60,3 +62,4 @@ void URScriptHandler::onRobotStateChange(RobotState state)
|
||||
{
|
||||
state_ = state;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -61,6 +61,8 @@ static const std::vector<std::string> DEFAULT_JOINTS = { "shoulder_pan_joint", "
|
||||
static const int UR_SECONDARY_PORT = 30002;
|
||||
static const int UR_RT_PORT = 30003;
|
||||
|
||||
using namespace ur_rtde_driver;
|
||||
|
||||
struct ProgArgs
|
||||
{
|
||||
public:
|
||||
|
||||
@@ -27,6 +27,8 @@
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/tcp_socket.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
TCPSocket::TCPSocket() : socket_fd_(-1), state_(SocketState::Invalid)
|
||||
{
|
||||
}
|
||||
@@ -184,3 +186,4 @@ bool TCPSocket::write(const uint8_t* buf, size_t buf_len, size_t& written)
|
||||
|
||||
return true;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include "ur_rtde_driver/ur/commander.h"
|
||||
#include "ur_rtde_driver/log.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
bool URCommander::write(const std::string& s)
|
||||
{
|
||||
size_t len = s.size();
|
||||
@@ -168,3 +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
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include "ur_rtde_driver/ur/master_board.h"
|
||||
#include "ur_rtde_driver/ur/consumer.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
bool SharedMasterBoardData::parseWith(BinParser& bp)
|
||||
{
|
||||
bp.parse(analog_input_range0);
|
||||
@@ -119,3 +121,4 @@ bool MasterBoardData_V3_2::consumeWith(URStatePacketConsumer& consumer)
|
||||
{
|
||||
return consumer.consume(*this);
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include "ur_rtde_driver/ur/messages.h"
|
||||
#include "ur_rtde_driver/ur/consumer.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
bool VersionMessage::parseWith(BinParser& bp)
|
||||
{
|
||||
bp.parse(project_name);
|
||||
@@ -35,3 +37,4 @@ bool VersionMessage::consumeWith(URMessagePacketConsumer& consumer)
|
||||
{
|
||||
return consumer.consume(*this);
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include "ur_rtde_driver/ur/robot_mode.h"
|
||||
#include "ur_rtde_driver/ur/consumer.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
bool SharedRobotModeData::parseWith(BinParser& bp)
|
||||
{
|
||||
bp.parse(timestamp);
|
||||
@@ -100,3 +102,4 @@ bool RobotModeData_V3_5::consumeWith(URStatePacketConsumer& consumer)
|
||||
{
|
||||
return consumer.consume(*this);
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -19,6 +19,8 @@
|
||||
#include "ur_rtde_driver/ur/rt_state.h"
|
||||
#include "ur_rtde_driver/ur/consumer.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
void RTShared::parse_shared1(BinParser& bp)
|
||||
{
|
||||
bp.parse(time);
|
||||
@@ -133,3 +135,4 @@ bool RTState_V3_2__3::consumeWith(URRTPacketConsumer& consumer)
|
||||
{
|
||||
return consumer.consume(*this);
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -25,6 +25,8 @@
|
||||
#include <cstring>
|
||||
#include "ur_rtde_driver/log.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
URServer::URServer(int port) : port_(port)
|
||||
{
|
||||
}
|
||||
@@ -149,3 +151,4 @@ bool URServer::readLine(char* buffer, size_t buf_len)
|
||||
*current_pointer = '\0';
|
||||
return true;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -24,6 +24,8 @@
|
||||
#include "ur_rtde_driver/log.h"
|
||||
#include "ur_rtde_driver/ur/stream.h"
|
||||
|
||||
namespace ur_rtde_driver
|
||||
{
|
||||
bool URStream::write(const uint8_t* buf, size_t buf_len, size_t& written)
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(write_mutex_);
|
||||
@@ -60,3 +62,4 @@ bool URStream::read(uint8_t* buf, size_t buf_len, size_t& total)
|
||||
|
||||
return remainder == 0;
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
@@ -22,6 +22,8 @@
|
||||
#include "ur_rtde_driver/test/utils.h"
|
||||
#include "ur_rtde_driver/types.h"
|
||||
|
||||
using namespace ur_rtde_driver;
|
||||
|
||||
TEST(MasterBoardData_V1_X, testRandomDataParsing)
|
||||
{
|
||||
RandomDataTest rdt(71);
|
||||
|
||||
@@ -22,6 +22,7 @@
|
||||
#include "ur_rtde_driver/test/utils.h"
|
||||
#include "ur_rtde_driver/types.h"
|
||||
|
||||
using namespace ur_rtde_driver;
|
||||
TEST(RobotModeData_V1_X, testRandomDataParsing)
|
||||
{
|
||||
RandomDataTest rdt(24);
|
||||
|
||||
@@ -22,6 +22,8 @@
|
||||
#include "ur_rtde_driver/test/utils.h"
|
||||
#include "ur_rtde_driver/types.h"
|
||||
|
||||
using namespace ur_rtde_driver;
|
||||
|
||||
TEST(RTState_V1_6__7, testRandomDataParsing)
|
||||
{
|
||||
RandomDataTest rdt(764);
|
||||
|
||||
Reference in New Issue
Block a user