瀏覽代碼

updated calibration values

main
Marcus Grieger 1 年之前
父節點
當前提交
eba9f8d454
共有 1 個文件被更改,包括 18 次插入18 次删除
  1. +18
    -18
      config/urdf/hexapod_robot_ros2_control.xacro

+ 18
- 18
config/urdf/hexapod_robot_ros2_control.xacro 查看文件

@@ -42,29 +42,29 @@
<hardware>
<plugin>hexapod_robot/HexapodRobotHardwareInterface</plugin>
<param name="i2c_device">/dev/i2c-1</param>
<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" startup_value="0"/>
<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" startup_value="-1.4"/>
<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" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="c1" i2c_address="0x40" channel="13" counts_intersect="389" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="f1" i2c_address="0x40" channel="14" counts_intersect="329" counts_slope="129" counts_min="125" counts_max="550" startup_value="-1.2"/>
<xacro:map_joint_name_to_hardware name="t1" i2c_address="0x40" channel="15" counts_intersect="202" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>

<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" startup_value="0"/>
<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" startup_value="-1.4"/>
<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" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="c2" i2c_address="0x40" channel="9" counts_intersect="329" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="f2" i2c_address="0x40" channel="10" counts_intersect="334" counts_slope="129" counts_min="125" counts_max="550" startup_value="-1.2"/>
<xacro:map_joint_name_to_hardware name="t2" i2c_address="0x40" channel="11" counts_intersect="232" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<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" startup_value="0"/>
<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" startup_value="-1.4"/>
<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" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="c3" i2c_address="0x40" channel="2" counts_intersect="238" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="f3" i2c_address="0x40" channel="1" counts_intersect="320" counts_slope="129" counts_min="125" counts_max="550" startup_value="-1.2"/>
<xacro:map_joint_name_to_hardware name="t3" i2c_address="0x40" channel="0" counts_intersect="279" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<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" startup_value="0"/>
<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" startup_value="1.4"/>
<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" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="c4" i2c_address="0x41" channel="13" counts_intersect="448" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="f4" i2c_address="0x41" channel="14" counts_intersect="371" counts_slope="129" counts_min="125" counts_max="550" startup_value="1.2"/>
<xacro:map_joint_name_to_hardware name="t4" i2c_address="0x41" channel="15" counts_intersect="479" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<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" startup_value="0"/>
<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" startup_value="1.4"/>
<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" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="c5" i2c_address="0x41" channel="6" counts_intersect="355" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="f5" i2c_address="0x41" channel="5" counts_intersect="363" counts_slope="129" counts_min="125" counts_max="550" startup_value="1.2"/>
<xacro:map_joint_name_to_hardware name="t5" i2c_address="0x41" channel="4" counts_intersect="424" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<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" startup_value="0"/>
<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" startup_value="1.4"/>
<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" startup_value="0"/>
<xacro:map_joint_name_to_hardware name="c6" i2c_address="0x41" channel="2" counts_intersect="252" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
<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" startup_value="1.2"/>
<xacro:map_joint_name_to_hardware name="t6" i2c_address="0x41" channel="0" counts_intersect="447" counts_slope="129" counts_min="125" counts_max="550" startup_value="0"/>
</hardware>

<xacro:create_leg_joints number="1"/>


Loading…
取消
儲存