Added robotoid's urdf
This commit is contained in:
34
toid_bot_description/CMakeLists.txt
Normal file
34
toid_bot_description/CMakeLists.txt
Normal file
@@ -0,0 +1,34 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.8)
|
||||||
|
project(toid_bot_description)
|
||||||
|
|
||||||
|
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||||
|
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# find dependencies
|
||||||
|
find_package(ament_cmake REQUIRED)
|
||||||
|
# uncomment the following section in order to fill in
|
||||||
|
# further dependencies manually.
|
||||||
|
# find_package(<dependency> REQUIRED)
|
||||||
|
|
||||||
|
install(
|
||||||
|
DIRECTORY
|
||||||
|
src
|
||||||
|
launch
|
||||||
|
rviz
|
||||||
|
DESTINATION share/${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
|
||||||
|
if(BUILD_TESTING)
|
||||||
|
find_package(ament_lint_auto REQUIRED)
|
||||||
|
# the following line skips the linter which checks for copyrights
|
||||||
|
# comment the line when a copyright and license is added to all source files
|
||||||
|
set(ament_cmake_copyright_FOUND TRUE)
|
||||||
|
# the following line skips cpplint (only works in a git repo)
|
||||||
|
# comment the line when this package is in a git repo and when
|
||||||
|
# a copyright and license is added to all source files
|
||||||
|
set(ament_cmake_cpplint_FOUND TRUE)
|
||||||
|
ament_lint_auto_find_test_dependencies()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
ament_package()
|
||||||
17
toid_bot_description/LICENSE
Normal file
17
toid_bot_description/LICENSE
Normal file
@@ -0,0 +1,17 @@
|
|||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in
|
||||||
|
all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
|
||||||
|
THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
THE SOFTWARE.
|
||||||
50
toid_bot_description/launch/display.launch.py
Normal file
50
toid_bot_description/launch/display.launch.py
Normal file
@@ -0,0 +1,50 @@
|
|||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument
|
||||||
|
from launch.conditions import IfCondition, UnlessCondition
|
||||||
|
from launch.substitutions import Command, LaunchConfiguration
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
import os
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
pkg_share = FindPackageShare("").find('toid_bot_description')
|
||||||
|
default_model_path = os.path.join(pkg_share, 'src', 'toid_bot_description.urdf')
|
||||||
|
default_rviz_config_path = os.path.join(pkg_share, 'rviz', 'default.rviz')
|
||||||
|
|
||||||
|
robot_state_publisher_node = Node(
|
||||||
|
package='robot_state_publisher',
|
||||||
|
executable='robot_state_publisher',
|
||||||
|
parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}]
|
||||||
|
)
|
||||||
|
|
||||||
|
joint_state_publisher_node = Node(
|
||||||
|
package='joint_state_publisher',
|
||||||
|
executable='joint_state_publisher',
|
||||||
|
name='joint_state_publisher',
|
||||||
|
parameters=[{'robot_description': Command(['xacro ', default_model_path])}],
|
||||||
|
condition=UnlessCondition(LaunchConfiguration('gui'))
|
||||||
|
)
|
||||||
|
|
||||||
|
joint_state_publisher_gui_node = Node(
|
||||||
|
package='joint_state_publisher_gui',
|
||||||
|
executable='joint_state_publisher_gui',
|
||||||
|
name='joint_state_publisher_gui',
|
||||||
|
condition=IfCondition(LaunchConfiguration('gui'))
|
||||||
|
)
|
||||||
|
|
||||||
|
rviz_node = Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz2',
|
||||||
|
output='screen',
|
||||||
|
arguments=['-d', default_rviz_config_path]
|
||||||
|
)
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
DeclareLaunchArgument(name='gui', default_value='True', description='Flag to enable joint_state_publisher'),
|
||||||
|
DeclareLaunchArgument(name='model', default_value=default_model_path, description='Path to model'),
|
||||||
|
robot_state_publisher_node,
|
||||||
|
joint_state_publisher_node,
|
||||||
|
joint_state_publisher_gui_node,
|
||||||
|
rviz_node
|
||||||
|
])
|
||||||
24
toid_bot_description/package.xml
Normal file
24
toid_bot_description/package.xml
Normal file
@@ -0,0 +1,24 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>toid_bot_description</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>TODO: Package description</description>
|
||||||
|
<maintainer email="example@example.com">pimpest</maintainer>
|
||||||
|
<license>MIT</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<exec_depend>joint_state_publisher</exec_depend>
|
||||||
|
<exec_depend>joint_state_publisher_gui</exec_depend>
|
||||||
|
<exec_depend>robot_state_publisher</exec_depend>
|
||||||
|
<exec_depend>rviz2</exec_depend>
|
||||||
|
<exec_depend>xacro</exec_depend>
|
||||||
|
|
||||||
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
235
toid_bot_description/rviz/default.rviz
Normal file
235
toid_bot_description/rviz/default.rviz
Normal file
@@ -0,0 +1,235 @@
|
|||||||
|
Panels:
|
||||||
|
- Class: rviz_common/Displays
|
||||||
|
Help Height: 78
|
||||||
|
Name: Displays
|
||||||
|
Property Tree Widget:
|
||||||
|
Expanded:
|
||||||
|
- /Global Options1
|
||||||
|
- /Status1
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
Tree Height: 542
|
||||||
|
- Class: rviz_common/Selection
|
||||||
|
Name: Selection
|
||||||
|
- Class: rviz_common/Tool Properties
|
||||||
|
Expanded:
|
||||||
|
- /2D Goal Pose1
|
||||||
|
- /Publish Point1
|
||||||
|
Name: Tool Properties
|
||||||
|
Splitter Ratio: 0.5886790156364441
|
||||||
|
- Class: rviz_common/Views
|
||||||
|
Expanded:
|
||||||
|
- /Current View1
|
||||||
|
Name: Views
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
- Class: rviz_common/Time
|
||||||
|
Experimental: false
|
||||||
|
Name: Time
|
||||||
|
SyncMode: 0
|
||||||
|
SyncSource: ""
|
||||||
|
Visualization Manager:
|
||||||
|
Class: ""
|
||||||
|
Displays:
|
||||||
|
- Alpha: 0.5
|
||||||
|
Cell Size: 1
|
||||||
|
Class: rviz_default_plugins/Grid
|
||||||
|
Color: 160; 160; 164
|
||||||
|
Enabled: true
|
||||||
|
Line Style:
|
||||||
|
Line Width: 0.029999999329447746
|
||||||
|
Value: Lines
|
||||||
|
Name: Grid
|
||||||
|
Normal Cell Count: 0
|
||||||
|
Offset:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Plane: XY
|
||||||
|
Plane Cell Count: 10
|
||||||
|
Reference Frame: <Fixed Frame>
|
||||||
|
Value: true
|
||||||
|
- Alpha: 0.30000001192092896
|
||||||
|
Class: rviz_default_plugins/RobotModel
|
||||||
|
Collision Enabled: false
|
||||||
|
Description File: ""
|
||||||
|
Description Source: Topic
|
||||||
|
Description Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /robot_description
|
||||||
|
Enabled: true
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base_footprint:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
base_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
drivewhl_l_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
drivewhl_r_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
left_caster:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
lidar:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
right_caster:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
Mass Properties:
|
||||||
|
Inertia: false
|
||||||
|
Mass: false
|
||||||
|
Name: RobotModel
|
||||||
|
TF Prefix: ""
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
Visual Enabled: true
|
||||||
|
- Class: rviz_default_plugins/TF
|
||||||
|
Enabled: true
|
||||||
|
Filter (blacklist): ""
|
||||||
|
Filter (whitelist): ""
|
||||||
|
Frame Timeout: 15
|
||||||
|
Frames:
|
||||||
|
All Enabled: true
|
||||||
|
base_footprint:
|
||||||
|
Value: true
|
||||||
|
base_link:
|
||||||
|
Value: true
|
||||||
|
drivewhl_l_link:
|
||||||
|
Value: true
|
||||||
|
drivewhl_r_link:
|
||||||
|
Value: true
|
||||||
|
left_caster:
|
||||||
|
Value: true
|
||||||
|
lidar:
|
||||||
|
Value: true
|
||||||
|
right_caster:
|
||||||
|
Value: true
|
||||||
|
Marker Scale: 0.30000001192092896
|
||||||
|
Name: TF
|
||||||
|
Show Arrows: true
|
||||||
|
Show Axes: true
|
||||||
|
Show Names: true
|
||||||
|
Tree:
|
||||||
|
base_link:
|
||||||
|
base_footprint:
|
||||||
|
{}
|
||||||
|
drivewhl_l_link:
|
||||||
|
{}
|
||||||
|
drivewhl_r_link:
|
||||||
|
{}
|
||||||
|
left_caster:
|
||||||
|
{}
|
||||||
|
lidar:
|
||||||
|
{}
|
||||||
|
right_caster:
|
||||||
|
{}
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
Enabled: true
|
||||||
|
Global Options:
|
||||||
|
Background Color: 48; 48; 48
|
||||||
|
Fixed Frame: base_footprint
|
||||||
|
Frame Rate: 30
|
||||||
|
Name: root
|
||||||
|
Tools:
|
||||||
|
- Class: rviz_default_plugins/Interact
|
||||||
|
Hide Inactive Objects: true
|
||||||
|
- Class: rviz_default_plugins/MoveCamera
|
||||||
|
- Class: rviz_default_plugins/Select
|
||||||
|
- Class: rviz_default_plugins/FocusCamera
|
||||||
|
- Class: rviz_default_plugins/Measure
|
||||||
|
Line color: 128; 128; 0
|
||||||
|
- Class: rviz_default_plugins/SetInitialPose
|
||||||
|
Covariance x: 0.25
|
||||||
|
Covariance y: 0.25
|
||||||
|
Covariance yaw: 0.06853891909122467
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /initialpose
|
||||||
|
- Class: rviz_default_plugins/SetGoal
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /goal_pose
|
||||||
|
- Class: rviz_default_plugins/PublishPoint
|
||||||
|
Single click: true
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /clicked_point
|
||||||
|
Transformation:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/TF
|
||||||
|
Value: true
|
||||||
|
Views:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/XYOrbit
|
||||||
|
Distance: 1.59040105342865
|
||||||
|
Enable Stereo Rendering:
|
||||||
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
|
Stereo Focal Distance: 1
|
||||||
|
Swap Stereo Eyes: false
|
||||||
|
Value: false
|
||||||
|
Focal Point:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Focal Shape Fixed Size: false
|
||||||
|
Focal Shape Size: 0.05000000074505806
|
||||||
|
Invert Z Axis: false
|
||||||
|
Name: Current View
|
||||||
|
Near Clip Distance: 0.009999999776482582
|
||||||
|
Pitch: 0.6053992509841919
|
||||||
|
Target Frame: <Fixed Frame>
|
||||||
|
Value: XYOrbit (rviz_default_plugins)
|
||||||
|
Yaw: 1.088563323020935
|
||||||
|
Saved: ~
|
||||||
|
Window Geometry:
|
||||||
|
Displays:
|
||||||
|
collapsed: false
|
||||||
|
Height: 846
|
||||||
|
Hide Left Dock: false
|
||||||
|
Hide Right Dock: false
|
||||||
|
QMainWindow State: 000000ff00000000fd00000004000000000000016c000002acfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f000002ac000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002acfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003f000002ac000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002de00fffffffb0000000800540069006d0065010000000000000450000000000000000000000229000002ac00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||||
|
Selection:
|
||||||
|
collapsed: false
|
||||||
|
Time:
|
||||||
|
collapsed: false
|
||||||
|
Tool Properties:
|
||||||
|
collapsed: false
|
||||||
|
Views:
|
||||||
|
collapsed: false
|
||||||
|
Width: 1200
|
||||||
|
X: 60
|
||||||
|
Y: 60
|
||||||
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.30"/>
|
||||||
|
<xacro:property name="base_length" value="0.30"/>
|
||||||
|
<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="${-wheel_xoff} 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