xArm-Developer / xarm_ros2

ROS2 developer packages for robotic products from UFACTORY
https://www.ufactory.cc/pages/xarm
BSD 3-Clause "New" or "Revised" License
115 stars 72 forks source link

Initial_value for joints in fake_system_hardware #45

Open JensVanhooydonck opened 1 year ago

JensVanhooydonck commented 1 year ago

Add initial_value in the fake_hardware_interface.

DaniGarciaLopez commented 11 months ago

I'm interested in this PR. I would also like to set an initial value for the robot using fake hardware.

@JensVanhooydonck , how do you set the initial position? I tried adding the initial_value as follows in .ros2_control.xacro but apparently it doesn't have any effect:

<joint name="${prefix}joint3">
  <command_interface name="position">
    <param name="min">${joint3_lower_limit}</param>
    <param name="max">${joint3_upper_limit}</param>
  </command_interface>
  <command_interface name="velocity">
    <param name="min">-3.14</param>
    <param name="max">3.14</param>
  </command_interface>
  <state_interface name="position">   
    <param name="initial_value">0.5</param>
  </state_interface>
  <state_interface name="velocity"/>
  <!-- <state_interface name="effort"/> -->
</joint>
JensVanhooydonck commented 11 months ago

@DaniGarciaLopez This is indeed how I assign these values.

DaniGarciaLopez commented 11 months ago

Okay, yes, it works. I was just sourcing an incorrect file. Thanks, @JensVanhooydonck!

destogl commented 2 months ago

Hi, Dr. Denis here, maintainer of ros2_control. I am wondering, why do you have your implementation of the Fake Hardware? Does the generic implementation of (now renamed!) Mock Hardware is missing something relevant for you? If so, please let me know, and we can extend the generic version, so you don't have to maintain your custom version :smiley:

From what I have understood, you have just a version cut down to your manipulators - this is the reason of asking.