init
This commit is contained in:
35
toid_bot_description/src/toid_bot_control.xacro
Normal file
35
toid_bot_description/src/toid_bot_control.xacro
Normal file
@@ -0,0 +1,35 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="toid_control" params="name:=toid_control use_mock_hardware:=^|true">
|
||||
|
||||
<ros2_control name="${name}" type="system">
|
||||
<xacro:unless value="${use_mock_hardware}">
|
||||
<hardware>
|
||||
<!-- plugin would eventually go here-->
|
||||
</hardware>
|
||||
</xacro:unless>
|
||||
<xacro:if value="${use_mock_hardware}">
|
||||
<hardware>
|
||||
<plugin>mock_components/GenericSystem</plugin>
|
||||
<param name="calculate_dynamics">true</param>
|
||||
</hardware>
|
||||
</xacro:if>
|
||||
|
||||
<joint name="drivewhl_l_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
|
||||
<joint name="drivewhl_r_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
|
||||
</ros2_control>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
117
toid_bot_description/src/toid_bot_description.urdf
Normal file
117
toid_bot_description/src/toid_bot_description.urdf
Normal file
@@ -0,0 +1,117 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot name="toid_bot" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:arg name="use_mock" default="true" />
|
||||
|
||||
<xacro:property name="base_width" value="0.31"/>
|
||||
<xacro:property name="base_length" value="0.25"/>
|
||||
<xacro:property name="base_height" value="0.34"/>
|
||||
|
||||
<xacro:property name="wheel_radius" value="0.04"/>
|
||||
<xacro:property name="wheel_width" value="0.03"/>
|
||||
|
||||
<xacro:property name="wheel_zoff" value="0.03"/>
|
||||
<xacro:property name="wheel_xoff" value="-0.07"/>
|
||||
<xacro:property name="wheel_inset" value="0.01"/>
|
||||
|
||||
<xacro:property name="caster_radius" value="0.02"/>
|
||||
|
||||
<xacro:property name="caster_inset" value="0.04"/>
|
||||
<xacro:property name="caster_xoff" value="0.10"/>
|
||||
|
||||
|
||||
<xacro:property name="lidar_radius" value="0.03"/>
|
||||
<xacro:property name="lidar_height" value="0.02"/>
|
||||
<xacro:property name="lidar_xoff" value="0.09"/>
|
||||
|
||||
<xacro:property name="base_zoff" value="${-wheel_zoff + wheel_radius + base_height/2}"/>
|
||||
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="${base_length} ${base_width} ${base_height}"/>
|
||||
</geometry>
|
||||
<material name="Cyan">
|
||||
<color rgba="0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<link name="base_footprint"/>
|
||||
|
||||
<link name="lidar">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder radius="${lidar_radius}" length="${lidar_height}"/>
|
||||
</geometry>
|
||||
<material name="White">
|
||||
<color rgba="0.9 0.9 0.9 1.0"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="base_joint" type="fixed">
|
||||
<child link="base_link"/>
|
||||
<parent link="base_footprint"/>
|
||||
<origin xyz="0.0 0.0 ${base_zoff}" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<joint name="lidar_joint" type="fixed">
|
||||
<parent link="base_link"/>
|
||||
<child link="lidar"/>
|
||||
<origin xyz="${lidar_xoff} 0 ${(base_height + lidar_height)/2}" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<xacro:macro name="wheel" params="prefix y_reflect">
|
||||
<link name="${prefix}_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
|
||||
</geometry>
|
||||
<material name="Yellow">
|
||||
<color rgba="0.8 0.8 0.3 1.0"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="${prefix}_joint" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="${prefix}_link"/>
|
||||
<origin xyz="${wheel_xoff} ${y_reflect*(base_width/2 - wheel_inset)} ${wheel_zoff-base_height/2}" rpy="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
</joint>
|
||||
</xacro:macro>
|
||||
|
||||
|
||||
<xacro:macro name="cstr" params="prefix y_reflect">
|
||||
<link name="${prefix}_caster">
|
||||
<visual>
|
||||
<geometry>
|
||||
<sphere radius="${caster_radius}"/>
|
||||
</geometry>
|
||||
<material name="White">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="${prefix}_caster_joint" type="fixed">
|
||||
<parent link="base_link"/>
|
||||
<child link="${prefix}_caster"/>
|
||||
<origin xyz="${caster_xoff} ${y_reflect*(base_width/2 - caster_inset)} ${caster_radius-base_zoff}" rpy="0 0 0"/>
|
||||
</joint>
|
||||
</xacro:macro>
|
||||
|
||||
|
||||
<xacro:wheel prefix="drivewhl_l" y_reflect="1" />
|
||||
<xacro:wheel prefix="drivewhl_r" y_reflect="-1" />
|
||||
|
||||
<xacro:cstr prefix="left" y_reflect="1" />
|
||||
<xacro:cstr prefix="right" y_reflect="-1" />
|
||||
|
||||
<xacro:include filename="$(find toid_bot_description)/src/toid_bot_control.xacro"/>
|
||||
<xacro:toid_control name="toid_bot_control" use_mock_hardware="$(arg use_mock)"/>
|
||||
|
||||
</robot>
|
||||
Reference in New Issue
Block a user