ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Hi, I'm running the configuration with the launch files I attached. Give it a try and let me know if it works for you. Regards, Micha

Hi, I'm running the configuration with the launch files I attached. Give it a try and let me know if it works for you. Regards, Micha

master.launch which starts everything needed:

<?xml version="1.0"?>
<launch>
    <node name="stage" pkg ="stage_ros" type="stageros" args="$(find multi_robot_simulation)/world/world.world" />
    <param name="use_sim_time"  value="true"/>
    <group ns="robot_0">
        <include file="$(find adhoc_communication)/launch/adhoc_communication.launch">
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="robot_name" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="interface" value="lo" />
            <arg name="use_sim_time" value="true" />
            <arg name="mac" value="02:01:00:00:00:00" />
            <arg name="sim_robot_macs" value="robot_0,02:01:00:00:00:00!robot_1,02:02:00:00:00:00" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/move_base.launch">
            <arg name="robot" value="robot_0" />
            <arg name="robot_pref" value="/robot_0" />
            <arg name="output" value="log" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/mapping.launch">
            <arg name="robot" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="robot_local_map_frame" value="robot_0/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
            <arg name="xmax" value="35" />
            <arg name="xmin" value="-35" />
            <arg name="ymax" value="35" />
            <arg name="ymin" value="-35" />
        </include>
        <include file="$(find map_merger)/launch/map_merger.launch">
            <arg name="robot_name" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="robot_local_map_frame" value="robot_0/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
        </include>
        <include file="$(find explorer)/launch/exploration.launch">
            <arg name="robot_name" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="frontier_selection" value="1" />
            <arg name="use_sim_time" value="true" />
        </include>
    </group>
    <group ns="robot_1">
        <include file="$(find adhoc_communication)/launch/adhoc_communication.launch">
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="robot_name" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="interface" value="lo" />
            <arg name="use_sim_time" value="true" />
            <arg name="mac" value="02:02:00:00:00:00" />
            <arg name="sim_robot_macs" value="robot_0,02:01:00:00:00:00!robot_1,02:02:00:00:00:00" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/move_base.launch">
            <arg name="robot" value="robot_1" />
            <arg name="robot_pref" value="/robot_1" />
            <arg name="output" value="log" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/mapping.launch">
            <arg name="robot" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="robot_local_map_frame" value="robot_1/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
            <arg name="xmax" value="35" />
            <arg name="xmin" value="-35" />
            <arg name="ymax" value="35" />
            <arg name="ymin" value="-35" />
        </include>
        <include file="$(find map_merger)/launch/map_merger.launch">
            <arg name="robot_name" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="robot_local_map_frame" value="robot_1/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
        </include>
        <include file="$(find explorer)/launch/exploration.launch">
            <arg name="robot_name" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" />
            <arg name="frontier_selection" value="1" />
            <arg name="use_sim_time" value="true" />
        </include>
    </group>
</launch>

mapping.launch:

<?xml version="1.0"?>
<launch>
    <arg name="robot" />
    <arg name="robot_prefix" />
    <arg name="robot_local_map_frame" />
    <arg name="log_path" />
    <arg name="use_sim_time" default="true" />
    <arg name="output" default="log" />
    <arg name="xmax" default="35" />
    <arg name="xmin" default="-35" />
    <arg name="ymax" default="35" />
    <arg name="ymin" default="-35" />

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

    <node pkg="gmapping" type="slam_gmapping" name="mapping">
        <param name="base_frame" value="$(arg robot_prefix)/base_footprint" />
        <param name="odom_frame" value="$(arg robot_prefix)/odom" />
        <param name="map_frame" value="$(arg robot_prefix)/map" />
        <param name="scan_topic" value="$(arg robot_prefix)/base_scan" />
        <param name="xmax" value="$(arg xmax)" />
        <param name="ymax" value="$(arg ymax)" />
        <param name="xmin" value="$(arg xmin)" />
        <param name="ymin" value="$(arg ymin)" />
        <param name="transform_publish_period " value="1.00" />
        <param name="particles" value="5" />
        <param name="maxRange" value="60" />
        <param name="maxUrange" value="59.9" />
        <param name="temporalUpdate" value="2.0" />

        <remap from="scan" to="base_scan" />
    </node>
</launch>

move_base.launch:

<?xml version="1.0"?>
<launch>
    <arg name="robot" />
    <arg name="robot_pref" />
    <arg name="output" default="log" />

    <node pkg="move_base" type="move_base" name="move_base" >
        <param name="local_costmap/robot_base_frame" value="$(arg robot_pref)/base_footprint" />
        <param name="local_costmap/global_frame" value="$(arg robot_pref)/odom" />
        <param name="global_costmap/robot_base_frame" value="$(arg robot_pref)/base_footprint" />
        <param name="global_costmap/global_frame" value="$(arg robot_pref)/map" />
        <param name="global_costmap/map_topic" value="map_merger/global_map" />
        <param name="local_costmap/observation_sources" value="scan" />
        <param name="local_costmap/scan/topic" value="base_scan" />
        <param name="local_costmap/scan/data_type" value="LaserScan" />
        <param name="local_costmap/map_topic" value="map_merger/global_map" />
        <param name="local_costmap/scan/clearing" value="true" />
        <param name="local_costmap/scan/marking" value="true" />
        <param name="observation_persistence" value="0.1" />

        <rosparam file="common_costmap.yaml" command="load" ns="global_costmap" />
        <rosparam file="common_costmap.yaml" command="load" ns="local_costmap" />
        <rosparam file="navigation.yaml"     command="load" />
        <rosparam file="local_costmap.yaml"  command="load" />
        <rosparam file="global_costmap.yaml" command="load" />

        <remap from="$(arg robot_pref)$(arg robot_pref)/map" to="$(arg robot_pref)/map" />
    </node>
</launch>

common_costmap.yaml:

map_type: costmap
transform_tolerance: 50
obstacle_range: 2.5
raytrace_range: 4.0
inscribed_radius: 0.35
circumscribed_radius: 0.4
inflation_radius: 0.6
cost_scaling_factor: 15.0
lethal_cost_threshold: 100
footprint: [[-0.12, -0.12], [-0.12, 0.12], [0.12, 0.12],[0.12, -0.12]]

global_costmap.yaml:

global_costmap:
   update_frequency: 0.2
   publish_frequency: 0.5
   static_map: true
   rolling_window: false
   width: 150.0
   height: 150.0
   max_obstacle_height: 1.0

local_costmap.yaml:

local_costmap:
  update_frequency: 6
  publish_frequency: 6
  static_map: false
  rolling_window: true
  width: 8.0
  height: 8.0
  publish_voxel_map : true
  unknown_cost_value : 255
  track_unknown_space : true
  origin_x: 0.0
  origin_y: 0.0
  origin_z: 0.0
  unknown_threshold: 15
  resolution: 0.05
  restore_defaults: false
  mark_threshold: 0
  max_obstacle_height: 2.0
  max_obstacle_range: 2.5
  map_topic: map
  z_resolution: 0.2
  z_voxels: 10

navigation.yaml:

controller_frequency: 5.0
TrajectoryPlannerROS:
  max_vel_x: 0.50
  min_vel_x: 0.10
  max_rotational_vel: 1.5
  min_in_place_rotational_vel: 1.0
  acc_lim_th: 0.75
  acc_lim_x: 0.50
  acc_lim_y: 0.50

  transform_tolerance: 5
  default_tolerance: 5

  holonomic_robot: false
  yaw_goal_tolerance: 0.3
  xy_goal_tolerance: 0.25
  goal_distance_bias: 0.8
  path_distance_bias: 0.6
  sim_time: 1.5
  heading_lookahead: 0.325
  oscillation_reset_dist: 0.05

  vx_samples: 6
  vtheta_samples: 20
  dwa: false

Hi, I'm running the configuration with the launch files I attached. Give it a try and let me know if it works for you. Regards, Micha

master.launch which starts everything needed:

<?xml version="1.0"?>
<launch>
    <node name="stage" pkg ="stage_ros" type="stageros" args="$(find multi_robot_simulation)/world/world.world" />
    <param name="use_sim_time"  value="true"/>
    <group ns="robot_0">
        <include file="$(find adhoc_communication)/launch/adhoc_communication.launch">
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="logs/15-11-20/14-06-42/1" />
            <arg name="robot_name" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="interface" value="lo" />
            <arg name="use_sim_time" value="true" />
            <arg name="mac" value="02:01:00:00:00:00" />
            <arg name="sim_robot_macs" value="robot_0,02:01:00:00:00:00!robot_1,02:02:00:00:00:00" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/move_base.launch">
            <arg name="robot" value="robot_0" />
            <arg name="robot_pref" value="/robot_0" />
            <arg name="output" value="log" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/mapping.launch">
            <arg name="robot" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="robot_local_map_frame" value="robot_0/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
            <arg name="xmax" value="35" />
            <arg name="xmin" value="-35" />
            <arg name="ymax" value="35" />
            <arg name="ymin" value="-35" />
        </include>
        <include file="$(find map_merger)/launch/map_merger.launch">
            <arg name="robot_name" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="robot_local_map_frame" value="robot_0/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
        </include>
        <include file="$(find explorer)/launch/exploration.launch">
            <arg name="robot_name" value="robot_0" />
            <arg name="robot_prefix" value="/robot_0" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="logs/15-11-20/14-06-42/1" />
            <arg name="frontier_selection" value="1" />
            <arg name="use_sim_time" value="true" />
        </include>
    </group>
    <group ns="robot_1">
        <include file="$(find adhoc_communication)/launch/adhoc_communication.launch">
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="logs/15-11-20/14-06-42/1" />
            <arg name="robot_name" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="interface" value="lo" />
            <arg name="use_sim_time" value="true" />
            <arg name="mac" value="02:02:00:00:00:00" />
            <arg name="sim_robot_macs" value="robot_0,02:01:00:00:00:00!robot_1,02:02:00:00:00:00" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/move_base.launch">
            <arg name="robot" value="robot_1" />
            <arg name="robot_pref" value="/robot_1" />
            <arg name="output" value="log" />
        </include>
        <include file="$(find multi_robot_simulation)/launch/mapping.launch">
            <arg name="robot" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="robot_local_map_frame" value="robot_1/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
            <arg name="xmax" value="35" />
            <arg name="xmin" value="-35" />
            <arg name="ymax" value="35" />
            <arg name="ymin" value="-35" />
        </include>
        <include file="$(find map_merger)/launch/map_merger.launch">
            <arg name="robot_name" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="robot_local_map_frame" value="robot_1/map" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="logs/15-11-20/14-06-42/1" />
            <arg name="use_sim_time" value="true" />
        </include>
        <include file="$(find explorer)/launch/exploration.launch">
            <arg name="robot_name" value="robot_1" />
            <arg name="robot_prefix" value="/robot_1" />
            <arg name="output" value="log" />
            <arg name="log_path" value="/home/mrappapo/ros_indigo_internal/src/multi_robot_exploration/multi_robot_analyzer/logs/15-11-20/14-06-42/1" value="15-11-20/14-06-42/1" />
            <arg name="frontier_selection" value="1" />
            <arg name="use_sim_time" value="true" />
        </include>
    </group>
</launch>

mapping.launch:

<?xml version="1.0"?>
<launch>
    <arg name="robot" />
    <arg name="robot_prefix" />
    <arg name="robot_local_map_frame" />
    <arg name="log_path" />
    <arg name="use_sim_time" default="true" />
    <arg name="output" default="log" />
    <arg name="xmax" default="35" />
    <arg name="xmin" default="-35" />
    <arg name="ymax" default="35" />
    <arg name="ymin" default="-35" />

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

    <node pkg="gmapping" type="slam_gmapping" name="mapping">
        <param name="base_frame" value="$(arg robot_prefix)/base_footprint" />
        <param name="odom_frame" value="$(arg robot_prefix)/odom" />
        <param name="map_frame" value="$(arg robot_prefix)/map" />
        <param name="scan_topic" value="$(arg robot_prefix)/base_scan" />
        <param name="xmax" value="$(arg xmax)" />
        <param name="ymax" value="$(arg ymax)" />
        <param name="xmin" value="$(arg xmin)" />
        <param name="ymin" value="$(arg ymin)" />
        <param name="transform_publish_period " value="1.00" />
        <param name="particles" value="5" />
        <param name="maxRange" value="60" />
        <param name="maxUrange" value="59.9" />
        <param name="temporalUpdate" value="2.0" />

        <remap from="scan" to="base_scan" />
    </node>
</launch>

move_base.launch:

<?xml version="1.0"?>
<launch>
    <arg name="robot" />
    <arg name="robot_pref" />
    <arg name="output" default="log" />

    <node pkg="move_base" type="move_base" name="move_base" >
        <param name="local_costmap/robot_base_frame" value="$(arg robot_pref)/base_footprint" />
        <param name="local_costmap/global_frame" value="$(arg robot_pref)/odom" />
        <param name="global_costmap/robot_base_frame" value="$(arg robot_pref)/base_footprint" />
        <param name="global_costmap/global_frame" value="$(arg robot_pref)/map" />
        <param name="global_costmap/map_topic" value="map_merger/global_map" />
        <param name="local_costmap/observation_sources" value="scan" />
        <param name="local_costmap/scan/topic" value="base_scan" />
        <param name="local_costmap/scan/data_type" value="LaserScan" />
        <param name="local_costmap/map_topic" value="map_merger/global_map" />
        <param name="local_costmap/scan/clearing" value="true" />
        <param name="local_costmap/scan/marking" value="true" />
        <param name="observation_persistence" value="0.1" />

        <rosparam file="common_costmap.yaml" command="load" ns="global_costmap" />
        <rosparam file="common_costmap.yaml" command="load" ns="local_costmap" />
        <rosparam file="navigation.yaml"     command="load" />
        <rosparam file="local_costmap.yaml"  command="load" />
        <rosparam file="global_costmap.yaml" command="load" />

        <remap from="$(arg robot_pref)$(arg robot_pref)/map" to="$(arg robot_pref)/map" />
    </node>
</launch>

common_costmap.yaml:

map_type: costmap
transform_tolerance: 50
obstacle_range: 2.5
raytrace_range: 4.0
inscribed_radius: 0.35
circumscribed_radius: 0.4
inflation_radius: 0.6
cost_scaling_factor: 15.0
lethal_cost_threshold: 100
footprint: [[-0.12, -0.12], [-0.12, 0.12], [0.12, 0.12],[0.12, -0.12]]

global_costmap.yaml:

global_costmap:
   update_frequency: 0.2
   publish_frequency: 0.5
   static_map: true
   rolling_window: false
   width: 150.0
   height: 150.0
   max_obstacle_height: 1.0

local_costmap.yaml:

local_costmap:
  update_frequency: 6
  publish_frequency: 6
  static_map: false
  rolling_window: true
  width: 8.0
  height: 8.0
  publish_voxel_map : true
  unknown_cost_value : 255
  track_unknown_space : true
  origin_x: 0.0
  origin_y: 0.0
  origin_z: 0.0
  unknown_threshold: 15
  resolution: 0.05
  restore_defaults: false
  mark_threshold: 0
  max_obstacle_height: 2.0
  max_obstacle_range: 2.5
  map_topic: map
  z_resolution: 0.2
  z_voxels: 10

navigation.yaml:

controller_frequency: 5.0
TrajectoryPlannerROS:
  max_vel_x: 0.50
  min_vel_x: 0.10
  max_rotational_vel: 1.5
  min_in_place_rotational_vel: 1.0
  acc_lim_th: 0.75
  acc_lim_x: 0.50
  acc_lim_y: 0.50

  transform_tolerance: 5
  default_tolerance: 5

  holonomic_robot: false
  yaw_goal_tolerance: 0.3
  xy_goal_tolerance: 0.25
  goal_distance_bias: 0.8
  path_distance_bias: 0.6
  sim_time: 1.5
  heading_lookahead: 0.325
  oscillation_reset_dist: 0.05

  vx_samples: 6
  vtheta_samples: 20
  dwa: false