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

get frequency from robot

This commit is contained in:
Felix Mauch
2019-05-07 14:30:45 +02:00
parent f38ec92389
commit 4106aa9fb8
10 changed files with 49 additions and 31 deletions

View File

@@ -30,10 +30,10 @@
namespace ur_driver
{
HardwareInterface::HardwareInterface()
: joint_position_command_{ 0, 0, 0, 0, 0, 0 }
, joint_positions_{ 0, 0, 0, 0, 0, 0 }
, joint_velocities_{ 0, 0, 0, 0, 0, 0 }
, joint_efforts_{ 0, 0, 0, 0, 0, 0 }
: joint_position_command_({ 0, 0, 0, 0, 0, 0 })
, joint_positions_{ { 0, 0, 0, 0, 0, 0 } }
, joint_velocities_{ { 0, 0, 0, 0, 0, 0 } }
, joint_efforts_{ { 0, 0, 0, 0, 0, 0 } }
, joint_names_(6)
, position_controller_running_(false)
@@ -42,8 +42,8 @@ HardwareInterface::HardwareInterface()
bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh)
{
joint_velocities_ = { 0, 0, 0, 0, 0, 0 };
joint_efforts_ = { 0, 0, 0, 0, 0, 0 };
joint_velocities_ = { { 0, 0, 0, 0, 0, 0 } };
joint_efforts_ = { { 0, 0, 0, 0, 0, 0 } };
std::string ROBOT_IP = robot_hw_nh.param<std::string>("robot_ip", "192.168.56.101");
ROS_INFO_STREAM("Initializing urdriver");

View File

@@ -48,7 +48,9 @@ int main(int argc, char** argv)
auto stopwatch_now = stopwatch_last;
hw_interface.init(nh, nh_priv);
ROS_INFO_STREAM("initialized hw interface");
controller_manager::ControllerManager cm(&hw_interface, nh);
ROS_INFO_STREAM("started controller manager");
// Get current time and elapsed time since last read
timestamp = ros::Time::now();
@@ -76,7 +78,8 @@ int main(int argc, char** argv)
if (!control_rate.sleep())
{
ROS_WARN_STREAM("Could not keep cycle rate of " << control_rate.expectedCycleTime().toNSec() / 1000000.0 << "ms");
// ROS_WARN_STREAM("Could not keep cycle rate of " << control_rate.expectedCycleTime().toNSec() / 1000000.0 <<
// "ms");
}
}