report 30/09

This commit is contained in:
Ly PECHVATTANA 2023-09-29 21:57:00 -07:00
parent 91fe3eac74
commit 68b4d32ea9
4 changed files with 36 additions and 10 deletions

View File

@ -1,6 +1,7 @@
<launch>
<param name="robot_description" command="$(find xacro)/xacro '$(find agv_description)/urdf/agv.urdf.xacro'" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher">
</node>
</launch>

View File

@ -75,7 +75,7 @@
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.175 0" rpy="-${pi/2} 0 0" />
<origin xyz="0 0.134 0.0375" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
@ -101,14 +101,12 @@
</gazebo>
<!-- RIGHT WHEEL LINK -->
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 -0.175 0" rpy="${pi/2} 0 0" />
<origin xyz="0 -0.134 0.0375" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
</joint>
@ -139,20 +137,20 @@
<joint name="caster_wheel_joint" type="fixed">
<parent link="chassis"/>
<child link="caster_wheel"/>
<origin xyz="0.24 0 0"/>
<origin xyz="0.24 0 0.02"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.05"/>
<sphere radius="0.02"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
<sphere radius="0.02"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="0.05">
@ -161,7 +159,7 @@
</link>
<gazebo reference="caster_wheel">
<material>Gazebo/Black</material>
<material>Gazebo/Red</material>
<mu1 value="0.001"/>
<mu2 value="0.001"/>
</gazebo>

View File

@ -6,7 +6,7 @@
<joint name="laser_joint" type="fixed">
<parent link="chassis"/>
<child link="laser_frame"/>
<origin xyz="0.1 0 0.175" rpy="0 0 0"/>
<origin xyz="0.2 0 0.14" rpy="0 0 0"/>
</joint>
<link name="laser_frame">

View File

@ -0,0 +1,27 @@
<?xml version="1.0"?>
<launch>
<arg name="trajectory_source_frame_name" default="/base_link"/>
<arg name="trajectory_update_rate" default="4"/>
<arg name="trajectory_publish_rate" default="0.25"/>
<arg name="map_file_path" default="$(find hector_geotiff)/maps"/>
<arg name="map_file_base_name" default="hector_slam_map"/>
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server" output="screen">
<param name="target_frame_name" type="string" value="/map" />
<param name="source_frame_name" type="string" value="$(arg trajectory_source_frame_name)" />
<param name="trajectory_update_rate" type="double" value="$(arg trajectory_update_rate)" />
<param name="trajectory_publish_rate" type="double" value="$(arg trajectory_publish_rate)" />
</node>
<node pkg="hector_geotiff" type="geotiff_node" name="hector_geotiff_node" output="screen" launch-prefix="nice -n 15">
<remap from="map" to="/dynamic_map" />
<param name="map_file_path" type="string" value="$(arg map_file_path)" />
<param name="map_file_base_name" type="string" value="$(arg map_file_base_name)" />
<param name="geotiff_save_period" type="double" value="0" />
<param name="draw_background_checkerboard" type="bool" value="true" />
<param name="draw_free_space_grid" type="bool" value="true" />
<param name="plugins" type="string" value="hector_geotiff_plugins/TrajectoryMapWriter" />
</node>
</launch>