diff --git a/include/ur_rtde_driver/bin_parser.h b/include/ur_rtde_driver/bin_parser.h index 65baf49..1915ddd 100644 --- a/include/ur_rtde_driver/bin_parser.h +++ b/include/ur_rtde_driver/bin_parser.h @@ -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 diff --git a/include/ur_rtde_driver/event_counter.h b/include/ur_rtde_driver/event_counter.h index 60ff1ea..46a25fd 100644 --- a/include/ur_rtde_driver/event_counter.h +++ b/include/ur_rtde_driver/event_counter.h @@ -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() { } -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/pipeline.h b/include/ur_rtde_driver/pipeline.h index a855c4f..ef7d950 100644 --- a/include/ur_rtde_driver/pipeline.h +++ b/include/ur_rtde_driver/pipeline.h @@ -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 diff --git a/include/ur_rtde_driver/ros/action_server.h b/include/ur_rtde_driver/ros/action_server.h index ffb2eb5..6a77a6f 100644 --- a/include/ur_rtde_driver/ros/action_server.h +++ b/include/ur_rtde_driver/ros/action_server.h @@ -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 diff --git a/include/ur_rtde_driver/ros/action_trajectory_follower_interface.h b/include/ur_rtde_driver/ros/action_trajectory_follower_interface.h index 9157dc0..13cd484 100644 --- a/include/ur_rtde_driver/ros/action_trajectory_follower_interface.h +++ b/include/ur_rtde_driver/ros/action_trajectory_follower_interface.h @@ -26,6 +26,8 @@ #include #include +namespace ur_rtde_driver +{ struct TrajectoryPoint { std::array positions; @@ -50,3 +52,4 @@ public: virtual void stop() = 0; virtual ~ActionTrajectoryFollowerInterface(){}; }; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ros/controller.h b/include/ur_rtde_driver/ros/controller.h index 8e9a0c0..4c6e5f1 100644 --- a/include/ur_rtde_driver/ros/controller.h +++ b/include/ur_rtde_driver/ros/controller.h @@ -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 diff --git a/include/ur_rtde_driver/ros/hardware_interface.h b/include/ur_rtde_driver/ros/hardware_interface.h index 1663918..6152c14 100644 --- a/include/ur_rtde_driver/ros/hardware_interface.h +++ b/include/ur_rtde_driver/ros/hardware_interface.h @@ -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 diff --git a/include/ur_rtde_driver/ros/io_service.h b/include/ur_rtde_driver/ros/io_service.h index 8a8c961..293ab9e 100644 --- a/include/ur_rtde_driver/ros/io_service.h +++ b/include/ur_rtde_driver/ros/io_service.h @@ -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)) { } -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ros/lowbandwidth_trajectory_follower.h b/include/ur_rtde_driver/ros/lowbandwidth_trajectory_follower.h index 9962866..54e68d5 100644 --- a/include/ur_rtde_driver/ros/lowbandwidth_trajectory_follower.h +++ b/include/ur_rtde_driver/ros/lowbandwidth_trajectory_follower.h @@ -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 diff --git a/include/ur_rtde_driver/ros/mb_publisher.h b/include/ur_rtde_driver/ros/mb_publisher.h index 445a046..76c0c18 100644 --- a/include/ur_rtde_driver/ros/mb_publisher.h +++ b/include/ur_rtde_driver/ros/mb_publisher.h @@ -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 diff --git a/include/ur_rtde_driver/ros/rt_publisher.h b/include/ur_rtde_driver/ros/rt_publisher.h index 5623031..bdc5ca8 100644 --- a/include/ur_rtde_driver/ros/rt_publisher.h +++ b/include/ur_rtde_driver/ros/rt_publisher.h @@ -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 diff --git a/include/ur_rtde_driver/ros/service_stopper.h b/include/ur_rtde_driver/ros/service_stopper.h index 2829bd1..bb5cac4 100644 --- a/include/ur_rtde_driver/ros/service_stopper.h +++ b/include/ur_rtde_driver/ros/service_stopper.h @@ -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 diff --git a/include/ur_rtde_driver/ros/trajectory_follower.h b/include/ur_rtde_driver/ros/trajectory_follower.h index d30d8dd..d1cb659 100644 --- a/include/ur_rtde_driver/ros/trajectory_follower.h +++ b/include/ur_rtde_driver/ros/trajectory_follower.h @@ -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 diff --git a/include/ur_rtde_driver/ros/urscript_handler.h b/include/ur_rtde_driver/ros/urscript_handler.h index 74cb891..bac501d 100644 --- a/include/ur_rtde_driver/ros/urscript_handler.h +++ b/include/ur_rtde_driver/ros/urscript_handler.h @@ -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 diff --git a/include/ur_rtde_driver/tcp_socket.h b/include/ur_rtde_driver/tcp_socket.h index 36709bb..459de96 100644 --- a/include/ur_rtde_driver/tcp_socket.h +++ b/include/ur_rtde_driver/tcp_socket.h @@ -24,6 +24,8 @@ #include #include +namespace ur_rtde_driver +{ enum class SocketState { Invalid, @@ -70,3 +72,4 @@ public: void close(); }; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/test/random_data.h b/include/ur_rtde_driver/test/random_data.h index bdb75b3..a280588 100644 --- a/include/ur_rtde_driver/test/random_data.h +++ b/include/ur_rtde_driver/test/random_data.h @@ -26,6 +26,8 @@ #include #include "ur_rtde_driver/bin_parser.h" +namespace ur_rtde_driver +{ class RandomDataTest { private: @@ -77,4 +79,5 @@ public: { bp_.consume(n); } -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/types.h b/include/ur_rtde_driver/types.h index 2293dac..b5f4f1e 100644 --- a/include/ur_rtde_driver/types.h +++ b/include/ur_rtde_driver/types.h @@ -20,6 +20,8 @@ #include +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; -} \ No newline at end of file +} +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/commander.h b/include/ur_rtde_driver/ur/commander.h index 0166fe5..e7f20c5 100644 --- a/include/ur_rtde_driver/ur/commander.h +++ b/include/ur_rtde_driver/ur/commander.h @@ -22,6 +22,8 @@ #include #include "ur_rtde_driver/ur/stream.h" +namespace ur_rtde_driver +{ class URCommander { private: @@ -91,3 +93,4 @@ public: virtual bool speedj(std::array& speeds, double acceleration); }; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/consumer.h b/include/ur_rtde_driver/ur/consumer.h index 547af27..6cfd65b 100644 --- a/include/ur_rtde_driver/ur/consumer.h +++ b/include/ur_rtde_driver/ur/consumer.h @@ -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 { public: @@ -65,4 +67,5 @@ public: } virtual bool consume(VersionMessage& message) = 0; -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/factory.h b/include/ur_rtde_driver/ur/factory.h index ef0c994..ea33f16 100644 --- a/include/ur_rtde_driver/ur/factory.h +++ b/include/ur_rtde_driver/ur/factory.h @@ -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>(new URRTStateParser_V3_2__3); } } -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/master_board.h b/include/ur_rtde_driver/ur/master_board.h index 9501b6a..96fac79 100644 --- a/include/ur_rtde_driver/ur/master_board.h +++ b/include/ur_rtde_driver/ur/master_board.h @@ -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 diff --git a/include/ur_rtde_driver/ur/messages.h b/include/ur_rtde_driver/ur/messages.h index cf348b3..ac5ec76 100644 --- a/include/ur_rtde_driver/ur/messages.h +++ b/include/ur_rtde_driver/ur/messages.h @@ -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; -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/messages_parser.h b/include/ur_rtde_driver/ur/messages_parser.h index ea7d482..00c9e8a 100644 --- a/include/ur_rtde_driver/ur/messages_parser.h +++ b/include/ur_rtde_driver/ur/messages_parser.h @@ -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 { public: @@ -68,4 +70,5 @@ public: results.push_back(std::move(result)); return parsed; } -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/parser.h b/include/ur_rtde_driver/ur/parser.h index 345d0d7..d175658 100644 --- a/include/ur_rtde_driver/ur/parser.h +++ b/include/ur_rtde_driver/ur/parser.h @@ -21,9 +21,12 @@ #include "ur_rtde_driver/bin_parser.h" #include "ur_rtde_driver/pipeline.h" +namespace ur_rtde_driver +{ template class URParser { public: virtual bool parse(BinParser& bp, std::vector>& results) = 0; }; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/producer.h b/include/ur_rtde_driver/ur/producer.h index b016e12..a0af94a 100644 --- a/include/ur_rtde_driver/ur/producer.h +++ b/include/ur_rtde_driver/ur/producer.h @@ -22,6 +22,8 @@ #include "ur_rtde_driver/ur/parser.h" #include "ur_rtde_driver/ur/stream.h" +namespace ur_rtde_driver +{ template class URProducer : public IProducer { @@ -80,4 +82,5 @@ public: BinParser bp(buf, read); return parser_.parse(bp, products); } -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/robot_mode.h b/include/ur_rtde_driver/ur/robot_mode.h index 6007887..0f0e5a5 100644 --- a/include/ur_rtde_driver/ur/robot_mode.h +++ b/include/ur_rtde_driver/ur/robot_mode.h @@ -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 diff --git a/include/ur_rtde_driver/ur/rt_parser.h b/include/ur_rtde_driver/ur/rt_parser.h index 92d3399..068489f 100644 --- a/include/ur_rtde_driver/ur/rt_parser.h +++ b/include/ur_rtde_driver/ur/rt_parser.h @@ -24,6 +24,8 @@ #include "ur_rtde_driver/ur/parser.h" #include "ur_rtde_driver/ur/rt_state.h" +namespace ur_rtde_driver +{ template class URRTStateParser : public URParser { @@ -53,4 +55,5 @@ public: typedef URRTStateParser URRTStateParser_V1_6__7; typedef URRTStateParser URRTStateParser_V1_8; typedef URRTStateParser URRTStateParser_V3_0__1; -typedef URRTStateParser URRTStateParser_V3_2__3; \ No newline at end of file +typedef URRTStateParser URRTStateParser_V3_2__3; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/rt_state.h b/include/ur_rtde_driver/ur/rt_state.h index 149bf21..4bfdede 100644 --- a/include/ur_rtde_driver/ur/rt_state.h +++ b/include/ur_rtde_driver/ur/rt_state.h @@ -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!"); -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/server.h b/include/ur_rtde_driver/ur/server.h index 4bf938f..1484da0 100644 --- a/include/ur_rtde_driver/ur/server.h +++ b/include/ur_rtde_driver/ur/server.h @@ -26,6 +26,8 @@ #include #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 diff --git a/include/ur_rtde_driver/ur/state.h b/include/ur_rtde_driver/ur/state.h index 50d4668..fdbe24d 100644 --- a/include/ur_rtde_driver/ur/state.h +++ b/include/ur_rtde_driver/ur/state.h @@ -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 diff --git a/include/ur_rtde_driver/ur/state_parser.h b/include/ur_rtde_driver/ur/state_parser.h index 51a819e..53bfc4b 100644 --- a/include/ur_rtde_driver/ur/state_parser.h +++ b/include/ur_rtde_driver/ur/state_parser.h @@ -26,6 +26,8 @@ #include "ur_rtde_driver/ur/robot_mode.h" #include "ur_rtde_driver/ur/state.h" +namespace ur_rtde_driver +{ template class URStateParser : public URParser { @@ -115,3 +117,4 @@ typedef URStateParser URStateParser_V1 typedef URStateParser URStateParser_V3_0__1; typedef URStateParser URStateParser_V3_2; typedef URStateParser URStateParser_V3_5; +} // namespace ur_rtde_driver diff --git a/include/ur_rtde_driver/ur/stream.h b/include/ur_rtde_driver/ur/stream.h index 38d016f..0e5bcf5 100644 --- a/include/ur_rtde_driver/ur/stream.h +++ b/include/ur_rtde_driver/ur/stream.h @@ -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); -}; \ No newline at end of file +}; +} // namespace ur_rtde_driver diff --git a/src/ros/action_server.cpp b/src/ros/action_server.cpp index ce1f3e6..1265470 100644 --- a/src/ros/action_server.cpp +++ b/src/ros/action_server.cpp @@ -21,6 +21,8 @@ #include "ur_rtde_driver/ros/action_server.h" #include +namespace ur_rtde_driver +{ ActionServer::ActionServer(ActionTrajectoryFollowerInterface& follower, std::vector& 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 diff --git a/src/ros/controller.cpp b/src/ros/controller.cpp index b2f1fc6..554ecaa 100644 --- a/src/ros/controller.cpp +++ b/src/ros/controller.cpp @@ -18,6 +18,8 @@ #include "ur_rtde_driver/ros/controller.h" +namespace ur_rtde_driver +{ ROSController::ROSController(URCommander& commander, TrajectoryFollower& follower, std::vector& 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 diff --git a/src/ros/hardware_interface.cpp b/src/ros/hardware_interface.cpp index 320ab6f..636c1ea 100644 --- a/src/ros/hardware_interface.cpp +++ b/src/ros/hardware_interface.cpp @@ -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& joint_names) { @@ -104,3 +106,4 @@ void PositionInterface::stop() { follower_.stop(); } +} // namespace ur_rtde_driver diff --git a/src/ros/lowbandwidth_trajectory_follower.cpp b/src/ros/lowbandwidth_trajectory_follower.cpp index 965ddee..87f13be 100644 --- a/src/ros/lowbandwidth_trajectory_follower.cpp +++ b/src/ros/lowbandwidth_trajectory_follower.cpp @@ -19,6 +19,8 @@ #include #include +namespace ur_rtde_driver +{ static const std::array 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 diff --git a/src/ros/mb_publisher.cpp b/src/ros/mb_publisher.cpp index 62cc4ea..7cec1ae 100644 --- a/src/ros/mb_publisher.cpp +++ b/src/ros/mb_publisher.cpp @@ -18,6 +18,8 @@ #include "ur_rtde_driver/ros/mb_publisher.h" +namespace ur_rtde_driver +{ inline void appendAnalog(std::vector& 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 diff --git a/src/ros/rt_publisher.cpp b/src/ros/rt_publisher.cpp index 1e4a42c..0ffd549 100644 --- a/src/ros/rt_publisher.cpp +++ b/src/ros/rt_publisher.cpp @@ -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 diff --git a/src/ros/service_stopper.cpp b/src/ros/service_stopper.cpp index af16fbe..bf6d750 100644 --- a/src/ros/service_stopper.cpp +++ b/src/ros/service_stopper.cpp @@ -18,6 +18,8 @@ #include "ur_rtde_driver/ros/service_stopper.h" +namespace ur_rtde_driver +{ ServiceStopper::ServiceStopper(std::vector 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 diff --git a/src/ros/trajectory_follower.cpp b/src/ros/trajectory_follower.cpp index b01a65a..1defb2c 100644 --- a/src/ros/trajectory_follower.cpp +++ b/src/ros/trajectory_follower.cpp @@ -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 diff --git a/src/ros/urscript_handler.cpp b/src/ros/urscript_handler.cpp index a49b248..20aa0cf 100644 --- a/src/ros/urscript_handler.cpp +++ b/src/ros/urscript_handler.cpp @@ -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 diff --git a/src/ros_main.cpp b/src/ros_main.cpp index 761d98a..afde87d 100644 --- a/src/ros_main.cpp +++ b/src/ros_main.cpp @@ -61,6 +61,8 @@ static const std::vector 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: diff --git a/src/tcp_socket.cpp b/src/tcp_socket.cpp index d817ec2..a8b20a2 100644 --- a/src/tcp_socket.cpp +++ b/src/tcp_socket.cpp @@ -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 diff --git a/src/ur/commander.cpp b/src/ur/commander.cpp index f5f1c38..450b4a3 100644 --- a/src/ur/commander.cpp +++ b/src/ur/commander.cpp @@ -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& speeds, double acceleration std::string s(out.str()); return write(s); } +} // namespace ur_rtde_driver diff --git a/src/ur/master_board.cpp b/src/ur/master_board.cpp index e67e54b..59918d3 100644 --- a/src/ur/master_board.cpp +++ b/src/ur/master_board.cpp @@ -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); -} \ No newline at end of file +} +} // namespace ur_rtde_driver diff --git a/src/ur/messages.cpp b/src/ur/messages.cpp index 2944690..9ef8837 100644 --- a/src/ur/messages.cpp +++ b/src/ur/messages.cpp @@ -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); -} \ No newline at end of file +} +} // namespace ur_rtde_driver diff --git a/src/ur/robot_mode.cpp b/src/ur/robot_mode.cpp index 758f57a..4771c50 100644 --- a/src/ur/robot_mode.cpp +++ b/src/ur/robot_mode.cpp @@ -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 diff --git a/src/ur/rt_state.cpp b/src/ur/rt_state.cpp index 6a78951..ef545bc 100644 --- a/src/ur/rt_state.cpp +++ b/src/ur/rt_state.cpp @@ -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); -} \ No newline at end of file +} +} // namespace ur_rtde_driver diff --git a/src/ur/server.cpp b/src/ur/server.cpp index 1eac797..b8e5c20 100644 --- a/src/ur/server.cpp +++ b/src/ur/server.cpp @@ -25,6 +25,8 @@ #include #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 diff --git a/src/ur/stream.cpp b/src/ur/stream.cpp index 8c4e989..74c1759 100644 --- a/src/ur/stream.cpp +++ b/src/ur/stream.cpp @@ -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 lock(write_mutex_); @@ -59,4 +61,5 @@ bool URStream::read(uint8_t* buf, size_t buf_len, size_t& total) } return remainder == 0; -} \ No newline at end of file +} +} // namespace ur_rtde_driver diff --git a/tests/ur/master_board.cpp b/tests/ur/master_board.cpp index 3c437ea..2b024ee 100644 --- a/tests/ur/master_board.cpp +++ b/tests/ur/master_board.cpp @@ -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); diff --git a/tests/ur/robot_mode.cpp b/tests/ur/robot_mode.cpp index 78f4718..abb01bb 100644 --- a/tests/ur/robot_mode.cpp +++ b/tests/ur/robot_mode.cpp @@ -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); diff --git a/tests/ur/rt_state.cpp b/tests/ur/rt_state.cpp index 8d01833..45ac796 100644 --- a/tests/ur/rt_state.cpp +++ b/tests/ur/rt_state.cpp @@ -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); @@ -205,4 +207,4 @@ TEST(RTState_V3_2__3, testTooSmallBuffer) BinParser bp = rdt.getParser(true); RTState_V3_2__3 state; EXPECT_FALSE(state.parseWith(bp)) << "parse() should fail when buffer not big enough"; -} \ No newline at end of file +}