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)