Skip to content

mesh_rotation

Jennifer Buehler edited this page May 3, 2019 · 5 revisions

A common issue is the rotation of meshes, especially if you are using .dae (collada) files, which often have their "up" vector defined as the Y axis, while URDF defines the up vector as z axis.

This issue will become apparent if the robot parts are off when viewed with urdf_viewer or the files produced by urdf2inventor. To fix this issue, you can rotate all "visuals" (all meshes) with a parameter. The easiest is to use a launch file, adjusting parameters visual_corr_axis_x/y/z/angle as described in the following.

For urdf_viewer

Run the launch file with roslaunch <your-package> urdf_viewer.launch

<launch>
    <arg name="urdf_file" default=YOUR_URDF_FILE/>

    # start the display from the given link name. Set to "root" for
    # displaying from root, or set to the name of the link otherwise
    <arg name="from_link" default="root"/>

    # join fixed links before displaying URDF
    <arg name="join_fixed_links" default="false"/>

    # rotate all axes to z before displaying URDF
    <arg name="rotate_axes_z" default="false"/>
   
    # set to true to display axes of local joint coordinate systems 
    <arg name="display_axes" default="false"/>
    <arg name="axes_radius" default="0.001"/>
    <arg name="axes_length" default="0.015"/>
    
    # An axis and angle (degrees) can be specified which will transform *all*
    # visuals (not links, but their visuals!) within their local coordinate system.
    # This can be used to correct transformation errors which may have been 
    # introduced in converting meshes from one format to the other, losing orientation information
    # For example, .dae has an "up vector" definition which may have been ignored.
    <arg name="visual_corr_axis_x" default="1"/>
    <arg name="visual_corr_axis_y" default="0"/>
    <arg name="visual_corr_axis_z" default="0"/>
    <arg name="visual_corr_axis_angle" default="0"/>

    <node name="urdf_viewer" pkg="urdf_viewer" type="urdf_viewer_node" respawn="false"
        output="screen" args="$(arg urdf_file) $(arg from_link)">
        <param name="join_fixed_links" value="$(arg join_fixed_links)"/>
        <param name="rotate_axes_z" value="$(arg rotate_axes_z)"/>
        <param name="display_axes" value="$(arg display_axes)"/>
        <param name="axes_radius" value="$(arg axes_radius)"/>
        <param name="axes_length" value="$(arg axes_length)"/>
        <param name="visual_corr_axis_x" value="$(arg visual_corr_axis_x)"/>
        <param name="visual_corr_axis_y" value="$(arg visual_corr_axis_y)"/>
        <param name="visual_corr_axis_z" value="$(arg visual_corr_axis_z)"/>
        <param name="visual_corr_axis_angle" value="$(arg visual_corr_axis_angle)"/>
    </node>
</launch>

For urdf2inventor

Run the following launch file with roslaunch <your-package> urdf2inventor.launch

urdf2inventor.launch:

<launch>
    <arg name="output_dir"/>
    <arg name="urdf_file" default="YOUR_URDF_FILE"/>

    # factor to scale the model by 
    <arg name="scale_factor" default="1"/>

    # An axis and angle (degrees) can be specified which will transform *all*
    # visuals (not links, but their visuals!) within their local coordinate system.
    # This can be used to correct transformation errors which may have been 
    # introduced in converting meshes from one format to the other, losing orientation information
    # For example, .dae has an "up vector" definition which may have been ignored.
    <arg name="visual_corr_axis_x" default="1"/>
    <arg name="visual_corr_axis_y" default="0"/>
    <arg name="visual_corr_axis_z" default="0"/>
    <arg name="visual_corr_axis_angle" default="0"/>

     <node name="urdf2inventor" pkg="urdf2inventor" type="urdf2inventor_node" respawn="false"
        output="screen" args="$(arg urdf_file) $(arg output_dir)">
		<param name="scale_factor" value="$(arg scale_factor)"/>
        <param name="visual_corr_axis_x" value="$(arg visual_corr_axis_x)"/>
        <param name="visual_corr_axis_y" value="$(arg visual_corr_axis_y)"/>
        <param name="visual_corr_axis_z" value="$(arg visual_corr_axis_z)"/>
        <param name="visual_corr_axis_angle" value="$(arg visual_corr_axis_angle)"/>
    </node>
</launch>
Clone this wiki locally