robomechanics / quad-sdk

Software tools for agile quadrupeds, developed by the Robomechanics Lab at Carnegie Mellon University.
https://robomechanics.github.io/quad-sdk/
MIT License
697 stars 133 forks source link

Unitree A1 convention used in xacro / kinematics / urdf #325

Closed thvhauwe closed 1 year ago

thvhauwe commented 1 year ago

Hello and thanks for providing this codebase.

I'm having trouble to execute simulated motions of the unitree A1 robot on real hardware. I noticed there is a difference in definition of the revolute joint in HFE and KFE joints, originating in edits in the xacro files leg.xacro and const.xacro, compared to the ones provided by the manufacturer Unitree (https://github.com/unitreerobotics/unitree_ros/tree/master/robots/a1_description/xacro).

The result is that computed joint angles for KFE joint for example return positive values (e.g. during standing) but on the unitree A1 this is an invalid position, as this joint angle should lie between (-2.7, -0.9).

Bottomline: difference in xacro/urdf/kinematics complicates execution of code on real A1 hardware. Could you elaborate why this different convention was introduced? What files/configs would need to be editted to use the original xacro/urdf conventions with quad-sdk(as to allow execution on the hardware)

jrenaf commented 1 year ago

Hi @thvhauwe, thanks for trying out quad-sdk. Yes, there is a difference on hip and knee joint limit between sdf/urdf/xacro in our code and that from Unitree. To fit in A1 hardware configuration, a straightforward approach we would suggest is to set up a linear mapping between two configurations within controller and estimator plugin in quad_simulator when using gazebo or in robot_driver when using hardwares which interfaces the local planner with robot motors.

jcnorby commented 1 year ago

To give some more context to this answer, even though many commercially available quadrupeds share similar morphologies, there is no set convention between robot brands/models on joint zeros/directions. As a result, adding a new robot requires either updating the urdf to match one particular convention, or writing plugins for any particular robot model which handle this mapping. For simplicity we chose the former option (using the default Spirit 40 convention as that is the platform we use for hardware testing), although the latter may be more generalizeable in the long term. If this is something that the community prioritizes we could consider adding it to the list of desired features, although as always we welcome PRs if folks develop their own solution!

Also to clarify the files that would need to be changed for hardware execution - I would recommend making a new class that inherits HardwareInterface called A1Interface which can handle this mapping when sending and receiving data from the robot (see SpiritInterface for an example). As Jiming mentioned you would need to update controller_plugin.cpp and estimator_plugin.cpp to do the same thing in simulation.

thvhauwe commented 1 year ago

Thanks for this clarification. I understand now this was a practical decision to take. For now I execute commands from quad-sdk on the A1 hardware using a ros node that subscribes to quad-sdk commands, performs conversions and linear mapping and then sends those commands to the robot using LCM. This is an adhoc solution and essentially results in open-loop control. Indeed creation of a A1 hardware interface would be a better solution, maybe one I can commit some time into in the near future.

jcnorby commented 1 year ago

Yep, that functionality is exactly what the HardwareInterface class is for. Since it is embedded directly within the RobotDriver loop it doesn't introduce the additional latency/overhead associated with ROS messaging (same thing for receiving sensor data from the robot).

jcnorby commented 1 year ago

Closing this issue due to lack of activity, and also for lack of an A1 platform to test on. Can be reopened in the future if progress is made.