Commit ab88f534 authored by Simon Markus Haller-Seeber's avatar Simon Markus Haller-Seeber
Browse files

Some MoveIT config to easier regenerate it. Addtional Example launchfile for...

Some MoveIT config to easier regenerate it. Addtional Example launchfile for the LSS 4 DoF ROS Control
parent 1210c470
<?xml version="1.0"?>
<launch>
<arg name="enabled" default="true"/>
<!-- GDB functionality -->
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<!-- Load configuration settings -->
<rosparam file="$(find lss_4dof_hw)/config/names.yaml" command="load"/>
<rosparam file="$(find lss_4dof_hw)/config/hardware_interfaces.yaml" command="load"/>
<rosparam file="$(find lss_4dof_hw)/config/controllers.yaml" command="load"/>
<!-- Load hardware interface -->
<group if="$(arg enabled)">
<node if="$(arg enabled)" name="lss_4dof_hw" pkg="lss_4dof_hw" type="lss_4dof_hw_node" output="screen" launch-prefix="$(arg launch_prefix)"/>
</group>
</launch>
......@@ -3,5 +3,5 @@
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find minibot)/model/minibot_in_world.urdf.xacro"/>
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" if="$(arg use_gui)" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" unless="$(arg use_gui)" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
</launch>
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="Eddie">
<xacro:include filename="$(find minibot)/model/minibot.urdf.xacro" />
<xacro:include filename="$(find minibot)/model/minibot.urdf2.xacro" />
<link name="world" />
<link name="base_link" />
<xacro:minibot name="minibot" parent="world">
<xacro:minibot name="minibot" parent="base_link">
<origin xyz="0.0 0.0 0.0"/>
</xacro:minibot>
<joint name="world_joint" type="fixed">
......
<?xml version="1.0" encoding="utf-8"?>
<robot name="Minibot">
<material name="SpheroRVR/White">
<color rgba="1 1 1 1.0"/>
</material>
<material name="SpheroRVR/DarkGrey">
<color rgba="0.3 0.3 0.3 1.0"/>
</material>
<material name="SpheroRVR/LightGrey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
<material name="SpheroRVR/Black">
<color rgba="0 0 0 1.0"/>
</material>
<material name="SpheroRVR/Grey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<material name="SpheroRVR/Blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<!-- NOTE: inertia values are approximated using meshlab and only using the significant elements -->
<!-- from http://answers.ros.org/question/11350/is-there-any-way-to-calculate-inertial-property-of-a-robot-to-simulate-it-in-gazebo/s
One general rule of thumb I use for checking my inertia tensors is: If total mass of the rigid body is m, and the dimension of the corresponding body is d, then check to see if ixx, iyy, izz are near m*(d/2)^2.
This is by no means correct, but a sanity check to make sure the moment of inertia are the right order of magnitudes, so the model behaves somewhat physically realistically.
-->
<material name="Arm/White">
<color rgba="1 1 1 1.0"/>
</material>
<material name="Arm/DarkGrey">
<color rgba="0.3 0.3 0.3 1.0"/>
</material>
<material name="Arm/LightGrey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
<material name="Arm/Black">
<color rgba="0 0 0 1.0"/>
</material>
<material name="Arm/Grey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<material name="Arm/Blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<!-- NOTE: inertia values are approximated using meshlab and only using the significant elements -->
<!-- from http://answers.ros.org/question/11350/is-there-any-way-to-calculate-inertial-property-of-a-robot-to-simulate-it-in-gazebo/s
One general rule of thumb I use for checking my inertia tensors is: If total mass of the rigid body is m, and the dimension of the corresponding body is d, then check to see if ixx, iyy, izz are near m*(d/2)^2.
This is by no means correct, but a sanity check to make sure the moment of inertia are the right order of magnitudes, so the model behaves somewhat physically realistically.
-->
<!-- The base fixed to its parent. -->
<joint name="battery_holder_link_lss_4dof_base_joint" type="fixed">
<origin rpy="0 0 1.57079632679" xyz="0.0 -0.0465 0.019"/>
<parent link="battery_holder_link"/>
<child link="lss_4dof_base_link"/>
</joint>
<link name="lss_4dof_base_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.009 0.0068 0"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Arm_Base.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Arm/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0 0.021"/>
<geometry>
<cylinder length="0.042" radius="0.055"/>
</geometry>
</collision>
</link>
<!-- 1-Axis -->
<joint name="lss_4dof_axis_1_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="204" lower="-3.14159265359" upper="3.14159265359" velocity="3.14159265359"/>
<safety_controller k_position="30" k_velocity="30" soft_lower_limit="-3.14159265359" soft_upper_limit="3.14159265359"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="lss_4dof_base_link"/>
<child link="lss_4dof_axis_1_link"/>
</joint>
<link name="lss_4dof_axis_1_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.016 0.016 0.0425"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Link_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Arm/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0 0.072"/>
<geometry>
<box size="0.04 0.027 0.07"/>
</geometry>
</collision>
</link>
<!-- 2-Axis -->
<joint name="lss_4dof_axis_2_joint" type="revolute">
<!-- add 0.0142 in z and sub 0.007 in y -->
<!-- <origin xyz="0.004 0.007 0.083" rpy="0 0 0"/> -->
<origin rpy="0 0 0" xyz="0 0.0 0.0955"/>
<axis xyz="1 0 0"/>
<limit effort="204" lower="-1.91986217719" upper="1.74532925199" velocity="3.14159265359"/>
<safety_controller k_position="30" k_velocity="30" soft_lower_limit="-1.91986217719" soft_upper_limit="1.74532925199"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="lss_4dof_axis_1_link"/>
<child link="lss_4dof_axis_2_link"/>
</joint>
<link name="lss_4dof_axis_2_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.004 -0.0148 -0.0125"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Link_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Arm/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0 0.087"/>
<geometry>
<box size="0.025 0.025 0.127"/>
</geometry>
</collision>
</link>
<!-- 3-Axis -->
<joint name="lss_4dof_axis_3_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.025 0.14"/>
<axis xyz="1 0 0"/>
<limit effort="204" lower="-0.523598775598" upper="3.10668606855" velocity="3.14159265359"/>
<safety_controller k_position="30" k_velocity="30" soft_lower_limit="-0.523598775598" soft_upper_limit="3.05432619099"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="lss_4dof_axis_2_link"/>
<child link="lss_4dof_axis_3_link"/>
</joint>
<link name="lss_4dof_axis_3_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.004 0.007 -0.013"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Link_3.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Arm/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0 0.087"/>
<geometry>
<box size="0.025 0.025 0.127"/>
</geometry>
</collision>
</link>
<!-- 4-Axis -->
<joint name="lss_4dof_axis_4_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0005 0.1628"/>
<axis xyz="1 0 0"/>
<limit effort="204" lower="-2.16420827247" upper="2.16420827247" velocity="3.14159265359"/>
<safety_controller k_position="30" k_velocity="30" soft_lower_limit="-2.09439510239" soft_upper_limit="2.09439510239"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="lss_4dof_axis_3_link"/>
<child link="lss_4dof_axis_4_link"/>
</joint>
<link name="lss_4dof_axis_4_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0135 0.0127 -0.0128"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Link_4.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Arm/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0 0.042"/>
<geometry>
<box size="0.06 0.03 0.04"/>
</geometry>
</collision>
</link>
<!-- Gripper -->
<joint name="lss_4dof_gripper_l" type="revolute">
<origin rpy="0 0 0" xyz="0.0155 -0.02 0.0505"/>
<axis xyz="0 1 0"/>
<limit effort="204" lower="-0.0349065850399" upper="1.308996939" velocity="3.14159265359"/>
<safety_controller k_position="30" k_velocity="30" soft_lower_limit="-0.0174532925199" soft_upper_limit="1.308996939"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="lss_4dof_axis_4_link"/>
<child link="lss_4dof_gripper_l_link"/>
</joint>
<joint name="lss_4dof_gripper_r" type="revolute">
<origin rpy="0 0 0" xyz="-0.010 -0.02 0.0505"/>
<mimic joint="lss_4dof_gripper_l" multiplier="-1" offset="0"/>
<axis xyz="0 1 0"/>
<limit effort="204" lower="-0.0349065850399" upper="1.308996939" velocity="3.14159265359"/>
<safety_controller k_position="30" k_velocity="30" soft_lower_limit="-0.0174532925199" soft_upper_limit="1.308996939"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="lss_4dof_axis_4_link"/>
<child link="lss_4dof_gripper_r_link"/>
</joint>
<link name="lss_4dof_gripper_l_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.008 -0.02 -0.012"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Gripper_L.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Arm/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 -0.002 0.035"/>
<geometry>
<box size="0.02 0.01 0.05"/>
</geometry>
</collision>
</link>
<link name="lss_4dof_gripper_r_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.0055 -0.02 -0.012"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Gripper_R.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Arm/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 -0.002 0.035"/>
<geometry>
<box size="0.02 0.01 0.05"/>
</geometry>
</collision>
</link>
<transmission name="lss_4dof_axis_1_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="lss_4dof_axis_1_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="lss_4dof_axis_1_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<transmission name="lss_4dof_axis_2_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="lss_4dof_axis_2_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="lss_4dof_axis_2_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<transmission name="lss_4dof_axis_3_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="lss_4dof_axis_3_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="lss_4dof_axis_3_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<transmission name="lss_4dof_axis_4_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="lss_4dof_axis_4_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="lss_4dof_axis_4_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<!-- The base fixed to its parent. -->
<joint name="base_link_sphero_rvr_base_joint" type="fixed">
<origin xyz="0.0 0.0 0.0"/>
<parent link="base_link"/>
<child link="sphero_rvr_base_link"/>
</joint>
<link name="sphero_rvr_base_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.017 -0.101 0.017"/>
<geometry>
<mesh filename="package://sphero_rvr_description/meshes/Sphero_Base.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="SpheroRVR/White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0 0.04"/>
<geometry>
<box size="0.2 0.13 0.06"/>
</geometry>
</collision>
</link>
<!-- Left Front/Rear Wheel -->
<joint name="sphero_rvr_wheel_fl_joint" type="continuous">
<origin rpy="0 90 0" xyz="0.059 0.09 0.03"/>
<axis xyz="0 1 0"/>
<limit effort="30" velocity="1.0"/>
<safety_controller k_position="15" k_velocity="10"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="sphero_rvr_base_link"/>
<child link="sphero_rvr_wheel_fl_link"/>
</joint>
<joint name="sphero_rvr_wheel_rl_joint" type="continuous">
<origin rpy="0 0 0" xyz="-0.059 0.09 0.03"/>
<mimic joint="sphero_rvr_wheel_fl_joint" multiplier="1" offset="0"/>
<axis xyz="0 1 0"/>
<limit effort="30" velocity="1.0"/>
<safety_controller k_position="15" k_velocity="10"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="sphero_rvr_base_link"/>
<child link="sphero_rvr_wheel_rl_link"/>
</joint>
<link name="sphero_rvr_wheel_fl_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.042 0 -0.033"/>
<geometry>
<mesh filename="package://sphero_rvr_description/meshes/Sphero_Wheel_L.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="SpheroRVR/White"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0.0 0 0.0"/>
<geometry>
<cylinder length="0.03" radius="0.033"/>
</geometry>
</collision>
</link>
<link name="sphero_rvr_wheel_rl_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.042 0 -0.033"/>
<geometry>
<mesh filename="package://sphero_rvr_description/meshes/Sphero_Wheel_L.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="SpheroRVR/White"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0.0 0 0.0"/>
<geometry>
<cylinder length="0.03" radius="0.033"/>
</geometry>
</collision>
</link>
<!-- Right Front/Rear Wheel -->
<joint name="sphero_rvr_wheel_fr_joint" type="continuous">
<origin rpy="0 90 0" xyz="0.059 -0.09 0.03"/>
<axis xyz="0 1 0"/>
<limit effort="30" velocity="1.0"/>
<safety_controller k_position="15" k_velocity="10"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="sphero_rvr_base_link"/>
<child link="sphero_rvr_wheel_fr_link"/>
</joint>
<joint name="sphero_rvr_wheel_rr_joint" type="continuous">
<origin rpy="0 0 0" xyz="-0.059 -0.09 0.03"/>
<mimic joint="sphero_rvr_wheel_fr_joint" multiplier="1" offset="0"/>
<axis xyz="0 1 0"/>
<limit effort="30" velocity="1.0"/>
<safety_controller k_position="15" k_velocity="10"/>
<dynamics damping="1.0" friction="1.0"/>
<parent link="sphero_rvr_base_link"/>
<child link="sphero_rvr_wheel_rr_link"/>
</joint>
<link name="sphero_rvr_wheel_fr_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.042 0 -0.033"/>
<geometry>
<mesh filename="package://sphero_rvr_description/meshes/Sphero_Wheel_R.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="SpheroRVR/White"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0.0 0 0.0"/>
<geometry>
<cylinder length="0.03" radius="0.033"/>
</geometry>
</collision>
</link>
<link name="sphero_rvr_wheel_rr_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.042 0 -0.033"/>
<geometry>
<mesh filename="package://sphero_rvr_description/meshes/Sphero_Wheel_R.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="SpheroRVR/White"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0.0 0 0.0"/>
<geometry>
<cylinder length="0.03" radius="0.033"/>
</geometry>
</collision>
</link>
<transmission name="sphero_rvr_wheel_fl_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="sphero_rvr_wheel_fl_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="sphero_rvr_wheel_fl_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<transmission name="sphero_rvr_wheel_fr_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="sphero_rvr_wheel_fr_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="sphero_rvr_wheel_fr_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<transmission name="sphero_rvr_wheel_rl_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="sphero_rvr_wheel_rl_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="sphero_rvr_wheel_rl_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<transmission name="sphero_rvr_wheel_rr_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="sphero_rvr_wheel_rr_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="sphero_rvr_wheel_rr_joint_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
</transmission>
<link name="base_link"/>
<joint name="sphero_rvr_battery_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0465 0.0885"/>
<parent link="sphero_rvr_base_link"/>
<child link="battery_holder_link"/>
</joint>
<link name="battery_holder_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="package://minibot/meshes/battery_holder.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 -0.045 0.0"/>
<geometry>
<box size="0.18 0.13 0.03"/>
</geometry>
</collision>
</link>
<joint name="jetson_protection_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0 0.039"/>
<parent link="lss_4dof_base_link"/>
<child link="jetson_protection_link"/>
</joint>
<link name="jetson_protection_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="package://minibot/meshes/jetson_protection.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.092 0.002"/>
<geometry>
<box size="0.11 0.068 0.003"/>
</geometry>
</collision>
</link>
<joint name="camera_mount_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0 0.0"/>
<parent link="lss_4dof_axis_4_link"/>
<child link="camera_mount_link"/>
</joint>
<link name="camera_mount_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 1.57079632679" xyz="0.0545 -0.0523 0.0385"/>
<geometry>
<mesh filename="package://minibot/meshes/realsense_mount.stl" scale="0.001 0.001 0.001"/>