From e250128d7e8691f7f158bb130dd9fb9287c2310b Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Thu, 6 Jun 2019 10:45:05 +0200 Subject: [PATCH] fix naming conventions --- .../include/ur_rtde_driver/comm/script_sender.h | 4 ++-- .../ur_rtde_driver/primary/primary_parser.h | 8 ++++---- .../include/ur_rtde_driver/rtde/data_package.h | 2 +- .../include/ur_rtde_driver/rtde/rtde_parser.h | 4 ++-- .../src/ros/hardware_interface_node.cpp | 16 ++++++++-------- ur_rtde_driver/src/rtde/data_package.cpp | 6 +++--- ur_rtde_driver/src/ur/ur_driver.cpp | 4 ++-- 7 files changed, 22 insertions(+), 22 deletions(-) diff --git a/ur_rtde_driver/include/ur_rtde_driver/comm/script_sender.h b/ur_rtde_driver/include/ur_rtde_driver/comm/script_sender.h index 297c9b1..f4f9dd7 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/comm/script_sender.h +++ b/ur_rtde_driver/include/ur_rtde_driver/comm/script_sender.h @@ -58,7 +58,7 @@ private: std::thread script_thread_; std::string program_; - const std::string PROGRAM_REQUEST = std::string("request_program\n"); + const std::string PROGRAM_REQUEST_ = std::string("request_program\n"); void runScriptSender() { @@ -86,7 +86,7 @@ private: if (read_successful) { - if (std::string(buffer) == PROGRAM_REQUEST) + if (std::string(buffer) == PROGRAM_REQUEST_) { return true; } diff --git a/ur_rtde_driver/include/ur_rtde_driver/primary/primary_parser.h b/ur_rtde_driver/include/ur_rtde_driver/primary/primary_parser.h index 6805643..4d9ed99 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/primary/primary_parser.h +++ b/ur_rtde_driver/include/ur_rtde_driver/primary/primary_parser.h @@ -70,7 +70,7 @@ public: RobotStateType type; sbp.parse(type); - std::unique_ptr packet(state_from_type(type)); + std::unique_ptr packet(stateFromType(type)); if (packet == nullptr) { @@ -109,7 +109,7 @@ public: bp.parse(source); bp.parse(message_type); - std::unique_ptr packet(message_from_type(message_type, timestamp, source)); + std::unique_ptr packet(messageFromType(message_type, timestamp, source)); if (!packet->parseWith(bp)) { LOG_ERROR("Package parsing of type %d failed!", static_cast(message_type)); @@ -132,7 +132,7 @@ public: } private: - RobotState* state_from_type(RobotStateType type) + RobotState* stateFromType(RobotStateType type) { switch (type) { @@ -149,7 +149,7 @@ private: } } - RobotMessage* message_from_type(RobotMessagePackageType type, uint64_t timestamp, uint8_t source) + RobotMessage* messageFromType(RobotMessagePackageType type, uint64_t timestamp, uint8_t source) { switch (type) { diff --git a/ur_rtde_driver/include/ur_rtde_driver/rtde/data_package.h b/ur_rtde_driver/include/ur_rtde_driver/rtde/data_package.h index 2906a2b..2a7cab8 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/rtde/data_package.h +++ b/ur_rtde_driver/include/ur_rtde_driver/rtde/data_package.h @@ -109,7 +109,7 @@ public: private: // Const would be better here - static std::unordered_map type_list_; + static std::unordered_map g_type_list; uint8_t recipe_id_; std::unordered_map data_; std::vector recipe_; diff --git a/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_parser.h b/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_parser.h index 4241e2d..40cdfb8 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_parser.h +++ b/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_parser.h @@ -75,7 +75,7 @@ public: } default: { - std::unique_ptr package(package_from_type(type)); + std::unique_ptr package(packageFromType(type)); if (!package->parseWith(bp)) { LOG_ERROR("Package parsing of type %d failed!", static_cast(type)); @@ -98,7 +98,7 @@ public: private: std::vector recipe_; - RTDEPackage* package_from_type(PackageType type) + RTDEPackage* packageFromType(PackageType type) { switch (type) { diff --git a/ur_rtde_driver/src/ros/hardware_interface_node.cpp b/ur_rtde_driver/src/ros/hardware_interface_node.cpp index 24a9298..c9a6821 100644 --- a/ur_rtde_driver/src/ros/hardware_interface_node.cpp +++ b/ur_rtde_driver/src/ros/hardware_interface_node.cpp @@ -30,13 +30,13 @@ #include #include -std::unique_ptr hw_interface; +std::unique_ptr g_hw_interface; void signalHandler(int signum) { std::cout << "Interrupt signal (" << signum << ") received.\n"; - hw_interface.reset(); + g_hw_interface.reset(); // cleanup and close up stuff here // terminate program @@ -62,15 +62,15 @@ int main(int argc, char** argv) auto stopwatch_last = std::chrono::steady_clock::now(); auto stopwatch_now = stopwatch_last; - hw_interface.reset(new ur_driver::HardwareInterface); + g_hw_interface.reset(new ur_driver::HardwareInterface); - if (!hw_interface->init(nh, nh_priv)) + if (!g_hw_interface->init(nh, nh_priv)) { ROS_ERROR_STREAM("Could not correctly initialize robot. Exiting"); exit(1); } ROS_INFO_STREAM("initialized hw interface"); - controller_manager::ControllerManager cm(hw_interface.get(), nh); + controller_manager::ControllerManager cm(g_hw_interface.get(), nh); ROS_INFO_STREAM("started controller manager"); // Get current time and elapsed time since last read @@ -128,13 +128,13 @@ int main(int argc, char** argv) } } - double expected_cycle_time = 1.0 / (static_cast(hw_interface->getControlFrequency())); + double expected_cycle_time = 1.0 / (static_cast(g_hw_interface->getControlFrequency())); // Run as fast as possible while (ros::ok()) { // Receive current state from robot - hw_interface->read(timestamp, period); + g_hw_interface->read(timestamp, period); // Get current time and elapsed time since last read timestamp = ros::Time::now(); @@ -144,7 +144,7 @@ int main(int argc, char** argv) cm.update(timestamp, period); - hw_interface->write(timestamp, period); + g_hw_interface->write(timestamp, period); // if (!control_rate.sleep()) if (period.toSec() > expected_cycle_time) { diff --git a/ur_rtde_driver/src/rtde/data_package.cpp b/ur_rtde_driver/src/rtde/data_package.cpp index a6ce07e..e72f90f 100644 --- a/ur_rtde_driver/src/rtde/data_package.cpp +++ b/ur_rtde_driver/src/rtde/data_package.cpp @@ -30,7 +30,7 @@ namespace ur_driver { namespace rtde_interface { -std::unordered_map DataPackage::type_list_{ +std::unordered_map DataPackage::g_type_list{ { "timestamp", double() }, { "target_q", vector6d_t() }, { "target_qd", vector6d_t() }, @@ -193,9 +193,9 @@ bool rtde_interface::DataPackage ::parseWith(comm::BinParser& bp) bp.parse(recipe_id_); for (auto& item : recipe_) { - if (type_list_.find(item) != type_list_.end()) + if (g_type_list.find(item) != g_type_list.end()) { - _rtde_type_variant entry = type_list_[item]; + _rtde_type_variant entry = g_type_list[item]; auto bound_visitor = std::bind(ParseVisitor(), std::placeholders::_1, bp); boost::apply_visitor(bound_visitor, entry); data_[item] = entry; diff --git a/ur_rtde_driver/src/ur/ur_driver.cpp b/ur_rtde_driver/src/ur/ur_driver.cpp index 306237d..bf75a61 100644 --- a/ur_rtde_driver/src/ur/ur_driver.cpp +++ b/ur_rtde_driver/src/ur/ur_driver.cpp @@ -36,7 +36,7 @@ namespace ur_driver { -static const int32_t MULT_JOINTSTATE_ = 1000000; +static const int32_t MULT_JOINTSTATE = 1000000; static const std::string JOINT_STATE_REPLACE("{{JOINT_STATE_REPLACE}}"); static const std::string SERVO_J_REPLACE("{{SERVO_J_REPLACE}}"); static const std::string SERVER_IP_REPLACE("{{SERVER_IP_REPLACE}}"); @@ -67,7 +67,7 @@ ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& sc uint32_t script_sender_port = 50002; // TODO: Make this a parameter std::string prog = readScriptFile(script_file); - prog.replace(prog.find(JOINT_STATE_REPLACE), JOINT_STATE_REPLACE.length(), std::to_string(MULT_JOINTSTATE_)); + prog.replace(prog.find(JOINT_STATE_REPLACE), JOINT_STATE_REPLACE.length(), std::to_string(MULT_JOINTSTATE)); std::ostringstream out; out << "lookahead_time=" << servoj_lookahead_time_ << ", gain=" << servoj_gain_; prog.replace(prog.find(SERVO_J_REPLACE), SERVO_J_REPLACE.length(), out.str());