mirror of
https://github.com/bjoernellens1/cps_loki_description.git
synced 2024-11-21 23:23:49 +00:00
update
This commit is contained in:
parent
5c97dd15d5
commit
5d21b0b2dc
5
setup.py
5
setup.py
@ -1,15 +1,18 @@
|
||||
import os
|
||||
from glob import glob
|
||||
from setuptools import setup
|
||||
|
||||
package_name = 'bot_mini_description'
|
||||
|
||||
setup(
|
||||
name=package_name,
|
||||
version='0.0.0',
|
||||
version='0.0.1',
|
||||
packages=[package_name],
|
||||
data_files=[
|
||||
('share/ament_index/resource_index/packages',
|
||||
['resource/' + package_name]),
|
||||
('share/' + package_name, ['package.xml']),
|
||||
(os.path.join('share', package_name), glob('urdf/*.xacro')),
|
||||
],
|
||||
install_requires=['setuptools'],
|
||||
zip_safe=True,
|
||||
|
40
urdf/diffbot.materials.xacro
Normal file
40
urdf/diffbot.materials.xacro
Normal file
@ -0,0 +1,40 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Copied from ROS1 example:
|
||||
https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_description/urdf/materials.xacro
|
||||
-->
|
||||
<robot>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="orange">
|
||||
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="brown">
|
||||
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
184
urdf/diffbot_description.urdf.xacro
Normal file
184
urdf/diffbot_description.urdf.xacro
Normal file
@ -0,0 +1,184 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="diffbot" params="prefix">
|
||||
|
||||
<!-- Constants for robot dimensions -->
|
||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||
<xacro:property name="base_mass" value="0.3" /> <!-- arbitrary value for base mass -->
|
||||
<xacro:property name="base_width" value="0.26" />
|
||||
<xacro:property name="base_length" value="0.34" />
|
||||
<xacro:property name="base_height" value="0.1" />
|
||||
<xacro:property name="wheel_mass" value="0.3" /> <!-- arbitrary value for wheel mass -->
|
||||
<xacro:property name="wheel_len" value="0.020" />
|
||||
<xacro:property name="wheel_radius" value="0.0625" />
|
||||
<xacro:property name="caster_wheel_mass" value="0.1" /> <!-- arbitrary value for caster wheel mass -->
|
||||
<xacro:property name="caster_wheel_radius" value="0.04" />
|
||||
<xacro:property name="z_offset" value="-${base_height/2}" /> <!-- Space btw top of beam and the each joint -->
|
||||
|
||||
<!-- Base Link -->
|
||||
<link name="${prefix}base_link">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="${base_width} ${base_length} ${base_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 ${base_height/2}" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="${base_width} ${base_length} ${base_height}"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="${base_mass}"/>
|
||||
<inertia
|
||||
ixx="${base_mass / 12.0 * (base_length*base_length + base_height*base_height)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${base_mass / 12.0 * (base_height*base_height + base_width*base_width)}" iyz="0.0"
|
||||
izz="${base_mass / 12.0 * (base_width*base_width + base_length*base_length)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${prefix}left_wheel_joint" type="continuous">
|
||||
<parent link="${prefix}base_link"/>
|
||||
<child link="${prefix}left_wheel"/>
|
||||
<origin xyz="0 -0.07 ${z_offset}" rpy="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.2"/>
|
||||
</joint>
|
||||
|
||||
<!-- left wheel Link -->
|
||||
<link name="${prefix}left_wheel">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
|
||||
<mass value="${wheel_mass}"/>
|
||||
<inertia
|
||||
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
|
||||
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${prefix}right_wheel_joint" type="continuous">
|
||||
<parent link="${prefix}base_link"/>
|
||||
<child link="${prefix}right_wheel"/>
|
||||
<origin xyz="0 -0.07 ${z_offset}" rpy="0 0 0"/>
|
||||
<axis xyz="0 -1 0"/>
|
||||
<dynamics damping="0.2"/>
|
||||
</joint>
|
||||
|
||||
<!-- right wheel Link -->
|
||||
<link name="${prefix}right_wheel">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
|
||||
<mass value="${wheel_mass}"/>
|
||||
<inertia
|
||||
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
|
||||
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${prefix}caster_frontal_wheel_joint" type="fixed">
|
||||
<parent link="${prefix}base_link"/>
|
||||
<child link="${prefix}caster_frontal_wheel"/>
|
||||
<origin xyz="${base_width/2 - caster_wheel_radius} 0 ${z_offset}" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<!-- caster frontal wheel Link -->
|
||||
<link name="${prefix}caster_frontal_wheel">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${caster_wheel_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${caster_wheel_radius}"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="${caster_wheel_mass}"/>
|
||||
<inertia
|
||||
ixx="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" iyz="0.0"
|
||||
izz="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${prefix}caster_rear_wheel_joint" type="fixed">
|
||||
<parent link="${prefix}base_link"/>
|
||||
<child link="${prefix}caster_rear_wheel"/>
|
||||
<origin xyz="${-base_width/2 + caster_wheel_radius} 0 ${z_offset}" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<!-- caster rear wheel Link -->
|
||||
<link name="${prefix}caster_rear_wheel">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${caster_wheel_radius}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="${caster_wheel_radius}"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="${caster_wheel_mass}"/>
|
||||
<inertia
|
||||
ixx="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" ixy="0.0" ixz="0.0"
|
||||
iyy="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" iyz="0.0"
|
||||
izz="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
37
urdf/odrive.ros2_control.xacro
Normal file
37
urdf/odrive.ros2_control.xacro
Normal file
@ -0,0 +1,37 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="odrive_ros2_control"
|
||||
params="name serial_number:=^|000000000000 enable_joint0:=^|true enable_joint1:=^|true joint0_name:=^|joint0 joint1_name:=^|joint1">
|
||||
|
||||
<ros2_control name="${name}" type="system">
|
||||
<hardware>
|
||||
<plugin>odrive_hardware_interface/ODriveHardwareInterface</plugin>
|
||||
</hardware>
|
||||
|
||||
<sensor name="odrv0">
|
||||
<param name="serial_number">${serial_number}</param>
|
||||
</sensor>
|
||||
|
||||
<xacro:if value="${enable_joint0}">
|
||||
<joint name="${joint0_name}">
|
||||
<param name="serial_number">${serial_number}</param>
|
||||
<param name="axis">0</param>
|
||||
<param name="enable_watchdog">1</param>
|
||||
<param name="watchdog_timeout">0.1</param>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:if value="${enable_joint1}">
|
||||
<joint name="${joint1_name}">
|
||||
<param name="serial_number">${serial_number}</param>
|
||||
<param name="axis">1</param>
|
||||
<param name="enable_watchdog">1</param>
|
||||
<param name="watchdog_timeout">0.1</param>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
</ros2_control>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
34
urdf/odrive.urdf.xacro
Normal file
34
urdf/odrive.urdf.xacro
Normal file
@ -0,0 +1,34 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="odrive">
|
||||
|
||||
<xacro:arg name="enable_joint0" default="true" />
|
||||
<xacro:arg name="enable_joint1" default="true" />
|
||||
|
||||
<xacro:include filename="$(find odrive_demo_description)/urdf/odrive.ros2_control.xacro" />
|
||||
|
||||
<link name="world" />
|
||||
|
||||
<xacro:if value="$(arg enable_joint0)">
|
||||
<link name="link0" />
|
||||
<joint name="joint0" type="continuous">
|
||||
<parent link="world"/>
|
||||
<child link="link0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:if value="$(arg enable_joint1)">
|
||||
<link name="link1" />
|
||||
<joint name="joint1" type="continuous">
|
||||
<parent link="world"/>
|
||||
<child link="link1"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:odrive_ros2_control
|
||||
name="odrive_ros2_control"
|
||||
enable_joint0="$(arg enable_joint0)"
|
||||
enable_joint1="$(arg enable_joint1)" />
|
||||
|
||||
</robot>
|
19
urdf/odrive_diffbot.urdf.xacro
Normal file
19
urdf/odrive_diffbot.urdf.xacro
Normal file
@ -0,0 +1,19 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="diffdrive_robot">
|
||||
|
||||
<xacro:arg name="prefix" default="" />
|
||||
|
||||
<xacro:include filename="$(find odrive_demo_description)/urdf/diffbot_description.urdf.xacro" />
|
||||
|
||||
<xacro:include filename="$(find odrive_demo_description)/urdf/diffbot.materials.xacro" />
|
||||
|
||||
<xacro:include filename="$(find odrive_demo_description)/urdf/odrive.ros2_control.xacro" />
|
||||
|
||||
<xacro:diffbot prefix="$(arg prefix)" />
|
||||
|
||||
<xacro:odrive_ros2_control
|
||||
name="ODriveDiffBot"
|
||||
joint0_name="$(arg prefix)left_wheel_joint"
|
||||
joint1_name="$(arg prefix)right_wheel_joint" />
|
||||
|
||||
</robot>
|
23
urdf/odrive_rrbot.urdf.xacro
Normal file
23
urdf/odrive_rrbot.urdf.xacro
Normal file
@ -0,0 +1,23 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot">
|
||||
|
||||
<xacro:arg name="prefix" default="" />
|
||||
|
||||
<xacro:include filename="$(find rrbot_description)/urdf/rrbot_description.urdf.xacro" />
|
||||
|
||||
<xacro:include filename="$(find rrbot_description)/gazebo/rrbot.materials.xacro" />
|
||||
|
||||
<xacro:include filename="$(find odrive_demo_description)/urdf/odrive.ros2_control.xacro" />
|
||||
|
||||
<link name="world"/>
|
||||
|
||||
<xacro:rrbot parent="world" prefix="$(arg prefix)">
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
</xacro:rrbot>
|
||||
|
||||
<xacro:odrive_ros2_control
|
||||
name="ODriveRRBot"
|
||||
joint0_name="$(arg prefix)joint1"
|
||||
joint1_name="$(arg prefix)joint2" />
|
||||
|
||||
</robot>
|
Loading…
Reference in New Issue
Block a user