Skip to content
This repository has been archived by the owner on Jan 16, 2019. It is now read-only.

various improvements and fixes for use_ros_control=true #6

Merged
merged 6 commits into from
Dec 8, 2017

Conversation

v4hn
Copy link

@v4hn v4hn commented Dec 7, 2017

We spent a bit of work these days trying to get the ros_control version of this package to run nicely.

The attached patches make our UR5 work with the ros_control version.
We can switch controllers, use position_controllers/JointTrajectoryController, velocity_controllers/JointTrajectoryController (although the latter is not nicely parameterized ootb), but also position_controllers/JointGroupPositionController and - in theory, but as of yet untested velocity_controllers/JointGroupVelocityController.

With a low nice value and a low-latency kernel, the driver operates the arm without stumbling using either JointTrajectoryController.

2scholz and others added 5 commits December 5, 2017 16:30
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.
consume is defined as read+update, but update
does not include read in ros_control terminology.
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.
The messages had an empty frame_id before and could not be displayed in RViz
if (ci.claimed_resources.empty())
continue;

auto ait = available_interfaces_.find(ci.claimed_resources[0].hardware_interface);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This doesn't work on Indigo which was a requirement when I wrote the code, I don't know if it's reasonable to drop Indigo now?
It's not really my decision to make either as ROS Industrial is supposed to adopt the code eventually if my branch is every merged into the mainline.

Copy link
Author

@v4hn v4hn Dec 8, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In my understanding this branch was meant to replace ur_modern_driver (and hopefully ur_driver) in kinetic+, so I did not consider indigo compatibility.

Anyway, ros_control only generalized their code from single hardware interface to lists of hardware interfaces. I just added a preprocessor workaround to handle both cases. We use the same workaround in moveit.

@@ -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");
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you provide some context for what "ee_link" is?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The standard end effector link of the UR in ROS-I's urdfs

last_warn = now;
consumer_.onTimeout();
}
consumer_.onTimeout();
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The existing code here is a mess and it's no wonder you've removed it :-)
Since onTimeout isn't used at all and it's sort of being abused as a heartbeat function in your code I'm wondering if it wouldn't make better sense to just always call consume after 8ms but in the case of failure, product will be set to T::InvalidProduct which then would have to be typedef'ed for RTPacket, StatePacket and MessagePacket together with extending the the consumers to accept the new packet types.
At least that's something I might end up doing after merging if we can reach a conclusion for the Indigo problem.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Both ways sound ok to me.
You are right that my proposal uses onTimeout as a heartbeat, but consuming a non-existing package as an invalid package is just as weird in my opinion.

It's simply a matter of where you want to place the guarantee on the lower-bound of the call-rate.

The important point here is that the current pipeline behavior breaks the minimum update rate and results in jerking trajectory execution

@Zagitta Zagitta merged commit e4a503f into Zagitta:master Dec 8, 2017
@v4hn
Copy link
Author

v4hn commented Dec 8, 2017

Thanks a lot!

@Zagitta
Copy link
Owner

Zagitta commented Dec 8, 2017

Thanks for you contribution and communication.
Since I agree with you that both ways of handling the lower bound on call rates are weird I decided to merge as is and think about a better solution :-)

Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants