Browse Source

Cleanup whitespace in Stretch Navigation and Rtabmap

pull/37/head
Binit Shah 3 years ago
parent
commit
7ba9402a32
54 changed files with 143 additions and 151 deletions
  1. +1
    -1
      stretch_navigation/LICENSE.md
  2. +2
    -2
      stretch_navigation/README.md
  3. +2
    -2
      stretch_navigation/launch/navigation/map_server.launch
  4. +2
    -2
      stretch_navigation/launch/navigation/move_base.launch
  5. +2
    -2
      stretch_navigation/launch/navigation/octomap_server.launch
  6. +2
    -2
      stretch_navigation/launch/navigation_3d.launch
  7. +1
    -1
      stretch_navigation/resources/config/2d/base_local_planner_params.yaml
  8. +5
    -5
      stretch_navigation/resources/config/2d/costmap_common_params.yaml
  9. +1
    -3
      stretch_navigation/resources/config/2d/global_costmap_params.yaml
  10. +1
    -1
      stretch_navigation/resources/config/2d/global_planner_params.yaml
  11. +1
    -1
      stretch_navigation/resources/config/2d_unknown/base_local_planner_params.yaml
  12. +5
    -5
      stretch_navigation/resources/config/2d_unknown/costmap_common_params.yaml
  13. +1
    -1
      stretch_navigation/resources/config/2d_unknown/global_planner_params.yaml
  14. +2
    -2
      stretch_navigation/resources/config/3d/base_local_planner_params.yaml
  15. +6
    -6
      stretch_navigation/resources/config/3d/costmap_common_params.yaml
  16. +3
    -4
      stretch_navigation/resources/config/3d/global_costmap_params.yaml
  17. +1
    -1
      stretch_navigation/resources/config/3d/global_planner_params.yaml
  18. +2
    -2
      stretch_navigation/resources/config/3d_unknown/base_local_planner_params.yaml
  19. +7
    -7
      stretch_navigation/resources/config/3d_unknown/costmap_common_params.yaml
  20. +0
    -1
      stretch_navigation/resources/config/3d_unknown/global_costmap_params.yaml
  21. +1
    -1
      stretch_navigation/resources/config/3d_unknown/global_planner_params.yaml
  22. +1
    -1
      stretch_navigation/resources/config/amcl.yaml
  23. +1
    -1
      stretch_navigation/resources/config/costmap_height.yaml
  24. +1
    -1
      stretch_octomap/LICENSE.md
  25. +1
    -1
      stretch_octomap/README.md
  26. +3
    -3
      stretch_octomap/launch/octomap_mapper.launch
  27. +1
    -1
      stretch_rtabmap/LICENSE.md
  28. +6
    -5
      stretch_rtabmap/README.md
  29. +1
    -1
      stretch_rtabmap/config/2d/base_local_planner_params.yaml
  30. +5
    -5
      stretch_rtabmap/config/2d/costmap_common_params.yaml
  31. +1
    -3
      stretch_rtabmap/config/2d/global_costmap_params.yaml
  32. +1
    -1
      stretch_rtabmap/config/2d/global_planner_params.yaml
  33. +1
    -1
      stretch_rtabmap/config/2d_unknown/base_local_planner_params.yaml
  34. +5
    -5
      stretch_rtabmap/config/2d_unknown/costmap_common_params.yaml
  35. +1
    -1
      stretch_rtabmap/config/2d_unknown/global_planner_params.yaml
  36. +1
    -1
      stretch_rtabmap/config/3d/base_local_planner_params.yaml
  37. +4
    -4
      stretch_rtabmap/config/3d/costmap_common_params.yaml
  38. +1
    -2
      stretch_rtabmap/config/3d/global_costmap_params.yaml
  39. +1
    -1
      stretch_rtabmap/config/3d/global_planner_params.yaml
  40. +2
    -2
      stretch_rtabmap/config/3d_unknown/base_local_planner_params.yaml
  41. +7
    -7
      stretch_rtabmap/config/3d_unknown/costmap_common_params.yaml
  42. +0
    -1
      stretch_rtabmap/config/3d_unknown/global_costmap_params.yaml
  43. +1
    -1
      stretch_rtabmap/config/3d_unknown/global_planner_params.yaml
  44. +1
    -1
      stretch_rtabmap/config/amcl.yaml
  45. +1
    -1
      stretch_rtabmap/config/costmap_height.yaml
  46. +1
    -1
      stretch_rtabmap/config/stretch_gazebo.yaml
  47. +1
    -1
      stretch_rtabmap/launch/gazebo/gazebo.launch
  48. +2
    -2
      stretch_rtabmap/launch/move_base.launch
  49. +1
    -1
      stretch_rtabmap/launch/robot.launch
  50. +16
    -16
      stretch_rtabmap/launch/rtab.launch
  51. +19
    -19
      stretch_rtabmap/launch/rtab_gazebo.launch
  52. +2
    -2
      stretch_rtabmap/launch/rtabmapviz.launch
  53. +1
    -1
      stretch_rtabmap/launch/rviz_rtab.launch
  54. +4
    -4
      stretch_rtabmap/launch/start_rtab.launch

+ 1
- 1
stretch_navigation/LICENSE.md View File

@ -7,5 +7,5 @@ The Contents are licensed under the Apache License, Version 2.0 (the "License").
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, the Contents are distributed under the License are distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
For further information about the Contents including inquiries about dual licensing, please contact Hello Robot Inc.

+ 2
- 2
stretch_navigation/README.md View File

@ -30,7 +30,7 @@ Rviz will show the robot and the map that is being constructed. With the termina
```bash
mkdir -p ~/stretch_user/maps
rosrun map_server map_saver -f ${HELLO_FLEET_PATH}/maps/<map_name>
```
```
The `<map_name>` does not include an extension. Map_saver will save two files as `<map_name>.pgm` and `<map_name>.yaml`.
@ -76,4 +76,4 @@ roslaunch stretch_core teleop_twist.launch teleop_type:=keyboard # or use teleop
## License
For license information, please see the LICENSE files.
For license information, please see the LICENSE files.

+ 2
- 2
stretch_navigation/launch/navigation/map_server.launch View File

@ -4,5 +4,5 @@
<arg name="map_name" default="map" />
<!-- launch map server -->
<node name="map_server" pkg="map_server" type="map_server" output="screen" args="$(arg map_name)"/>
</launch>
<node name="map_server" pkg="map_server" type="map_server" output="screen" args="$(arg map_name)"/>
</launch>

+ 2
- 2
stretch_navigation/launch/navigation/move_base.launch View File

@ -2,7 +2,7 @@
<!-- Doc: http://wiki.ros.org/move_base?distro=kinetic -->
<arg name="config"/>
<arg name="cmd_vel_topic"/>
<arg name="odom_topic"/>
@ -27,4 +27,4 @@
<remap from="odom" to="$(arg odom_topic)" />
</node>
</launch>
</launch>

+ 2
- 2
stretch_navigation/launch/navigation/octomap_server.launch View File

@ -1,6 +1,6 @@
<launch>
<!-- Doc: http://wiki.ros.org/octomap_server?distro=kinetic -->
<arg name="map" default="map" />
<arg name="base_link" default="base_link" />
@ -30,4 +30,4 @@
<remap from="clear_bbx" to="clear_bbx_negative" />
<remap from="reset" to="reset_negative" />
</node>
</launch>
</launch>

+ 2
- 2
stretch_navigation/launch/navigation_3d.launch View File

@ -1,5 +1,5 @@
<launch>
<!-- The navigation_3d launch file includes all of the launch files needed for a robot to accomplish 3D navigation.
<!-- The navigation_3d launch file includes all of the launch files needed for a robot to accomplish 3D navigation.
The nodes needed for navigation are map_server, octomap_server, amcl, and move_base.-->
<!-- Map name -->
@ -43,4 +43,4 @@
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find stretch_navigation)/rviz/octomap.rviz" />
</launch>
</launch>

+ 1
- 1
stretch_navigation/resources/config/2d/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true

+ 5
- 5
stretch_navigation/resources/config/2d/costmap_common_params.yaml View File

@ -12,10 +12,10 @@ map_type: costmap
2d_obstacles:
observation_sources: laser
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
expected_update_rate: 0.3,
track_unknown_space: true
}
@ -23,4 +23,4 @@ map_type: costmap
inflation_layer:
inflation_radius: 0.3
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 1
- 3
stretch_navigation/resources/config/2d/global_costmap_params.yaml View File

@ -7,7 +7,5 @@ global_costmap:
robot_base_frame: base_link
update_frequency: 10.0
publish_frequency: 0.5
static_map:
static_map:
map_topic: /map

+ 1
- 1
stretch_navigation/resources/config/2d/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 1
- 1
stretch_navigation/resources/config/2d_unknown/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true

+ 5
- 5
stretch_navigation/resources/config/2d_unknown/costmap_common_params.yaml View File

@ -10,10 +10,10 @@ map_type: costmap
2d_obstacles:
observation_sources: laser
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
expected_update_rate: 0.3,
track_unknown_space: true
}
@ -21,4 +21,4 @@ map_type: costmap
inflation_layer:
inflation_radius: 0.75
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 1
- 1
stretch_navigation/resources/config/2d_unknown/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 2
- 2
stretch_navigation/resources/config/3d/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true
prune_plan: true

+ 6
- 6
stretch_navigation/resources/config/3d/costmap_common_params.yaml View File

@ -33,7 +33,7 @@ map_type: costmap
horizontal_fov_angle: 0.942478 #default 1.04, radians
decay_acceleration: 1 #default 0, 1/s^2. If laser scanner MUST be 0
model_type: 0 #default 0 (depth camera). Use 1 for 3D Lidar
negative_obstacle:
enabled: true #default true, can be toggled on/off with associated service call
data_type: PointCloud2
@ -52,10 +52,10 @@ map_type: costmap
2d_obstacles:
observation_sources: laser
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
expected_update_rate: 0.3,
track_unknown_space: true
}
@ -63,4 +63,4 @@ map_type: costmap
inflation_layer:
inflation_radius: 0.2
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 3
- 4
stretch_navigation/resources/config/3d/global_costmap_params.yaml View File

@ -11,10 +11,9 @@ global_costmap:
update_frequency: 10.0
publish_frequency: 0.5
rolling_window: false #idk about this one
static_map_2d:
static_map_2d:
map_topic: /map
static_map_3d_positive:
static_map_3d_positive:
map_topic: /projected_map
static_map_3d_negative:
static_map_3d_negative:
map_topic: /projected_map_negative

+ 1
- 1
stretch_navigation/resources/config/3d/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 2
- 2
stretch_navigation/resources/config/3d_unknown/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true
prune_plan: true

+ 7
- 7
stretch_navigation/resources/config/3d_unknown/costmap_common_params.yaml View File

@ -22,7 +22,7 @@ map_type: costmap
origin_z: 0.0 #meters
publish_voxel_map: true # default off
transform_tolerance: 0.4
transform_tolerance: 0.4
mapping_mode: false # default off, saves map not for navigation
map_save_duration: 60 #default 60s, how often to autosave
observation_sources: positive_obstacle negative_obstacle
@ -40,7 +40,7 @@ map_type: costmap
horizontal_fov_angle: 1.04 #default 1.04, radians
decay_acceleration: 1 #default 0, 1/s^2. If laser scanner MUST be 0
model_type: 0 #default 0 (depth camera). Use 1 for 3D Lidar
negative_obstacle:
enabled: true #default true, can be toggled on/off with associated service call
data_type: PointCloud2
@ -59,10 +59,10 @@ map_type: costmap
2d_obstacles:
observation_sources: laser
laser: {data_type: LaserScan,
topic: /scan,
marking: true,
clearing: true,
laser: {data_type: LaserScan,
topic: /scan,
marking: true,
clearing: true,
expected_update_rate: 0.3,
track_unknown_space: true
}
@ -70,4 +70,4 @@ map_type: costmap
inflation_layer:
inflation_radius: 0.75
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 0
- 1
stretch_navigation/resources/config/3d_unknown/global_costmap_params.yaml View File

@ -12,4 +12,3 @@ global_costmap:
width: 500.0
height: 500.0
resolution: 0.1

+ 1
- 1
stretch_navigation/resources/config/3d_unknown/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 1
- 1
stretch_navigation/resources/config/amcl.yaml View File

@ -40,4 +40,4 @@ amcl:
always_reset_initial_pose: false
use_map_topic: true
scan_topic: "/scan"
map_topic: "/map"
map_topic: "/map"

+ 1
- 1
stretch_navigation/resources/config/costmap_height.yaml View File

@ -1,3 +1,3 @@
3d_obstacles:
positive_obstacle:
max_obstacle_height: 1.5
max_obstacle_height: 1.5

+ 1
- 1
stretch_octomap/LICENSE.md View File

@ -7,5 +7,5 @@ The Contents are licensed under the Apache License, Version 2.0 (the "License").
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, the Contents are distributed under the License are distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
For further information about the Contents including inquiries about dual licensing, please contact Hello Robot Inc.

+ 1
- 1
stretch_octomap/README.md View File

@ -6,4 +6,4 @@
## License
For license information, please see the LICENSE files.
For license information, please see the LICENSE files.

+ 3
- 3
stretch_octomap/launch/octomap_mapper.launch View File

@ -1,6 +1,6 @@
<launch>
<!-- Doc: http://wiki.ros.org/octomap_server?distro=kinetic -->
<arg name="pointcloud_topic" />
<arg name="base_link" default="base_link" />
@ -12,6 +12,6 @@
<param name="frame_id" type="string" value="map" />
<param name="sensor_model/max_range" value="3.0" />
<param name="filter_ground" value="false" />
</node>
</launch>
</launch>

+ 1
- 1
stretch_rtabmap/LICENSE.md View File

@ -7,5 +7,5 @@ The Contents are licensed under the Apache License, Version 2.0 (the "License").
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, the Contents are distributed under the License are distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
For further information about the Contents including inquiries about dual licensing, please contact Hello Robot Inc.

+ 6
- 5
stretch_rtabmap/README.md View File

@ -34,9 +34,9 @@ Use `rosdep` to install the required packages.
```
## Code Status & Development Plans
Move_base_config | Gazebo | Stretch RE1
2d | okay | Good
2d_unkown | Not Implemented | Not Implemented
3d | Testing | Testing
3d_unkown | Not Implemented | Not Implemented
Move_base_config | Gazebo | Stretch RE1
-----------------|-----------------|----------------
2d | okay | Good
2d_unkown | Not Implemented | Not Implemented
3d | Testing | Testing
3d_unkown | Not Implemented | Not Implemented

+ 1
- 1
stretch_rtabmap/config/2d/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true

+ 5
- 5
stretch_rtabmap/config/2d/costmap_common_params.yaml View File

@ -12,10 +12,10 @@ map_type: costmap
2d_obstacles:
observation_sources: laser
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
expected_update_rate: 0.3,
track_unknown_space: true
}
@ -23,4 +23,4 @@ map_type: costmap
inflation_layer:
inflation_radius: 0.3
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 1
- 3
stretch_rtabmap/config/2d/global_costmap_params.yaml View File

@ -7,7 +7,5 @@ global_costmap:
robot_base_frame: base_link
update_frequency: 10.0
publish_frequency: 0.5
static_map:
static_map:
map_topic: /map

+ 1
- 1
stretch_rtabmap/config/2d/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 1
- 1
stretch_rtabmap/config/2d_unknown/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true

+ 5
- 5
stretch_rtabmap/config/2d_unknown/costmap_common_params.yaml View File

@ -10,10 +10,10 @@ map_type: costmap
2d_obstacles:
observation_sources: laser
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
laser: {data_type: LaserScan,
topic: scan,
marking: true,
clearing: true,
expected_update_rate: 0.3,
track_unknown_space: true
}
@ -21,4 +21,4 @@ map_type: costmap
inflation_layer:
inflation_radius: 0.75
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 1
- 1
stretch_rtabmap/config/2d_unknown/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 1
- 1
stretch_rtabmap/config/3d/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true

+ 4
- 4
stretch_rtabmap/config/3d/costmap_common_params.yaml View File

@ -35,11 +35,11 @@ map_type: voxel
2d_obstacles:
enabled: true
observation_sources: laser
laser:
data_type: LaserScan
laser:
data_type: LaserScan
topic: /scan
marking: true
clearing: true
clearing: true
expected_update_rate: 0.3
track_unknown_space: true
@ -47,4 +47,4 @@ map_type: voxel
inflation_layer:
enabled: true
inflation_radius: 0.3
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 1
- 2
stretch_rtabmap/config/3d/global_costmap_params.yaml View File

@ -9,6 +9,5 @@ global_costmap:
update_frequency: 1.0
publish_frequency: 0.5
rolling_window: true
static_map_2d:
static_map_2d:
map_topic: /map

+ 1
- 1
stretch_rtabmap/config/3d/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 2
- 2
stretch_rtabmap/config/3d_unknown/base_local_planner_params.yaml View File

@ -75,5 +75,5 @@ DWAPlannerROS:
#yaw_goal_tolerance: 0.05
#xy_goal_tolerance: 0.1
#latch_xy_goal_tolerance: false
prune_plan: true
prune_plan: true

+ 7
- 7
stretch_rtabmap/config/3d_unknown/costmap_common_params.yaml View File

@ -22,7 +22,7 @@ map_type: costmap
origin_z: 0.0 #meters
publish_voxel_map: true # default off
transform_tolerance: 0.4
transform_tolerance: 0.4
mapping_mode: false # default off, saves map not for navigation
map_save_duration: 60 #default 60s, how often to autosave
observation_sources: positive_obstacle negative_obstacle
@ -40,7 +40,7 @@ map_type: costmap
horizontal_fov_angle: 1.04 #default 1.04, radians
decay_acceleration: 1 #default 0, 1/s^2. If laser scanner MUST be 0
model_type: 0 #default 0 (depth camera). Use 1 for 3D Lidar
negative_obstacle:
enabled: true #default true, can be toggled on/off with associated service call
data_type: PointCloud2
@ -59,10 +59,10 @@ map_type: costmap
2d_obstacles:
observation_sources: laser
laser: {data_type: LaserScan,
topic: /scan,
marking: true,
clearing: true,
laser: {data_type: LaserScan,
topic: /scan,
marking: true,
clearing: true,
expected_update_rate: 0.3,
track_unknown_space: true
}
@ -70,4 +70,4 @@ map_type: costmap
inflation_layer:
inflation_radius: 0.75
cost_scaling_factor: 2.5
cost_scaling_factor: 2.5

+ 0
- 1
stretch_rtabmap/config/3d_unknown/global_costmap_params.yaml View File

@ -12,4 +12,3 @@ global_costmap:
width: 500.0
height: 500.0
resolution: 0.1

+ 1
- 1
stretch_rtabmap/config/3d_unknown/global_planner_params.yaml View File

@ -8,4 +8,4 @@ GlobalPlanner:
orientation_window_size: 1
publish_potential: false
default_tolerance: 0.2
outline_map: false
outline_map: false

+ 1
- 1
stretch_rtabmap/config/amcl.yaml View File

@ -20,4 +20,4 @@ amcl:
update_min_d: 0.25
use_map_topic: true
scan_topic: "/scan"
map_topic: "/map"
map_topic: "/map"

+ 1
- 1
stretch_rtabmap/config/costmap_height.yaml View File

@ -1,3 +1,3 @@
3d_obstacles:
positive_obstacle:
max_obstacle_height: 1.5
max_obstacle_height: 1.5

+ 1
- 1
stretch_rtabmap/config/stretch_gazebo.yaml View File

@ -3,4 +3,4 @@ odom_topic: "/stretch_diff_drive_controller/odom"
scan_topic: "/scan"
pointcloud_topic: "/camera/depth/image_raw"
rgb_topic: "/camera/color/image_raw"
rgb_camera_info: "/camera/color/camera_info"
rgb_camera_info: "/camera/color/camera_info"

+ 1
- 1
stretch_rtabmap/launch/gazebo/gazebo.launch View File

@ -31,7 +31,7 @@
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find stretch_gazebo)/config/sim.rviz" if="$(arg rviz)"/>
<rosparam command="load"
file="$(find stretch_gazebo)/config/joints.yaml"
file="$(find stretch_gazebo)/config/joints.yaml"
ns="stretch_joint_state_controller" />
<rosparam command="load"

+ 2
- 2
stretch_rtabmap/launch/move_base.launch View File

@ -2,7 +2,7 @@
<!-- Doc: http://wiki.ros.org/move_base?distro=kinetic -->
<arg name="config"/>
<arg name="cmd_vel_topic"/>
<arg name="odom_topic"/>
@ -26,4 +26,4 @@
<remap from="odom" to="$(arg odom_topic)" />
</node>
</launch>
</launch>

+ 1
- 1
stretch_rtabmap/launch/robot.launch View File

@ -33,4 +33,4 @@
<!-- ROBOT LOCALIZATION FILTER -->
<include file="$(find stretch_core)/launch/stretch_ekf.launch" />
<!-- -->
</launch>
</launch>

+ 16
- 16
stretch_rtabmap/launch/rtab.launch View File

@ -2,7 +2,7 @@
<arg name="localization"/>
<arg name="args"/>
<arg name="database_path"/>
<arg name="wait_for_transform"/>
<arg name="wait_for_transform"/>
<arg name="pointcloud_topic"/>
<arg name="cmd_vel_topic"/>
<arg name="odom_topic"/>
@ -21,37 +21,37 @@
<param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
<param name="subscribe_depth" type="bool" value="true"/>
<param name="subscribe_scan" type="bool" value="true"/>
<!-- inputs -->
<remap from="scan" to="$(arg scan)"/>
<remap from="rgb/image" to="$(arg rgb_topic)"/>
<remap from="depth/image" to="$(arg pointcloud_topic)"/>
<remap from="rgb/camera_info" to="$(arg rgb_camera_info)"/>
<!-- output -->
<remap from="grid_map" to="/map"/>
<!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
<param name="RGBD/ProximityBySpace" type="string" value="true"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="RGBD/ProximityBySpace" type="string" value="true"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="Kp/MaxDepth" type="string" value="4.0"/>
<param name="Reg/Strategy" type="string" value="1"/>
<param name="Reg/Strategy" type="string" value="1"/>
<param name="Icp/CoprrespondenceRatio" type="string" value="0.3"/>
<param name="Vis/MinInliers" type="string" value="6"/>
<param name="Vis/InlierDistance" type="string" value="0.1"/>
<param name="RGBD/AngularUpdate" type="string" value="0.1"/>
<param name="RGBD/LinearUpdate" type="string" value="0.1"/>
<param name="Vis/MinInliers" type="string" value="6"/>
<param name="Vis/InlierDistance" type="string" value="0.1"/>
<param name="RGBD/AngularUpdate" type="string" value="0.1"/>
<param name="RGBD/LinearUpdate" type="string" value="0.1"/>
<param name="Rtabmap/TimeThr" type="string" value="700"/>
<param name="Mem/RehearsalSimilarity" type="string" value="0.30"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Grid/FromDepth" type="string" value="true"/>
<param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>
<param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>
</node>
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
</group>
</launch>
</launch>

+ 19
- 19
stretch_rtabmap/launch/rtab_gazebo.launch View File

@ -1,22 +1,22 @@
<launch>
<arg name="database_path" default="rtabmap.db"/>
<arg name="args" default=""/>
<arg name="wait_for_transform" default="0.2"/>
<arg name="wait_for_transform" default="0.2"/>
<arg name="move_base_config" value="2d" />
<arg name="pointcloud_topic" default="/camera/depth/color/points"/>
<arg name="cmd_vel_topic" default="/stretch_diff_drive_controller/cmd_vel"/>
<arg name="odom_topic" default="/stretch_diff_drive_controller/odom"/>
<!-- Navigation stuff (move_base) -->
<include file="$(find stretch_navigation)/launch/navigation/move_base.launch">
<arg name="config" value="$(arg move_base_config)" />
<arg name="cmd_vel_topic" value="$(arg cmd_vel_topic)" />
<arg name="odom_topic" value="$(arg odom_topic)" />
</include>
<!-- Mapping -->
<group ns="rtabmap">
@ -27,35 +27,35 @@
<param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
<param name="subscribe_depth" type="bool" value="true"/>
<param name="subscribe_scan" type="bool" value="true"/>
<!-- inputs -->
<remap from="scan" to="/scan"/>
<remap from="rgb/image" to="/camera/color/image_raw"/>
<remap from="depth/image" to="/camera/depth/image_raw"/>
<remap from="rgb/camera_info" to="/camera/color/camera_info"/>
<!-- output -->
<remap from="grid_map" to="/map"/>
<!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
<param name="RGBD/ProximityBySpace" type="string" value="true"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="RGBD/ProximityBySpace" type="string" value="true"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="Kp/MaxDepth" type="string" value="4.0"/>
<param name="Reg/Strategy" type="string" value="1"/>
<param name="Reg/Strategy" type="string" value="1"/>
<param name="Icp/CoprrespondenceRatio" type="string" value="0.3"/>
<param name="Vis/MinInliers" type="string" value="6"/>
<param name="Vis/InlierDistance" type="string" value="0.1"/>
<param name="RGBD/AngularUpdate" type="string" value="0.1"/>
<param name="RGBD/LinearUpdate" type="string" value="0.1"/>
<param name="Vis/MinInliers" type="string" value="6"/>
<param name="Vis/InlierDistance" type="string" value="0.1"/>
<param name="RGBD/AngularUpdate" type="string" value="0.1"/>
<param name="RGBD/LinearUpdate" type="string" value="0.1"/>
<param name="Rtabmap/TimeThr" type="string" value="700"/>
<param name="Mem/RehearsalSimilarity" type="string" value="0.30"/>
<param name="Optimizer/Slam2D" type="string" value="true"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
</node>
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
</group>
</launch>
</launch>

+ 2
- 2
stretch_rtabmap/launch/rtabmapviz.launch View File

@ -1,8 +1,8 @@
<launch>
<group ns="rtabmap">
<group ns="rtabmap">
<!-- Visualisation RTAB-Map -->
<node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
<remap from="odom" to="/stretch_diff_drive_controller/odom"/>
</node>
</group>
</launch>
</launch>

+ 1
- 1
stretch_rtabmap/launch/rviz_rtab.launch View File

@ -6,4 +6,4 @@
<group unless="$(arg mapping)">
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find stretch_rtabmap)/rviz/rtab_navigation.rviz"/>
</group>
</launch>
</launch>

+ 4
- 4
stretch_rtabmap/launch/start_rtab.launch View File

@ -5,7 +5,7 @@
<arg name="database_path" default="rtabmap.db"/>
<arg name="args" default="-d"/> <!--Possible arg -d to delete database on startup-->
<arg name="wait_for_transform" default="0.2"/>
<arg name="wait_for_transform" default="0.2"/>
<arg name="move_base_config"/>
@ -26,7 +26,7 @@
<arg name="localization" value="$(arg localization)"/>
<arg name="args" value="$(arg args)"/>
<arg name="database_path" default="$(arg database_path)"/>
<arg name="wait_for_transform" default="$(arg wait_for_transform)"/>
<arg name="wait_for_transform" default="$(arg wait_for_transform)"/>
<arg name="pointcloud_topic" value="$(arg pointcloud_topic)"/>
<arg name="cmd_vel_topic" value="/stretch/cmd_vel"/>
<arg name="odom_topic" default="$(arg odom_topic)"/>
@ -53,7 +53,7 @@
<arg name="localization" value="$(arg localization)"/>
<arg name="args" value="$(arg args)"/>
<arg name="database_path" default="$(arg database_path)"/>
<arg name="wait_for_transform" default="$(arg wait_for_transform)"/>
<arg name="wait_for_transform" default="$(arg wait_for_transform)"/>
<arg name="pointcloud_topic" value="$(arg pointcloud_topic)"/>
<arg name="cmd_vel_topic" value="/stretch/cmd_vel"/>
<arg name="odom_topic" default="$(arg odom_topic)"/>
@ -62,4 +62,4 @@
<arg name="rgb_camera_info" default="$(arg rgb_camera_info)"/>
</include>
</group>
</launch>
</launch>

Loading…
Cancel
Save