Extending robot arm by rotation stage
Hello, I want to inspect an object on a rotation stage with a 6-DOF robot arm from staubli (TX90 series). Since 6-DOF robots are sometimes limited in their reachable space while inspecting objects with endeffector mounted cameras, I want to extend my system with this a rotary stage. The setup should then look something like this:
But instead of using the stage as a separate robot with a seperate movegroup, I want to integrate the stage into the serial chain of my industrial robot, so that the 6-DOF robot results in a 7-DOF robot. The tf_tree should then look something like this:
So the rotation_link is the new reference frame (or world coordinate system) of my system. My motivation is, that I am able to let MoveIt do the path planning for my entire 7-DOF-system then. I have already written a hardware_interface for my controller including a joint_state publisher and a position controller (the FollowJointTrajectoryAction client was not implemented yet).
Since the Staubli-Driver does not contain any hardware interfaces, that I am able to use with ros_control, I do not know how to combine those two hardware-systems. The staubli robot communication seems pretty isolated to me since it is just communicating with the simple_message protocol after opening a couple of generic nodes (described here).
So to summarize what I am asking:
How can I implement a joint_trajectory_action for those two existing systems?
Before rewriting the whole ros_industrial_client package, I would really like to hear some advices, if there is a convinient way of realizing my plans.
Thanks a lot for your help.
Nils
An observation: regardless of whether or not the robot driver has
ros_control
capabilities: achieving synchronised motion between the CS8 controller and the stage is going to be difficult. The stage is a relatively simple device controlled over USB with an unknown delay and no real-time .... (ie: determinism) guarantees afaict.
Coordinated motion between robots and external axes are at the moment still easier to achieve by integrating the additional axes into the robot's motion control system and then controlling that externally.
Afaik CS8 controllers don't support that though.
I actually do not need realtime capabilities. I do not even need synchronised motion between those two systems. The base minimum of what I am expecting is to consider the rotary stage in the path planning of moveit. If that results in a simple final position for the stage, it would be fine.
Do you have any idea how to implement a work around? Has there been nobody before with a similar idea?
re: CS8 support for external axes: you'd have to ask Staubli. It's been a while since I've worked with CS8 controllers, so perhaps the situation has improved, but last time I checked integrating external axes directly into the CS8 controller was not supported (natively at least).
If you don't need synchronised motion then just treat the stage as a "second robot" and express the kinematic relationship in your URDF using an appropriate joint.
MoveIt will take care of the rest. For execution of planned motions, just make sure the driver for the stage accepts ..
.. the regular goals MoveIt uses (ie:
FollowJointTrajectory
). But if you have ahardware_interface
for it then that should be solved already (just use thejoint_trajectory_controller
).I don't quite understand. How can i do my motion planning with respect to the "rotation frame" if the stage if ...