ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to interface abb_robot_driver with a high level velocity controller

asked 2021-12-17 03:55:55 -0500

bhomaidan gravatar image

Hi,

As stated in the title, I want to interface a high-level velocity controller with abb robot using abb_robot_driver, YuMi for example.

My problem here is that:

I don't know how to get a state_handle_ from abb_egm_hardware_interface to read the position/velocity from the robot directly, as I'm not sure that EGMStateHandle provides such possibility.

Can you please advise me on how can I get a state_handle_ to read the robot state (position/velocity)? thanks in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-12-17 04:38:08 -0500

gvdhoorn gravatar image

updated 2021-12-17 05:40:37 -0500

I took a quick look at the repository you linked.

The problem (or perhaps challenge) is that the controller implemented there is largely Panda-specific.

It uses very specific parts of the Franka Emika's hardware_interface of franka_ros (here for instance).

Those are not available in abb_robot_driver (which makes sense to me, Franka Emika != ABB).

It's not impossible to get things to work, but for now I would say the problem is not on the abb_robot_driver side, but on the side of the controller you want to use.

I don't know how to get a state_handle_ from abb_egm_hardware_interface to read the position/velocity from the robot directly, as I'm not sure that EGMStateHandle provides such possibility.

Please note: unless you want to make the same "mistake" as the authors of the repository you linked (ie: create controllers which can only be used with one specific hardware_interface implementation), you should not interface with EGMStateHandle directly.

The driver exposes generic position and velocity state interfaces as well as command interfaces, and I believe it would be beneficial to use those, as it would avoid vendor lock-in. Those generic interfaces are exactly the point of ros_control: to allow abstracted access to state and command interfaces in a way that allows control components to be written in a reusable way.

(there can of course be situations where using OEM-specific interfaces are required or beneficial. I just wanted to point out that it should not be your main approach, and only done after careful consideration of the drawbacks)

The controller you link also uses those generic interfaces, in addition to the Panda-specific ones (the hardware_interface::VelocityJointInterface and hardware_interface::EffortJointInterface). So the generic parts should be usable with abb_robot_driver. The Panda-specific parts would not be (and note that abb_robot_driver does not support effort control, so hardware_interface::EffortJointInterface cannot be used).


Edit: there is a chance the coupling between the controller and the Panda's hardware_interface is actually not that strong. I would recommend to get in touch with the developer/author, as there are indications (s)he made provisions for creating compatibility layers for other robot brands.


Edit 2: to give an actual answer to your question:

Can you please advise me on how can I get a state_handle_ to read the robot state (position/velocity)? thanks in advance.

as I wrote in my comment below: the main idea behind ros_control is for almost everything being generic (so no OEM-specific anything), except for the RobotHW implementation. That class is responsible for transforming OEM-specific representations of domain concepts (ie: positions, velocities, efforts, digital-io, etc) to-and-from their generic representations.

Those generic representations are then "exposed" to the controllers. But the controllers never talk directly to the hw, and should never use OEM-specific representations directly (well .. 'never' is perhaps too strong, but it should be minimised as much as possible).

As to how to retrieve a handle to the velocity interface of a particular joint (as an example): the repository you link already shows you (from here ... (more)

edit flag offensive delete link more

Comments

@gvdhoorn "The driver exposes generic position and velocity state interfaces as well as command interfaces", my problem is that I'm not sure how can I use these interfaces to get the pos/vel and command them, should I use them directly from the hardware_interface::VelocityJointInterface? or should I get them from the abb_egm_hardware_interface??, this information is all that I need to tweak the controller to work with YuMi, if you can provide a small example on how to do that it will be highly appreciated, thanks in advance.

bhomaidan gravatar image bhomaidan  ( 2021-12-17 05:19:47 -0500 )edit
1

I don't have any example I can immediately share with you.

The controller you link already does this (here). It would be exactly the same with abb_robot_driver. You can look up any controller from ros_control or any custom implementation which retrieves position/velocity/effort interfaces from a hardware_interface. It would all be the same (bar error detection and handling code).

The thing to realise is that controllers don't talk directly to anything OEM-specific (in the normal case). It's all intended to be through generic interfaces, and the hardware_interface implementation then is responsible for transforming to-and-from OEM-specific representations.

It's very unfortunate people start using these OEM-specific interfaces, as that's how we end up in situations like yours.

gvdhoorn gravatar image gvdhoorn  ( 2021-12-17 05:24:44 -0500 )edit

@gvdhoorn big thanks for your detailed explanation, it is now more clear.

bhomaidan gravatar image bhomaidan  ( 2021-12-17 08:10:53 -0500 )edit

@gvdhoorn still I can't claim the resources (Joints), and I don't know why! I'm getting this error: Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible. because the controller can't claim resources:

name: "velocity_qp"
    state: "initialized"
    type: "velocity_qp/YuMiController"
    claimed_resources: 
      - 
        hardware_interface: "hardware_interface::VelocityJointInterface"
        resources: []
      - 
        hardware_interface: "hardware_interface::PositionJointInterface"
        resources: []

Does the controller init function should look like this: bool init(abb::robot::EGMHardwareInterface *, ros::NodeHandle &);

bhomaidan gravatar image bhomaidan  ( 2021-12-20 05:37:23 -0500 )edit

Please do not post follow-up questions as comments under already accepted answers.

Post a new question, referring to your old one.

Having written that:

  • it's possible abb_robot_driver does not support having both the position and the velocity interfaces active at the same time
  • you should probably ask the maintainer / developer of the controller you are changing
gvdhoorn gravatar image gvdhoorn  ( 2021-12-20 05:51:15 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-12-17 03:55:55 -0500

Seen: 188 times

Last updated: Dec 17 '21