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:
@@ -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);
|
||||
@@ -118,4 +120,5 @@ bool MasterBoardData_V3_0__1::consumeWith(URStatePacketConsumer& consumer)
|
||||
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);
|
||||
@@ -34,4 +36,5 @@ bool VersionMessage::parseWith(BinParser& bp)
|
||||
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);
|
||||
@@ -132,4 +134,5 @@ bool RTState_V3_0__1::consumeWith(URRTPacketConsumer& consumer)
|
||||
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_);
|
||||
@@ -59,4 +61,5 @@ bool URStream::read(uint8_t* buf, size_t buf_len, size_t& total)
|
||||
}
|
||||
|
||||
return remainder == 0;
|
||||
}
|
||||
}
|
||||
} // namespace ur_rtde_driver
|
||||
|
||||
Reference in New Issue
Block a user