Commit 938071e9 authored by Paul Rouanet's avatar Paul Rouanet
Browse files

Modif step by step

parent c4760e69
......@@ -4,7 +4,7 @@ project(ros2_description_bolt)
find_package(ament_cmake REQUIRED)
install(
DIRECTORY meshes ros2_control urdf launch
DIRECTORY meshes ros2_control urdf launch gazebo
DESTINATION share/${PROJECT_NAME}
)
......
latest_list
\ No newline at end of file
list_2021-08-24_16-05-50
\ No newline at end of file
[0.442s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'list', '-p', '--base-paths', '/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt']
[0.442s] DEBUG:colcon:Parsed command line arguments: Namespace(base_paths=['/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt'], build_base='build', ignore_user_meta=False, log_base=None, log_level=None, main=<bound method ListVerb.main of <colcon_package_information.verb.list.ListVerb object at 0x7f331d2931f0>>, metas=['./colcon.meta'], names_only=False, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_end=None, packages_ignore=None, packages_ignore_regex=None, packages_select=None, packages_select_build_failed=False, packages_select_by_dep=None, packages_select_regex=None, packages_select_test_failures=False, packages_skip=None, packages_skip_build_finished=False, packages_skip_by_dep=None, packages_skip_regex=None, packages_skip_test_passed=False, packages_skip_up_to=None, packages_start=None, packages_up_to=None, packages_up_to_regex=None, paths=None, paths_only=True, topological_graph=False, topological_graph_density=False, topological_graph_dot=False, topological_graph_dot_cluster=False, topological_graph_dot_include_skipped=False, topological_graph_legend=False, topological_order=False, verb_extension=<colcon_package_information.verb.list.ListVerb object at 0x7f331d2931f0>, verb_name='list', verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0x7f331d1b4610>)
[0.465s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
[0.466s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
[0.466s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
[0.466s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
[0.466s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
[0.466s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt'
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extensions ['ignore', 'ignore_ament_install']
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extension 'ignore'
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extension 'ignore_ament_install'
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extensions ['colcon_pkg']
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extension 'colcon_pkg'
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extensions ['colcon_meta']
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extension 'colcon_meta'
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extensions ['ros']
[0.466s] Level 1:colcon.colcon_core.package_identification:_identify(/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt) by extension 'ros'
[0.478s] DEBUG:colcon.colcon_core.package_identification:Package '/usr/bolt_ws/src/ros2_control_bolt/ros2_description_bolt' with type 'ros.ament_cmake' and name 'ros2_description_bolt'
[0.478s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="system_bolt" params="name prefix use_sim:=^|false use_fake_hardware:=^|true fake_sensor_commands:=^|false slowdown:=2.0">
<xacro:macro name="system_bolt_ros2_control" params="name prefix use_sim:=^|false use_fake_hardware:=^|true fake_sensor_commands:=^|false slowdown:=2.0">
<ros2_control name="${name}" type="system">
......
<?xml version="1.0"?>
<robot xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" name="bolt">
<!-- See TODO: add the wiki link here -->
<!-- These are absolute distance value, the sign are decided below -->
<xacro:property name="base_2_HAA_x" value="${0.0 * 0.001}" />
<xacro:property name="base_2_HAA_y" value="${63.6 * 0.001}" />
<!--xacro:property name="base_2_HAA_x" value="${2.45656 * 0.001}" />
<xacro:property name="base_2_HAA_y" value="${63.6 * 0.001}" />
<xacro:property name="base_2_HAA_z" value="${33.0809 * 0.001}" /-->
<xacro:property name="HAA_2_HFE_y" value="${14.5 * 0.001}" />
<xacro:property name="HAA_2_HFE_z" value="${38.60 * 0.001}" />
<xacro:property name="HFE_2_KFE_y" value="${37.4 * 0.001}" />
<xacro:property name="HFE_2_KFE_z" value="${200.00 * 0.001}" />
<xacro:property name="KFE_2_FOOT_y" value="${8.0 * 0.001}" />
<xacro:property name="KFE_2_FOOT_z" value="${200.00 * 0.001}" />
<xacro:if value="${has_passive_ankle}">
<xacro:property name="ankle_joint_type" value="revolute" />
</xacro:if>
<xacro:unless value="${has_passive_ankle}">
<xacro:property name="ankle_joint_type" value="fixed" />
</xacro:unless>
<!-- Macro defining bolt leg. -->
<xacro:macro name="leg" params="prefix is_front is_right has_side_motion
mesh_ext color_name color opacity new_leg
has_passive_ankle">
<joint name="${prefix}_HAA" type="revolute">
<parent link="base_link"/>
<child link="${prefix}_SHOULDER"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the x-axis -->
<axis xyz="1 0 0"/>
<!-- placement of the joint -->
<xacro:unless value="${is_right}">
<origin xyz="${base_2_HAA_x} ${base_2_HAA_y} 0" rpy="0 0 0"/>
</xacro:unless>
<xacro:if value="${is_right}">
<origin xyz="${base_2_HAA_x} ${-base_2_HAA_y} 0" rpy="0 0 0"/>
</xacro:if>
<!--xacro:unless value="${is_right}">
<origin xyz="${base_2_HAA_x} ${base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
</xacro:unless>
<xacro:if value="${is_right}">
<origin xyz="${base_2_HAA_x} ${-base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
</xacro:if-->
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}_SHOULDER">
<!-- TODO: Update inertias and add visuals for link. -->
<!-- create a dummy shoulder link to join the two joints -->
<inertial>
<xacro:unless value="${is_right}">
<!-- Left upper leg inertia -->
<mass value="0.14004265"/>
<origin xyz="0.01708256 -0.00446892 -0.01095830" rpy="0 0 0"/>
<inertia ixx="0.00007443"
ixy="0.00000148"
ixz="0.00002154"
iyy="0.00013847"
iyz="-0.00001096"
izz="0.00009002"/>
</xacro:unless>
<xacro:if value="${is_right}">
<!-- Right upper leg inertia -->
<mass value="0.14004412"/>
<origin xyz="0.01708233 0.00447099 -0.01095846" rpy="0 0 0"/>
<inertia ixx="0.00007442"
ixy="-0.00000148"
ixz="0.00002154"
iyy="0.00013848"
iyz="0.00001095"
izz="0.00009001"/>
</xacro:if>
</inertial>
<!-- HIP LEG LINK VISUAL -->
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_hip_fe_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_hip_fe_right_side.${mesh_ext}"/>
</xacro:if>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</visual>
<!-- UPPER LEG LINK COLLISION -->
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_hip_fe_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_hip_fe_right_side.${mesh_ext}"/>
</xacro:if>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<joint name="${prefix}_HFE" type="revolute">
<parent link="${prefix}_SHOULDER"/>
<child link="${prefix}_UPPER_LEG"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<!-- placement of the joint -->
<xacro:if value="${is_right}">
<origin xyz="0 ${-HAA_2_HFE_y} ${-HAA_2_HFE_z}" rpy="0 0 0"/>
</xacro:if>
<xacro:unless value="${is_right}">
<origin xyz="0 ${HAA_2_HFE_y} ${-HAA_2_HFE_z}" rpy="0 0 0"/>
</xacro:unless>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}_UPPER_LEG">
<!-- UPPER LEG LINK INERTIAL -->
<xacro:unless value="${is_right}">
<!-- Left upper leg inertia -->
<inertial>
<origin xyz="0.00001377 0.01935853 -0.11870700" rpy="0 0 0"/>
<mass value="0.14853845"/>
<inertia ixx="0.00041107"
ixy="0.00000000"
ixz="0.00000009"
iyy="0.00041193"
iyz="-0.00004671"
izz="0.00003024"/>
</inertial>
</xacro:unless>
<xacro:if value="${is_right}">
<!-- Right upper leg inertia -->
<inertial>
<origin xyz="-0.00001377 -0.01935853 -0.11870700" rpy="0 0 0"/>
<mass value="0.14853845"/>
<inertia ixx="0.00041107"
ixy="0.00000000"
ixz="-0.00000009"
iyy="0.00041193"
iyz="0.00004671"
izz="0.00003024"/>
</inertial>
</xacro:if>
<!-- UPPER LEG LINK VISUAL -->
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<xacro:unless value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_upper_leg_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_upper_leg_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/upper_leg_200mm_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/upper_leg_200mm_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:if>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</visual>
<!-- UPPER LEG LINK COLLISION -->
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<xacro:unless value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_upper_leg_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_upper_leg_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/upper_leg_200mm_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/upper_leg_200mm_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:if>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<!-- END UPPER LEG LINK -->
<!-- KFE: Joint between the upper leg and the lower leg -->
<joint name="${prefix}_KFE" type="revolute">
<parent link="${prefix}_UPPER_LEG"/>
<child link="${prefix}_LOWER_LEG"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<!-- placement of the joint -->
<xacro:unless value="${is_right}">
<origin xyz="0 ${HFE_2_KFE_y} ${-HFE_2_KFE_z}" rpy="0 0 0"/>
</xacro:unless>
<xacro:if value="${is_right}">
<origin xyz="0 ${-HFE_2_KFE_y} ${-HFE_2_KFE_z}" rpy="0 0 0"/>
</xacro:if>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}_LOWER_LEG">
<!-- LOWER LEG LINK INERTIAL -->
<xacro:unless value="${is_right}">
<!-- Left lower leg inertia -->
<inertial>
<origin xyz="0.0 0.00836718 -0.11591877" rpy="0 0 0"/>
<mass value="0.03117243"/>
<inertia ixx="0.00011487"
ixy="0.00000000"
ixz="0.00000000"
iyy="0.00011556"
iyz="-0.00000190"
izz="0.00000220"/>
</inertial>
</xacro:unless>
<xacro:if value="${is_right}">
<!-- Right lower leg inertia -->
<inertial>
<origin xyz="0.0 -0.00836718 -0.11591877" rpy="0 0 0"/>
<mass value="0.03117243"/>
<inertia ixx="0.00011487"
ixy="0.00000000"
ixz="0.00000000"
iyy="0.00011556"
iyz="0.00000190"
izz="0.00000220"/>
</inertial>
</xacro:if>
<!-- LOWER LEG LINK VISUAL -->
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<xacro:unless value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_lower_leg_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_lower_leg_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/lower_leg_200mm_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/lower_leg_200mm_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:if>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</visual>
<!-- LOWER LEG LINK COLLISION -->
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<xacro:unless value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_lower_leg_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_lower_leg_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${new_leg}">
<xacro:unless value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/lower_leg_200mm_left_side.${mesh_ext}"/>
</xacro:unless>
<xacro:if value="${is_right}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/lower_leg_200mm_right_side.${mesh_ext}"/>
</xacro:if>
</xacro:if>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<!-- END LOWER LEG LINK -->
<!-- KFE: Joint between the upper leg and the lower leg -->
<joint name="${prefix}_ANKLE" type="${ankle_joint_type}">
<parent link="${prefix}_LOWER_LEG"/>
<child link="${prefix}_FOOT"/>
<!-- Joint placement -->
<xacro:unless value="${is_right}">
<origin xyz="0 ${KFE_2_FOOT_y} ${-KFE_2_FOOT_z}" rpy="0 0 0"/>
</xacro:unless>
<xacro:if value="${is_right}">
<origin xyz="0 ${-KFE_2_FOOT_y} ${-KFE_2_FOOT_z}" rpy="0 0 0"/>
</xacro:if>
<xacro:if value="${has_passive_ankle}">
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
</xacro:if>
<!-- Limits (usefull?) -->
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="${prefix}_FOOT">
<!-- FOOT INERTIAL -->
<!-- This link is symmetrical left or right -->
<inertial>
<origin xyz="0 0 0.00035767" rpy="0 0 0"/>
<xacro:if value="${has_passive_ankle}">
<mass value="0.00010"/>
</xacro:if>
<xacro:unless value="${has_passive_ankle}">
<mass value="0.0"/>
</xacro:unless>
<inertia ixx="0.00000057"
ixy="0.0"
ixz="0.0"
iyy="0.00000084"
iyz="0.0"
izz="0.00000053"/>
</inertial>
<!-- FOOT VISUAL -->
<visual>
<xacro:if value="${has_passive_ankle}">
<origin xyz="0 0 -0.01" rpy="0 2.35 0."/>
</xacro:if>
<xacro:unless value="${has_passive_ankle}">
<origin xyz="0 0 0.0" rpy="0 0. 0."/>
</xacro:unless>
<geometry>
<xacro:if value="${has_passive_ankle}">
<cylinder length="0.06" radius="0.0085"/>
</xacro:if>
<xacro:unless value="${has_passive_ankle}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_foot.${mesh_ext}"/>
</xacro:unless>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</visual>
<!-- FOOT COLLISION -->
<collision>
<xacro:if value="${has_passive_ankle}">
<origin xyz="0 0 -0.01" rpy="0 2.35 0."/>
</xacro:if>
<xacro:unless value="${has_passive_ankle}">
<origin xyz="0 0 0.0" rpy="0 0. 0."/>
</xacro:unless>
<geometry>
<xacro:if value="${has_passive_ankle}">
<cylinder length="0.06" radius="0.0085"/>
</xacro:if>
<xacro:unless value="${has_passive_ankle}">
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_foot.${mesh_ext}"/>
</xacro:unless>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="4.0"/>
<restitution value="0.0"/>
</contact>
</link>
<!-- END LOWER LEG LINK -->
</xacro:macro>
</robot>
\ No newline at end of file
<?xml version="1.0"?>
<!-- Revolute-Revolute Manipulator -->
<?xml version="1.0" ?>
<!--
Copied and modified from ROS2 example -
https://github.com/ros-controls/ros2_control_demos/blob/master/ros2_control_demo_description/rrbot_description/urdf/rrbot.urdf.xacro
Copied from ODRI -
https://github.com/open-dynamic-robot-initiative/robot_properties_bolt/blob/master/src/robot_properties_bolt/resources/xacro/bolt.xacro
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="bolt">
<xacro:arg name="prefix" default="" />
<!-- Import RRBot macro -->
<xacro:include filename="$(find ros2_description_bolt)/urdf/system_bolt_description.urdf.xacro" />
<robot name="bolt"
<!-- Import Rviz colors -->
<xacro:include filename="$(find ros2_description_bolt)/gazebo/system_bolt.materials.xacro" />
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<!-- Import RRBot ros2_control description -->
<xacro:include filename="$(find ros2_description_bolt)/ros2_control/system_bolt.ros2_control.xacro" />
<xacro:macro name="bolt_full" params="mesh_ext color_name color opacity new_leg has_passive_ankle">
<!-- Used for fixing robot -->
<link name="world"/>
<gazebo reference="world">
<static>true</static>
</gazebo>
<!-- This file is based on: https://atlas.is.localnet/confluence/display/AMDW/Quadruped+URDF+Files -->
<link name="base_link">
<!-- BASE LINK INERTIAL -->
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.61436936"/>
<!-- The base is extremely symmetrical. -->
<inertia ixx="0.00578574" ixy="0.0" ixz="0.0"
iyy="0.01938108" iyz="0.0"
izz="0.02476124"
/>
</inertial>
<!-- BASE LINK VISUAL -->
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://ros2_description_bolt/meshes/${mesh_ext}/bolt_body.${mesh_ext}"/>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</visual>
<!-- BASE LINK COLLISION -->
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://ros2_description_bolt/meshes/${mesh_ext}/bolt_body.${mesh_ext}"/>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link> <!-- END BASE LINK -->
<xacro:system_bolt parent="world" prefix="$(arg prefix)">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:system_bolt>
<!-- Include the legs -->
<xacro:include filename="leg.xacro"/>
<xacro:system_bolt_ros2_control
name="Bolt" prefix="$(arg prefix)" />
<!-- Include the front left leg -->
<xacro:leg
prefix="FL"
is_front="true"
is_right="false"
has_side_motion="true"
mesh_ext="${mesh_ext}"
color_name="${color_name}"
color="${color}"
opacity="${opacity}"
new_leg="${new_leg}"
has_passive_ankle="${has_passive_ankle}"/>
<!-- Include the front right leg -->
<xacro:leg
prefix="FR"
is_front="true"
is_right="true"
has_side_motion="true"
mesh_ext="${mesh_ext}"
color_name="${color_name}"
color="${color}"
opacity="${opacity}"
new_leg="${new_leg}"
has_passive_ankle="${has_passive_ankle}"/>
</xacro:macro>
</robot>
<!--
Copied from ODRI -
https://github.com/open-dynamic-robot-initiative/robot_properties_bolt/blob/master/src/robot_properties_bolt/resources/xacro/bolt.xacro
-->
<?xml version="1.0" ?>
<robot name="bolt"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<xacro:macro name="bolt_full" params="mesh_ext color_name color opacity new_leg has_passive_ankle">
<!-- This file is based on: https://atlas.is.localnet/confluence/display/AMDW/Quadruped+URDF+Files -->
<link name="base_link">
<!-- BASE LINK INERTIAL -->
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.61436936"/>
<!-- The base is extremely symmetrical. -->
<inertia ixx="0.00578574" ixy="0.0" ixz="0.0"
iyy="0.01938108" iyz="0.0"
izz="0.02476124"
/>
</inertial>
<!-- BASE LINK VISUAL -->
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://robot_properties_bolt/resources/meshes/${mesh_ext}/bolt_body.${mesh_ext}"/>
</geometry>
<material name="${color_name}">
<color rgba="${color} ${opacity}"/>
</material>