Unified hexapod repository, containing all modules
Du kannst nicht mehr als 25 Themen auswählen
Themen müssen entweder mit einem Buchstaben oder einer Ziffer beginnen. Sie können Bindestriche („-“) enthalten und bis zu 35 Zeichen lang sein.
|
- <?xml version="1.0"?>
- <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
-
- <xacro:macro name="create_leg_joints" params="number">
-
- <joint name="c${number}_joint">
- <command_interface name="position">
- <param name="min">-1.57</param>
- <param name="max">1.57</param>
- </command_interface>
- <state_interface name="position"/>
- </joint>
-
- <joint name="f${number}_joint">
- <command_interface name="position">
- <param name="min">-1.57</param>
- <param name="max">1.57</param>
- </command_interface>
- <state_interface name="position"/>
- </joint>
- <joint name="t${number}_joint">
- <command_interface name="position">
- <param name="min">-1.57</param>
- <param name="max">1.57</param>
- </command_interface>
- <state_interface name="position"/>
- </joint>
- </xacro:macro>
-
- <xacro:macro name="map_joint_name_to_hardware" params="name i2c_address channel counts_intersect counts_slope counts_min counts_max startup_value">
- <param name="${name}_joint_i2c_address">${i2c_address}</param>
- <param name="${name}_joint_channel">${channel}</param>
- <param name="${name}_joint_counts_intersect">${counts_intersect}</param>
- <param name="${name}_joint_counts_slope">${counts_slope}</param>
- <param name="${name}_joint_counts_min">${counts_min}</param>
- <param name="${name}_joint_counts_max">${counts_max}</param>
- <param name="${name}_joint_startup_value">${startup_value}</param>
- </xacro:macro>
-
- <ros2_control name="Hexapod" type="system">
-
- <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="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="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="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="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="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="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"/>
- <xacro:create_leg_joints number="2"/>
- <xacro:create_leg_joints number="3"/>
- <xacro:create_leg_joints number="4"/>
- <xacro:create_leg_joints number="5"/>
- <xacro:create_leg_joints number="6"/>
-
- </ros2_control>
- </robot>
|