ABB Plan with external (revolute) axis
Hi everyone,
Some background: I am quite fresh with ROS. The setup i am using includes ROS (kinetic), an ABB arm, ROS-I along with the abb_driver. Moveit for the motion planning, kinematics etc. Setup with just the arm is working as it is supposed to. The goal now is to control an external axis which is rotating.
As stated in the abb_driver wiki the driver supports up to 4 integrated external linear axis. But in this case the external axis is set in front of the robot on top of a fixed base.
As far as the message part goes, with a quick inspection I saw that a conversion from mm to m and vice-versa is happening at the RAPID side. From ROS side the information for the external axis seems to be incorporated into the joint_message
- joint_data
system. For the RAPID side, is it as simple as using conversion from degree2rad
instead of mm2m
in order to support a revolute joint?
Main question: If the message structure for the supported linear axis is possible to be used with a revolute joint, what is the correct way to add the external axis assembly in the URDF and Moveit?
Current idea:
- Add a world frame in the urdf.
- Add both the arm's and positioner's first links as children of the world frame (This will create a branch in the kinematic chain.).
- Place positioner_base in front of the robot with a fixed joint and attach the second link to the positioner_base with a revolute joint.
- Define a new positioner planning group.
- Define a new controller for that group.
I have tried this approach for now and set it up with MSA but as soon as I add the new joint in the joint_names.yaml
and execute the plan i get the error:
[ERROR] [1550352562.186055092]: Joint trajectory action failing on invalid joints
Moreover, IK solver does not like it if I create a planning_group that includes both "manipulator" and "positioner" as subgroups therefore i cannot incorporate them under the same planning_group. Currently i am using the TracIK kinematics plugin and it supports only chains.
If I create the second controller and name both of them accordingly: "manipulator", "positioner". I get the following error:
[ WARN] [1550403869.172061404]: Waiting for manipulator/joint_trajectory_action to come up
[ERROR] [1550403875.172279892]: Action client not connected: manipulator/joint_trajectory_action
Searching other posts for solutions i added two groups (inside robot_interface.launch
) in order to define two namespaces (i think at least) to start their own instance of joint_trajectory_action
but i still get the error.
Last, if I remove joint_7
(external axis) from the controller_joint_names
I can normally plan for the arm but I also get this:
[ WARN] [1550419157.365318143]: The complete state of the robot is not yet known. Missing joint_7
I am confused at this point since adding a second group which is also trying to connect to the same IP does not seem right (since the external axis is integrated in the abb controller). But how else will i be able to get Moveit side to work and include the external axis in the path planning?
p.s: I do not need to control a simultaneous movement of the arm+positioner or use the external axis to minimize movement of the arm. For now I need to only establish a way to control its angle. Similar to a dual arm concept but both joint states (arm+positioner) are received from the same port.
Edit 1:
An update. I made it work for use with the industrial_robot_simulator
. What i did is the following:
- Added the extra joint in the
controller_joint_names
parameter in thejoint_names.yaml
. - Created two controllers as explain above: "manipulator" and "positioner" in the
controllers.yaml
. - I added the
industrial_robot_simulator
package to my workspace and edited the .launch file to duplicate its functionality into two groups that each of them creates the appropriate namespace (manipulator/positioner). - Edited the
moveit_planning_execution
launch file to point to the edited simulator.
At this point i could not execute a plan since both instances of the simulator where looking at the /joint_states
topic for the state, therefore i added the following in the beginning of moveit_planning_execution.launch
to force the states to the appropriate topic (not sure that is the proper way to do it tho):
<remap from="/manipulator/joint_states" to="/joint_states" />
<remap from="/positioner/joint_states" to="/joint_states" />
I will provide another update with the changes to make it work with RobotStudio, but the idea should be the same i guess..
Edit 2:
Ok, I am having a problem with the concept idea when i am trying to connect it to RobotStudio. Here are two routes that i can think of:
Robot and Positioner in the same task (TROB1) and return the full state of the robot+positioner from the `ROSstateServer
and accept motion command with
ROS_motionServer`.Two different tasks in RAPID (TROB1 & TPOS1). Having a second task I need to create the appropriate motion and server files in RAPID. Assign 2 new ports and have Moveit connect to those from each group (namespace).
Following No1: I had to define a new controller " " with all 7 joints included which uses the '/jointtrajectoryaction', since i have only 1 connection. But i get this:
[ERROR] [1550747865.040852330]: Joint trajectory action rejected: waiting for (initial) feedback from controller
[ WARN] [1550747865.041136508]: Controller manipulator failed with error code INVALID_GOAL
[ WARN] [1550747865.041343308]: Controller handle manipulator reports status FAILED
I was initially worried about the /jointstates topic since it publishes all 7 joints together. Not sure if this was my problem i made a "splitter" node thats subscribes to the `/jointstatesand republishes 2 sets, one with the arm joints and one with the positioner joint. But that was not it.. It has to do something with the
/jointtrajectoryaction` that expects 7 joints and the "manipulator" controller when I plan-execute in moveit calculates 6 joints instead?
Following No2.: This way Moveit works fine, recieves the corrects joints, plans and executes for the arm. The problem arises with the positioner. Sending back a joint_data
message requires values in the 6 axis of the robot at least, this is the bytelength that ROS waits, and if I set up only 1 axis the message unload fails with: "Buffer is smaller than requested byteSize."
. If i include "dummy" joints the whole state node crashes.
I am not sure what is the "correct" way to build this, any ideas?
Asked by skop44 on 2019-02-17 11:52:18 UTC
Answers
Maybe I missed something somewhere but I could not find a straightforward solution to fit my needs.
The problem boiled down to the following:
In this case the relation between the ABB and ROS controllers-planning_groups is 1 to 2. There is one connection to the ABB driver (motion/state server). In Moveit I have two groups, in two namespaces, namely manipulator and positioner. Since I could use only one instance of the motion_download_interface
I could control only one out of the two groups.
This is is definitely a workaround and NOT a solution, but I made it work like this..:
- I created a third planning group named "both".
- Added a third controller named "both" which includes all the 7 joints (arm:6 + positioner:1)
robot_state
andmotion_download_interface
nodes are included in the "both" group under the same namespace.- All 3 namespaces (groups) include a
joint_trajectory_action
. - Created the following nodes:
joint_state_splitter
: responsible to split the 7 joints list that returns from the ABB controller (to the/both
namespace) into 6 and 1 and publish these lists to the respected/joint_states
topicsfeedback_state_splitter
: does the same as the above splitter for the feedback state positions.trajectory_merger
: when an individual plan is made (either for the manipulator or the positioner) this node listens to it, and is also subscribed to the state of the second group from where it takes the static position. It always creates a trajectory which includes 7 joints with 7 positions for each point and submits the edited trajectory to the/both/joint_trajectory_action
.
- In order for this to work, the trajectory_merger is doing some manipulation of the
controller_list
paremeter. Each time a plan is requested, the node sets the appropriate joint names to "both" controller and when the publish is complete it resets the parameter to the original value.
Since I consider all the above a quite dirty manipulation. I would like at least to suggest what in my mind sounds like a clean-solution:
- If multimove is an available option then a very clean 1-1 structure can be made for each group. This sums to two motion tasks in the RAPID side and the positioner is considered as separate unit (not integrated but 1-1 relation with ROS).
- If I could use an IK solver that could work with "tree" chain, meaning, one fixed joint and one branch for the arm plus one branch for the positioner, then probably moveit can plan for one group that includes both. Like that, there is again 1-1 to relation between ABB and ROS controllers. Probably a setup like this can plan for a simultaneous movement aswell?
Nonetheless, this is for now. In case there is suggested way to make this concept work, I am interested to hear it!
Asked by skop44 on 2019-02-25 13:11:47 UTC
Comments
This is all possible, and should not be that difficult to setup.
If you haven't figured it out or someone hasn't responded earlier, I'll post something tomorrow.
Asked by gvdhoorn on 2019-02-17 12:11:11 UTC
Nice these are good news, and thanks for the fast response. If I figure it out in the meantime I will update the post.
Asked by skop44 on 2019-02-17 12:18:03 UTC
An update on "Edit 2": Route No.2 is no longer an option since I do not have multimove option on the real IRC5 controller.
Asked by skop44 on 2019-02-21 09:19:59 UTC