123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112 |
- <?xml version="1.0"?>
- <robot
- xmlns:xacro="http://www.ros.org/wiki/xacro" name="hector_multisensor_head">
- <xacro:include filename="$(find hector_xacro_tools)/urdf/inertia_tensors.urdf.xacro"/>
- <xacro:include filename="$(find hector_sensors_description)/urdf/hokuyo_utm30lx.urdf.xacro" />
- <xacro:property name="M_PI" value="3.14159265359"/>
- <xacro:macro name="spinning_sensor_mount_macro" params="parent name scaling *origin">
- <!-- <link name="${name}_link">
- <inertial>
- <mass value="0.8"/>
- <inertia ixx="0.0025" ixy="0.0" ixz="0.0001" iyy="0.0013" iyz="0.0" izz="0.0026"/>
- </inertial>
- <collision name="collision">
- <xacro:insert_block name="origin"/>
- <geometry>
- <mesh filename="package://hector_components_description/meshes/hector_multisensor_head/multisensor_head_collision.stl" scale="${scaling} ${scaling} ${scaling}"/>
- </geometry>
- </collision>
- <visual>
- <xacro:insert_block name="origin"/>
- <geometry>
- <mesh filename="package://hector_components_description/meshes/hector_multisensor_head/multisensor_head.stl" scale="${scaling} ${scaling} ${scaling}"/>
- </geometry>
- </visual>
- </link>-->
- <joint name="${name}_spin_joint_fixed" type="fixed">
- <!--<origin xyz="0.061 0.0 0.134" rpy="0 0 0"/>-->
- <xacro:insert_block name="origin"/>
- <parent link="${parent}" />
- <child link="${name}_lidar_mount_link_fixed"/>
- <axis xyz="1 0 0" rpy="0 0 0"/>
- </joint>
- <link name="${name}_lidar_mount_link_fixed">
- </link>
- <joint name="${name}_spin_joint" type="continuous">
- <!--<origin xyz="0.061 0.0 0.134" rpy="0 0 0"/>-->
- <xacro:insert_block name="origin"/>
- <parent link="${parent}" />
- <child link="${name}_lidar_mount_link" />
- <axis xyz=" 0 0 1" />
- <limit effort="1000" velocity="100" />
- <joint_properties damping="500.0" friction="200.0" />
- </joint>
- <link name="${name}_lidar_mount_link">
- <xacro:inertial_sphere_with_pose mass="0.1" diameter="0.03">
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- </xacro:inertial_sphere_with_pose>
- <!-- Visualize collision cylinder
- <visual>
- <origin xyz="-0.01 0 0.01" rpy="0 ${M_PI/2} 0"/>
- <geometry>
- <cylinder radius="0.05" length="0.12" />
- </geometry>
- </visual>-->
-
- <!-- Visualize mesh data for checking LIDAR positioning-->
- <!--
- <visual>
- <origin xyz="-0.0 0 0.0" rpy="0 0 ${M_PI*0.5}"/>
- <geometry>
- <mesh filename="package://argo_tracker_description/meshes/argo_tracker_lidar_assembly.stl"/>
- </geometry>
- <material name="DarkGrey">
- <color rgba="0.3 0.3 0.3 1"/>
- </material>
- </visual>
- -->
-
- <collision>
- <origin xyz="0.0 0 0.08" rpy="0 0 0"/>
- <geometry>
- <cylinder radius="0.1" length="0.185" />
- </geometry>
- </collision>
- </link>
- <xacro:hokuyo_utm30lx name="${name}_pitch_hokuyo_laser" parent="${name}_lidar_mount_link" ros_topic="/spin_laser/pitch_scan_gazebo" update_rate="80" ray_count="1040" min_angle="-130" max_angle="130">
- <xacro:insert_block name="pitch_lidar_calibration" />
- </xacro:hokuyo_utm30lx>
-
- <xacro:hokuyo_utm30lx name="${name}_vertical_hokuyo_laser" parent="${name}_lidar_mount_link" ros_topic="/spin_laser/vertical_scan_gazebo" update_rate="80" ray_count="1040" min_angle="-130" max_angle="130">
- <xacro:insert_block name="vertical_lidar_calibration" />
- </xacro:hokuyo_utm30lx>
-
- <xacro:joint_standard_transmission name="${name}_spin_joint"/>
-
- <gazebo reference="${name}_spin_joint">
- <implicitSpringDamper>1</implicitSpringDamper>
- </gazebo>
-
- <gazebo>
- <!-- ros_control plugin -->
- <plugin name="gazebo_ros_control_select_joints" filename="libgazebo_ros_control_select_joints.so">
- <robotNamespace>spin_lidar_control</robotNamespace>
- <joints>spin_lidar_spin_joint</joints>
- </plugin>
- </gazebo>
- <!-- <xacro:asus_camera name="${name}_cam" parent="${name}_link">
- <origin xyz="0.065 0.0 0.23" rpy="0 0 0"/>
- </xacro:asus_camera> -->
- <!-- <gazebo reference="${name}_spinning_lidar_root_link"><material>Gazebo/Grey</material></gazebo><gazebo reference="${name}_spinning_lidar_spin_link"><material>Gazebo/Grey</material></gazebo> -->
- </xacro:macro>
- </robot>
|