Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
64 changes: 44 additions & 20 deletions rusty/launch/amcl.launch
Original file line number Diff line number Diff line change
@@ -1,27 +1,51 @@
<launch>
<!-- Arguments -->
<arg name="scan_topic" default="scan"/>
<arg name="initial_pose_x" default="0.0"/>
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_a" default="0.0"/>

<!-- Arguments -->
<arg name="scan_topic" default="scan"/>
<arg name="initial_pose_x" default="0.0"/>
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_a" default="0.0"/>
<!-- AMCL -->
<node pkg="amcl" type="amcl" name="amcl">


<!-- AMCL Node -->
<node name="amcl" pkg="amcl" type="amcl" output="screen">
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
<param name="gui_publish_rate" value="50.0"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="3000"/>
<param name="kld_err" value="0.02"/>
<param name="update_min_d" value="0.20"/>
<param name="update_min_a" value="0.20"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<param name="recovery_alpha_slow" value="0.00"/>
<param name="recovery_alpha_fast" value="0.00"/>
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
<param name="gui_publish_rate" value="50.0"/>

<remap from="scan" to="$(arg scan_topic)"/>
<param name="odom_model_type" value="diff-corrected"/>
<param name="odom_frame_id" value="odom"/>
<param name="base_frame_id" value="base_link"/>
<param name="global_frame_id" value="map"/>

</node>
<remap from="scan" to="$(arg scan_topic)"/>
<param name="laser_max_range" value="3.5"/>
<param name="laser_max_beams" value="180"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.5"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="laser_model_type" value="likelihood_field"/>


<param name="odom_model_type" value="diff"/>
<param name="odom_alpha1" value="0.1"/>
<param name="odom_alpha2" value="0.1"/>
<param name="odom_alpha3" value="0.1"/>
<param name="odom_alpha4" value="0.1"/>
<param name="odom_frame_id" value="scanmatch_odom"/>
<param name="base_frame_id" value="base_link"/>

<param name="tf_broadcast" value="true" />
<param name="base_frame_id" value="/base_link" />
<param name="global_frame_id" value="map" />
<param name="odom_frame_id" value="scanmatch_odom" />
<param name="use_map_topic" value="false" />
</node>
</launch>
16 changes: 13 additions & 3 deletions rusty/launch/move_base.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,17 +7,27 @@

<!-- move_base -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_global_planner" value="navfn/NavfnROS" />
<!--<param name="base_global_planner" value="navfn/NavfnROS" />
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS"/>
<rosparam file="$(find rusty)/params/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find rusty)/params/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find rusty)/params/local_costmap_params.yaml" command="load" />
<rosparam file="$(find rusty)/params/global_costmap_params.yaml" command="load" />
<rosparam file="$(find rusty)/params/move_base_params.yaml" command="load" />
<rosparam file="$(find rusty)/params/dwa_local_planner_params.yaml" command="load" />
<rosparam file="$(find rusty)/params/dwa_local_planner_params.yaml" command="load" />-->

<!-- ROBOT MOVE BASE -->
<param name="base_global_planner" value="navfn/NavfnROS" />
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS"/>
<rosparam file="$(find rusty)/robot_param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find rusty)/robot_param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find rusty)/robot_param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find rusty)/robot_param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find rusty)/robot_param/move_base_params.yaml" command="load" />
<rosparam file="$(find rusty)/robot_param/dwa_local_planner_params.yaml" command="load" />
<!--rosparam file="$(find rusty)/params/dwa_local_planner_params.yaml" command="load" /-->
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="odom" to="scanmatch_odom"/>

</node>
</launch>
12 changes: 9 additions & 3 deletions rusty/launch/navigation.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,19 +7,20 @@
<arg name="move_forward_only" default="false"/>

<!--MAP SERVER NODE-->
<arg name="map_file" default="$(find rusty)/maps/house.yaml"/>
<arg name="map_file" default="$(find rusty)/maps/first_slam.yaml"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />


<!-- AMCL -->
<include file="$(find rusty)/launch/amcl.launch"/>
<include file="$(find rusty)/launch/robot_localize.launch"/>

<!-- move_base -->
<include file="$(find rusty)/launch/move_base.launch">

<arg name="move_forward_only" value="$(arg move_forward_only)"/>
</include>
<rosparam command="load" file="$(find rusty)/config/location.yaml" />
<!--<rosparam command="load" file="$(find rusty)/config/location.yaml" />-->
<!-- rviz -->

<arg default="$(find rusty)/config/rusty_nav.rviz" name="rvizconfig"/>
Expand All @@ -29,4 +30,9 @@
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node args="-d $(arg rvizconfig)" name="rviz" pkg="rviz" required="true" type="rviz"/>


<!--static transform-->
<node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 base_link laser 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_to_map_broadcaster" args="0 0 0 0 0 0 map base_link 100"/>
<node pkg="tf" type="static_transform_publisher" name="map_nav_broadcaster" args="0 0 0 0 0 0 map odom 100"/>-->
</launch>
8 changes: 8 additions & 0 deletions rusty/launch/odomtransform.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<launch>

<node name="odomtransformer" pkg="lidarbot" type="odomtransformer.py" output="screen">
<param name="odom_input" value="/scanmatch_odom" />
<param name="tf_output" value="/base_link" />
</node>

</launch>
55 changes: 55 additions & 0 deletions rusty/launch/robot_localize.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
<launch>
<arg name="tf_map_scanmatch_transform_frame_name" default="scanmatcher_frame"/>
<arg name="base_frame" default="base_link"/>
<arg name="odom_frame" default="base_link"/>
<!-- Change below!! Used to be true. -->
<arg name="pub_map_odom_transform" default="false"/>
<arg name="scan_subscriber_queue_size" default="5"/>
<arg name="scan_topic" default="scan"/>
<arg name="map_size" default="2048"/>
<arg name="pub_odometry" default="true"/>

<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<param name="pub_odometry" value="$(arg pub_odometry)"/>

<!-- Frame names -->
<remap from="map" to="mapcurrent" />
<param name="map_frame" value="mapcurrent_frame" />
<param name="base_frame" value="$(arg base_frame)" />
<param name="odom_frame" value="$(arg odom_frame)" />

<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>

<!-- Map size / start point -->
<param name="map_resolution" value="0.050"/>
<param name="map_size" value="$(arg map_size)"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="map_multi_res_levels" value="2" />

<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.9" />
<param name="map_update_distance_thresh" value="0.4"/>
<param name="map_update_angle_thresh" value="0.06" />
<param name="laser_z_min_value" value = "-1.0" />
<param name="laser_z_max_value" value = "1.0" />

<!-- Advertising config -->
<param name="advertise_map_service" value="true"/>

<param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
<param name="scan_topic" value="$(arg scan_topic)"/>

<!-- Debug parameters -->
<!--
<param name="output_timing" value="false"/>
<param name="pub_drawings" value="true"/>
<param name="pub_debug_output" value="true"/>
-->
<param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)" />
</node>
</launch>
71 changes: 71 additions & 0 deletions rusty/launch/rusty_slam.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
<launch>
<!-- Arguments -->
<arg name="model" default="$(find rusty_description)/urdf/rusty.xacro"/>
<arg name="configuration_basename" default="/scan"/>

<arg name="odom_frame" default="base_link"/>
<arg name="base_frame" default="base_link"/>
<arg name="scan_subscriber_queue_size" default="5"/>
<arg name="scan_topic" default="scan"/>
<arg name="map_size" default="2048"/>
<arg name="pub_map_odom_transform" default="true"/>

<arg name="tf_map_scanmatch_transform_frame_name" default="scan"/>

<!--static transform-->
<node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 base_link laser 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_to_map_broadcaster" args="0 0 0 0 0 0 map base_link 100"/>
<node pkg="tf" type="static_transform_publisher" name="map_nav_broadcaster" args="0 0 0 0 0 0 map odom 100"/>-->

<!-- Hector mapping -->
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<!-- Frame names -->
<param name="map_frame" value="map" />
<param name="odom_frame" value="$(arg odom_frame)" />
<param name="base_frame" value="$(arg base_frame)" />

<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="pub_map_scanmatch_transform" value="true" />
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
<param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)" />

<!-- Map size / start point -->
<param name="map_resolution" value="0.050"/>
<param name="map_size" value="$(arg map_size)"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="map_multi_res_levels" value="2" />

<!-- Map update parameters -->
<param name="update_factor_free" value="0.05"/>
<param name="update_factor_occupied" value="0.9" />
<param name="map_update_distance_thresh" value="0.1"/>
<param name="map_update_angle_thresh" value="0.04" />
<param name="map_pub_period" value="2" />
<param name="laser_z_min_value" value= "-0.1" />
<param name="laser_z_max_value" value= "0.1" />
<param name="laser_min_dist" value="0.12" />
<param name="laser_max_dist" value="3.5" />

<!-- Advertising config -->
<param name="advertise_map_service" value="true"/>
<param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
<param name="scan_topic" value="$(arg scan_topic)"/>

<!-- Debug parameters -->
<!--
<param name="output_timing" value="false"/>
<param name="pub_drawings" value="true"/>
<param name="pub_debug_output" value="true"/>
-->
</node>
<!--RVIZ-->
<arg default="true" name="gui"/>
<arg default="$(find rover)/launch/urdf.rviz" name="rvizconfig"/>
<param command="$(find xacro)/xacro $(arg model)" name="robot_description"/>

<node args="-d $(arg rvizconfig)" name="rviz" pkg="rviz" required="true" type="rviz"/>

</launch>
23 changes: 23 additions & 0 deletions rusty/robot_param/base_local_planner.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
controller_frequency: 10

TrajectoryPlannerROS:
max_vel_x: 1.0
min_vel_x: -0.1
max_vel_theta: 1.57

min_in_place_vel_theta: 0.314

acc_lim_theta: 3.14
acc_lim_x: 2.0
acc_lim_y: 2.0

sim_time: 1.0

vx_samples: 5.0
vtheta_samples: 10.0

pdist_scale: 0.6 #0.6
gdist_scale: 0.8 #0.8
occdist_scale: 0.02

holonomic_robot: false
12 changes: 12 additions & 0 deletions rusty/robot_param/costmap_common_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
obstacle_range: 4.0
raytrace_range: 3.5

#footprint: [[0.250, 0.300], [-0.250, 0.300], [-0.250, -0.300], [0.250, -0.300]]
robot_radius: 0.305

inflation_radius: 0.6
cost_scaling_factor: 3.0

map_type: costmap
observation_sources: scan
scan: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
47 changes: 47 additions & 0 deletions rusty/robot_param/dwa_local_planner_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
DWAPlannerROS:

# Robot Configuration Parameters
max_vel_x: 0.35
min_vel_x: -0.20

max_vel_y: 0.0
min_vel_y: 0.0

# The velocity when robot is moving in a straight line
max_vel_trans: 0.35
min_vel_trans: -0.25

max_vel_theta: 2.8
min_vel_theta: 1.5

acc_lim_x: 2.5
acc_lim_y: 0.0
acc_lim_theta: 3.2

# Goal Tolerance Parametes
xy_goal_tolerance: 0.05
yaw_goal_tolerance: 0.17
latch_xy_goal_tolerance: false

# Forward Simulation Parameters
sim_time: 1.4
vx_samples: 20
vy_samples: 0
vth_samples: 40
controller_frequency: 10.0

# Trajectory Scoring Parameters
path_distance_bias: 25.0
goal_distance_bias: 10.0
occdist_scale: 0.02
forward_point_distance: 0.325
stop_time_buffer: 0.2
scaling_speed: 0.25
max_scaling_factor: 0.2

# Oscillation Prevention Parameters
oscillation_reset_dist: 0.05

# Debugging
publish_traj_pc : true
publish_cost_grid_pc: true
10 changes: 10 additions & 0 deletions rusty/robot_param/global_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
global_costmap:
global_frame: map
robot_base_frame: base_link

update_frequency: 10.0
publish_frequency: 10.0
transform_tolerance: 0.5

static_map: true

14 changes: 14 additions & 0 deletions rusty/robot_param/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
local_costmap:
global_frame: odom
robot_base_frame: base_link

update_frequency: 10.0
publish_frequency: 10.0
transform_tolerance: 0.5

static_map: false
rolling_window: true
width: 4
height: 4
resolution: 0.05

9 changes: 9 additions & 0 deletions rusty/robot_param/move_base_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
shutdown_costmaps: false
controller_frequency: 10.0
planner_patience: 5.0
controller_patience: 15.0
conservative_reset_dist: 3.0
planner_frequency: 10.0
oscillation_timeout: 10.0
oscillation_distance: 0.2

Loading