Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding a URDF for Xsens MTi #86

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
165 changes: 165 additions & 0 deletions config/xsens_urdf_check.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 775
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679016
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.0299999993
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: 1
Class: rviz/RobotModel
Collision Enabled: false
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_link:
Alpha: 1
Show Axes: false
Show Trail: false
imu:
Alpha: 1
Show Axes: false
Show Trail: false
imu_base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
imu:
Value: true
imu_base_link:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
imu_base_link:
imu:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Topic: /initialpose
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 0.512066483
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.0500000007
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.00999999978
Pitch: 0.89539814
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 2.60539675
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1056
Hide Left Dock: false
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000396000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 1855
X: 65
Y: 24
14 changes: 14 additions & 0 deletions launch/xsens_urdf_check.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<launch>

<arg name="model" default="$(find xsens_driver)/urdf/xsens_mti_example.urdf"/>
<arg name="gui" default="False" />
<arg name="rvizconfig" default="$(find xsens_driver)/config/xsens_urdf_check.rviz" />


<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />

<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" />

</launch>
72 changes: 72 additions & 0 deletions urdf/xsens_mti.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
<?xml version="1.0"?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:property name="M_PI" value="3.1415926535897931" />

<xacro:macro name="imu" params="name parent *origin">
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_base_link"/>
</joint>

<link name="${name}_base_link">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
</inertial>

<visual>
<origin xyz="0 0 ${0.0077+0.023/2}" rpy="0 0 0" />
<geometry>
<box size="0.058 0.0378 0.023" />
</geometry>
<material name="${name}_orange"/>
</visual>


<visual>
<origin xyz="0 0 ${0.0077/2}" rpy="0 0 0" />
<geometry>
<box size="0.0587 0.0506 0.0077" />
</geometry>
<material name="${name}_silver"/>
</visual>

<visual>
<origin xyz="-${0.058/2+0.005} 0 ${0.0077+0.023/2}" rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder length="0.01" radius="0.004" />
</geometry>
<material name="${name}_silver"/>
</visual>
<collision>
<origin xyz="0 0 ${0.0077/2}" rpy="0 0 0" />
<geometry>
<box size="0.0587 0.0506 0.0077" />
</geometry>
</collision>
</link>

<joint name="${name}_sensor_joint" type="fixed">
<origin xyz="${0.02935-0.012} ${.029-.0229} ${0.0095}" rpy="0.0 0.0 0.0" />
<parent link="${name}_base_link" />
<child link="${name}"/>
</joint>

<link name="${name}"/>

<material name="${name}_silver">
<color rgba="0.753 0.753 0.753 1"/>
</material>

<material name="${name}_orange">
<color rgba="1.0 0.647 0.0 1"/>
</material>


</xacro:macro>

</robot>
14 changes: 14 additions & 0 deletions urdf/xsens_mti_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<robot
name="xsens_test" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />
<link
name="base_link">

</link>

<xacro:include filename="$(find seabed_drivers)/urdf/xsens_mti.urdf.xacro"/>
<imu parent="base_link" name="imu">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
</imu>

</robot>