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

various improvements and fixes for use_ros_control=true (#6)

* Find matching hardware_interface using the required type

The name of the controller was used in order to find and start
the matching hardware interface.
In consequence this meant that one could only define one controller
for each hardware interface.

Now, the controller's required type of hardware interface is used
to find and start the matching hardware interface.

* separate read & update in controller

consume is defined as read+update, but update
does not include read in ros_control terminology.

* Handle latency in pipeline loop

The controllers need to update at a rate of *at least* 125Hz,
but the wait_dequeue_timed call could in theory slow the loop down to 62.5Hz.
The old ur_modern_driver worked around this problem by sending goals
at 4*125Hz.

This patch exploits the onTimeout method of a consumer to update with
the specified frequency of the control loop, even if no new state message
arrived after the previous command.

* publish wrench w.r.t. tcp frame

The messages had an empty frame_id before and could not be displayed in RViz

* support ros_control in indigo
This commit is contained in:
Michael Görner
2017-12-08 14:05:07 +01:00
committed by Simon Rasmussen
parent ef7aca7fb9
commit e4a503fe5f
7 changed files with 58 additions and 40 deletions

View File

@@ -1,7 +1,7 @@
#include "ur_modern_driver/ros/hardware_interface.h"
#include "ur_modern_driver/log.h"
const std::string JointInterface::INTERFACE_NAME = "joint_state_controller";
const std::string JointInterface::INTERFACE_NAME = "hardware_interface::JointStateInterface";
JointInterface::JointInterface(std::vector<std::string> &joint_names)
{
for (size_t i = 0; i < 6; i++)
@@ -18,10 +18,10 @@ void JointInterface::update(RTShared &packet)
}
const std::string WrenchInterface::INTERFACE_NAME = "force_torque_sensor_controller";
WrenchInterface::WrenchInterface()
const std::string WrenchInterface::INTERFACE_NAME = "hardware_interface::ForceTorqueSensorInterface";
WrenchInterface::WrenchInterface(std::string tcp_link)
{
registerHandle(hardware_interface::ForceTorqueSensorHandle("wrench", "", tcp_.begin(), tcp_.begin() + 3));
registerHandle(hardware_interface::ForceTorqueSensorHandle("wrench", tcp_link, tcp_.begin(), tcp_.begin() + 3));
}
void WrenchInterface::update(RTShared &packet)
@@ -30,7 +30,7 @@ void WrenchInterface::update(RTShared &packet)
}
const std::string VelocityInterface::INTERFACE_NAME = "vel_based_pos_traj_controller";
const std::string VelocityInterface::INTERFACE_NAME = "hardware_interface::VelocityJointInterface";
VelocityInterface::VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface,
std::vector<std::string> &joint_names, double max_vel_change)
: commander_(commander), max_vel_change_(max_vel_change)
@@ -62,7 +62,7 @@ void VelocityInterface::reset()
}
}
const std::string PositionInterface::INTERFACE_NAME = "pos_based_pos_traj_controller";
const std::string PositionInterface::INTERFACE_NAME = "hardware_interface::PositionJointInterface";
PositionInterface::PositionInterface(TrajectoryFollower &follower,
hardware_interface::JointStateInterface &js_interface,
std::vector<std::string> &joint_names)
@@ -87,4 +87,4 @@ void PositionInterface::start()
void PositionInterface::stop()
{
follower_.stop();
}
}