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

fix naming conventions

This commit is contained in:
Felix Mauch
2019-06-06 10:45:05 +02:00
committed by Tristan Schnell
parent 9788504f93
commit e250128d7e
7 changed files with 22 additions and 22 deletions

View File

@@ -30,13 +30,13 @@
#include <csignal>
#include <ur_rtde_driver/ros/hardware_interface.h>
std::unique_ptr<ur_driver::HardwareInterface> hw_interface;
std::unique_ptr<ur_driver::HardwareInterface> 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<double>(hw_interface->getControlFrequency()));
double expected_cycle_time = 1.0 / (static_cast<double>(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)
{