ROS Components for hexapod_robot
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

78 lines
5.0KB

  1. <?xml version="1.0"?>
  2. <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  3. <xacro:macro name="create_leg_joints" params="number">
  4. <joint name="c${number}_joint">
  5. <command_interface name="position">
  6. <param name="min">-1</param>
  7. <param name="max">1</param>
  8. </command_interface>
  9. <state_interface name="position"/>
  10. </joint>
  11. <joint name="f${number}_joint">
  12. <command_interface name="position">
  13. <param name="min">-1</param>
  14. <param name="max">1</param>
  15. </command_interface>
  16. <state_interface name="position"/>
  17. </joint>
  18. <joint name="t${number}_joint">
  19. <command_interface name="position">
  20. <param name="min">-1</param>
  21. <param name="max">1</param>
  22. </command_interface>
  23. <state_interface name="position"/>
  24. </joint>
  25. </xacro:macro>
  26. <xacro:macro name="map_joint_name_to_hardware" params="name i2c_address channel counts_intersect counts_slope counts_min counts_max">
  27. <param name="${name}_joint_i2c_address">${i2c_address}</param>
  28. <param name="${name}_joint_channel">${channel}</param>
  29. <param name="${name}_joint_counts_intersect">${counts_intersect}</param>
  30. <param name="${name}_joint_counts_slope">${counts_slope}</param>
  31. <param name="${name}_joint_counts_min">${counts_min}</param>
  32. <param name="${name}_joint_counts_max">${counts_max}</param>
  33. </xacro:macro>
  34. <ros2_control name="Hexapod" type="system">
  35. <hardware>
  36. <plugin>hexapod_robot/HexapodRobotHardwareInterface</plugin>
  37. <param name="i2c_device">/dev/i2c-1</param>
  38. <xacro:map_joint_name_to_hardware name="c1" i2c_address="0x40" channel="13" counts_intersect="386" counts_slope="129" counts_min="125" counts_max="550"/>
  39. <xacro:map_joint_name_to_hardware name="f1" i2c_address="0x40" channel="14" counts_intersect="307" counts_slope="129" counts_min="125" counts_max="550"/>
  40. <xacro:map_joint_name_to_hardware name="t1" i2c_address="0x40" channel="15" counts_intersect="189" counts_slope="129" counts_min="125" counts_max="550"/>
  41. <xacro:map_joint_name_to_hardware name="c2" i2c_address="0x40" channel="9" counts_intersect="327" counts_slope="129" counts_min="125" counts_max="550"/>
  42. <xacro:map_joint_name_to_hardware name="f2" i2c_address="0x40" channel="10" counts_intersect="317" counts_slope="129" counts_min="125" counts_max="550"/>
  43. <xacro:map_joint_name_to_hardware name="t2" i2c_address="0x40" channel="11" counts_intersect="227" counts_slope="129" counts_min="125" counts_max="550"/>
  44. <xacro:map_joint_name_to_hardware name="c3" i2c_address="0x40" channel="2" counts_intersect="237" counts_slope="129" counts_min="125" counts_max="550"/>
  45. <xacro:map_joint_name_to_hardware name="f3" i2c_address="0x40" channel="1" counts_intersect="307" counts_slope="129" counts_min="125" counts_max="550"/>
  46. <xacro:map_joint_name_to_hardware name="t3" i2c_address="0x40" channel="0" counts_intersect="267" counts_slope="129" counts_min="125" counts_max="550"/>
  47. <xacro:map_joint_name_to_hardware name="c4" i2c_address="0x41" channel="13" counts_intersect="451" counts_slope="129" counts_min="125" counts_max="550"/>
  48. <xacro:map_joint_name_to_hardware name="f4" i2c_address="0x41" channel="14" counts_intersect="367" counts_slope="129" counts_min="125" counts_max="550"/>
  49. <xacro:map_joint_name_to_hardware name="t4" i2c_address="0x41" channel="15" counts_intersect="487" counts_slope="129" counts_min="125" counts_max="550"/>
  50. <xacro:map_joint_name_to_hardware name="c5" i2c_address="0x41" channel="6" counts_intersect="357" counts_slope="129" counts_min="125" counts_max="550"/>
  51. <xacro:map_joint_name_to_hardware name="f5" i2c_address="0x41" channel="5" counts_intersect="367" counts_slope="129" counts_min="125" counts_max="550"/>
  52. <xacro:map_joint_name_to_hardware name="t5" i2c_address="0x41" channel="4" counts_intersect="437" counts_slope="129" counts_min="125" counts_max="550"/>
  53. <xacro:map_joint_name_to_hardware name="c6" i2c_address="0x41" channel="2" counts_intersect="255" counts_slope="129" counts_min="125" counts_max="550"/>
  54. <xacro:map_joint_name_to_hardware name="f6" i2c_address="0x41" channel="1" counts_intersect="335" counts_slope="129" counts_min="125" counts_max="550"/>
  55. <xacro:map_joint_name_to_hardware name="t6" i2c_address="0x41" channel="0" counts_intersect="444" counts_slope="129" counts_min="125" counts_max="550"/>
  56. </hardware>
  57. <xacro:create_leg_joints number="1"/>
  58. <xacro:create_leg_joints number="2"/>
  59. <xacro:create_leg_joints number="3"/>
  60. <xacro:create_leg_joints number="4"/>
  61. <xacro:create_leg_joints number="5"/>
  62. <xacro:create_leg_joints number="6"/>
  63. </ros2_control>
  64. </robot>