mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
saved work, odom not right, to be fixed
This commit is contained in:
31
scout_description/urdf/onboard_sensors.urdf
Normal file
31
scout_description/urdf/onboard_sensors.urdf
Normal file
@@ -0,0 +1,31 @@
|
||||
<robot>
|
||||
<joint name="hokuyo_joint" type="fixed">
|
||||
<origin xyz="0.26 0 0.3" rpy="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<axis xyz="0 1 0" />
|
||||
<child link="hokuyo_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- Hokuyo Laser -->
|
||||
<link name="hokuyo_link">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.1 0.1 0.1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/hokuyo.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<mass value="1e-5" />
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
|
||||
</inertial>
|
||||
</link>
|
||||
</robot>
|
||||
@@ -32,7 +32,7 @@ Reference:
|
||||
<!-- kp spring constant, kd damping constant -->
|
||||
<gazebo>
|
||||
<mu1 value="1.0"/>
|
||||
<mu2 value="0.9"/>
|
||||
<mu2 value="1.0"/>
|
||||
<kp value="10000000.0" />
|
||||
<kd value="1.0" />
|
||||
<fdir1 value="1 0 0"/>
|
||||
@@ -40,6 +40,43 @@ Reference:
|
||||
<maxContacts value="64"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- hokuyo -->
|
||||
<gazebo reference="hokuyo_link">
|
||||
<sensor type="ray" name="head_hokuyo_sensor">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>40</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>720</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-1.570796</min_angle>
|
||||
<max_angle>1.570796</max_angle>
|
||||
</horizontal>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.10</min>
|
||||
<max>30.0</max>
|
||||
<resolution>0.01</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<!-- Noise parameters based on published spec for Hokuyo laser
|
||||
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
|
||||
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
|
||||
reading. -->
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.01</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
|
||||
<topicName>/scan</topicName>
|
||||
<frameName>hokuyo_link</frameName>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- <gazebo>
|
||||
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
|
||||
<updateRate>100.0</updateRate>
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
|
||||
<xacro:arg name="robot_namespace" default="/" />
|
||||
<xacro:arg name="urdf_extras" default="empty.urdf" />
|
||||
<xacro:arg name="onboard_sensors" default="true" />
|
||||
|
||||
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type1.xacro" />
|
||||
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type2.xacro" />
|
||||
@@ -52,6 +53,14 @@
|
||||
<child link="chassis_link" />
|
||||
</joint> -->
|
||||
|
||||
<link name="base_footprint"/>
|
||||
|
||||
<joint name="base_footprint_joint" type="fixed">
|
||||
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="base_footprint" />
|
||||
</joint>
|
||||
|
||||
<link name="inertial_link">
|
||||
<inertial>
|
||||
<mass value="40" />
|
||||
@@ -93,6 +102,13 @@
|
||||
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
|
||||
</xacro:scout_wheel_type2>
|
||||
|
||||
<!-- Onboard sensors -->
|
||||
<xacro:if value="$(arg onboard_sensors)">
|
||||
<!-- <xacro:include filename="$(find scout_description)/urdf/onboard_sensors.xacro" />
|
||||
<xacro:sensor_frame /> -->
|
||||
<xacro:include filename="$(find scout_description)/urdf/onboard_sensors.urdf" />
|
||||
</xacro:if>
|
||||
|
||||
<!-- Additional definitions -->
|
||||
<xacro:include filename="$(arg urdf_extras)" />
|
||||
|
||||
|
||||
Reference in New Issue
Block a user