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:
committed by
Simon Rasmussen
parent
ef7aca7fb9
commit
e4a503fe5f
@@ -28,6 +28,7 @@ static const std::string MAX_VEL_CHANGE_ARG("~max_vel_change");
|
||||
static const std::string PREFIX_ARG("~prefix");
|
||||
static const std::string BASE_FRAME_ARG("~base_frame");
|
||||
static const std::string TOOL_FRAME_ARG("~tool_frame");
|
||||
static const std::string TCP_LINK_ARG("~tcp_link");
|
||||
static const std::string JOINT_NAMES_PARAM("hardware_interface/joints");
|
||||
|
||||
static const std::vector<std::string> DEFAULT_JOINTS = { "shoulder_pan_joint", "shoulder_lift_joint", "elbow_joint",
|
||||
@@ -43,6 +44,7 @@ public:
|
||||
std::string prefix;
|
||||
std::string base_frame;
|
||||
std::string tool_frame;
|
||||
std::string tcp_link;
|
||||
std::vector<std::string> joint_names;
|
||||
double max_acceleration;
|
||||
double max_velocity;
|
||||
@@ -65,6 +67,7 @@ bool parse_args(ProgArgs &args)
|
||||
ros::param::param(PREFIX_ARG, args.prefix, std::string());
|
||||
ros::param::param(BASE_FRAME_ARG, args.base_frame, args.prefix + "base_link");
|
||||
ros::param::param(TOOL_FRAME_ARG, args.tool_frame, args.prefix + "tool0_controller");
|
||||
ros::param::param(TCP_LINK_ARG, args.tcp_link, args.prefix + "ee_link");
|
||||
ros::param::param(JOINT_NAMES_PARAM, args.joint_names, DEFAULT_JOINTS);
|
||||
return true;
|
||||
}
|
||||
@@ -109,7 +112,7 @@ int main(int argc, char **argv)
|
||||
if (args.use_ros_control)
|
||||
{
|
||||
LOG_INFO("ROS control enabled");
|
||||
controller = new ROSController(*rt_commander, traj_follower, args.joint_names, args.max_vel_change);
|
||||
controller = new ROSController(*rt_commander, traj_follower, args.joint_names, args.max_vel_change, args.tcp_link);
|
||||
rt_vec.push_back(controller);
|
||||
services.push_back(controller);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user