Skip to content
Snippets Groups Projects
Commit e84c39a4 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Add mesh, urdf and launch files

parent d0f0e826
No related branches found
No related tags found
No related merge requests found
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="name" default="dabo"/>
<arg name="model" default="dabo"/>
<group ns="$(arg name)">
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find iri_dabo_description)/urdf/$(arg model).xacro' name:=$(arg name)" />
<node pkg="robot_state_publisher" type="state_publisher" name="state_publisher">
<param name="tf_prefix" type="string" value="/$(arg name)"/>
<param name="publish_frequency" type="double" value="20.0"/>
</node>
<!--
<node pkg="joint_state_publisher"
type="joint_state_publisher"
name="joint_state_publisher">
<param name="use_gui" value="true"/>
<remap from="$(arg name)/joint_states" to="$(arg name)/joint_states/"/>
<remap from="$(arg name)/robot_description" to="$(arg name)/robot_description/"/>
</node>
-->
</group>
<!--
<include file="$(find iri_segway_rmp200_description)/launch/wheel_static_transform.launch">
<arg name="name" value="$(arg name)"/>
</include>
-->
<include file="$(find iri_segway_rmp200_description)/launch/caster_wheels_static_transform.launch">
<arg name="name" value="$(arg name)"/>
</include>
</launch>
\ No newline at end of file
source diff could not be displayed: it is too large. Options to address this: view the blob.
File added
File added
source diff could not be displayed: it is too large. Options to address this: view the blob.
<?xml version="1.0"?>
<root xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="body" params="name parent">
<link name="body">
<visual>
<origin xyz="0 0 -0.48" rpy="0 0 0"/>
<geometry>
<mesh filename="package://iri_dabo_description/meshes/body.dae"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001"/>
</inertial>
</link>
<joint name="${parent}2body_joint" type="fixed">
<parent link="${parent}"/>
<child link="body"/>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<axis xyz="0 0 1"/>
</joint>
</xacro:macro>
</root>
<?xml version="1.0"?>
<robot name="dabo" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="name" default="dabo"/>
<xacro:include filename="$(find iri_segway_rmp200_description)/urdf/segway_rmp200.xacro" />
<xacro:segway_rmp200 name="$(arg name)" sim_config="$(find iri_dabo_gazebo)/config/dabo_sim_config.yaml"/>
<xacro:include filename="$(find iri_segway_rmp200_description)/urdf/caster_support_wheels.xacro" />
<xacro:caster_support_wheels/>
<xacro:include filename="$(find iri_dabo_description)/urdf/body.xacro" />
<xacro:body name="$(arg name)" parent="top_plate"/>
<xacro:include filename="$(find iri_dabo_description)/urdf/sensors.xacro" />
<xacro:sensors name="$(arg name)" parent="base_link"/>
</robot>
\ No newline at end of file
<?xml version="1.0"?>
<root xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find iri_hokuyo_laser2d_description)/urdf/hokuyo_laser2d.xacro" />
<xacro:macro name="sensors" params="name parent">
<xacro:property name="laser_config" value="$(find iri_dabo_gazebo)/config/hokuyo_utm30lx.yaml"/>
<xacro:hokuyo_laser2d name="front" prefix="${name}" parent="${parent}" mesh_resolution="low_res" model="utm30lx" config_file="${laser_config}">
<origin xyz="0.28 0.0 0.15" rpy="0 0 0" />
</xacro:hokuyo_laser2d>
<xacro:hokuyo_laser2d name="rear" prefix="${name}" parent="${parent}" mesh_resolution="low_res" model="utm30lx" config_file="${laser_config}">
<origin xyz="-0.28 0.0 0.15" rpy="0 0 3.14159" />
</xacro:hokuyo_laser2d>
</xacro:macro>
</root>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment