Skip to content

Commit

Permalink
Merge pull request #7 from Alpaca-zip/fix/params
Browse files Browse the repository at this point in the history
Fix/params
  • Loading branch information
Alpaca-zip authored Jan 1, 2024
2 parents 7e838c9 + f181ce3 commit 2f3f6a8
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 11 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ More info : [e-Manual](https://emanual.robotis.com/docs/en/platform/turtlebot3/n
- `~map_file`: Path to the configuration file (yaml) for the occupancy grid map.
- `~test_folder`: A debug folder primarily used for debugging the Visibility Graph algorithm.
- `~down_scale_factor`: A factor for downscaling the occupancy grid map. Please reduce this value if optimization is taking too long.
- `~clearance`: The required clearance for the robot to navigate. It has to be at least half the maximum width of the robot. This is also used for obstacle detection.
- `~robot_radius`: Specifies the radius of the robot. This is mainly used for obstacle detection.
- `~odom_topic`: The name of the odometry topic.
- `~scan_topic`: The name of the LaserScan topic.
- `~vel_linear`: Linear velocity.
Expand Down
4 changes: 2 additions & 2 deletions launch/include/vgraph_planner.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="map_file" default="$(find vgraph_nav)/map/map.yaml"/>
<arg name="test_folder" default="$(find vgraph_nav)/test"/>
<arg name="down_scale_factor" default="0.1"/>
<arg name="clearance" default="0.1"/>
<arg name="robot_radius" default="0.1"/>
<arg name="odom_topic" default="/odom"/>
<arg name="scan_topic" default="/scan"/>
<arg name="vel_linear" default="0.1"/>
Expand All @@ -16,7 +16,7 @@
<param name="~map_file" value="$(arg map_file)"/>
<param name="~test_folder" value="$(arg test_folder)"/>
<param name="~down_scale_factor" value="$(arg down_scale_factor)"/>
<param name="~clearance" value="$(arg clearance)"/>
<param name="~robot_radius" value="$(arg robot_radius)"/>
<param name="~odom_topic" value="$(arg odom_topic)"/>
<param name="~scan_topic" value="$(arg scan_topic)"/>
<param name="~vel_linear" value="$(arg vel_linear)"/>
Expand Down
4 changes: 2 additions & 2 deletions launch/turtlebot3_vgraph_navigation.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="map_file" default="$(find vgraph_nav)/maps/map.yaml"/>
<arg name="test_folder" default="$(find vgraph_nav)/test"/>
<arg name="down_scale_factor" default="0.3"/>
<arg name="clearance" default="0.15"/>
<arg name="robot_radius" default="0.15"/>
<arg name="odom_topic" default="/odom"/>
<arg name="scan_topic" default="/scan"/>
<arg name="vel_linear" default="0.1"/>
Expand Down Expand Up @@ -39,7 +39,7 @@
<arg name="map_file" value="$(arg map_file)"/>
<arg name="test_folder" value="$(arg test_folder)"/>
<arg name="down_scale_factor" value="$(arg down_scale_factor)"/>
<arg name="clearance" value="$(arg clearance)"/>
<arg name="robot_radius" value="$(arg robot_radius)"/>
<arg name="odom_topic" value="$(arg odom_topic)"/>
<arg name="scan_topic" value="$(arg scan_topic)"/>
<arg name="vel_linear" value="$(arg vel_linear)"/>
Expand Down
12 changes: 6 additions & 6 deletions scripts/vgraph_planner.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/usr/bin/env python3
# -*- coding: utf-8 -*-

# Copyright (C) 2023 Alapaca-zip
# Copyright (C) 2023-2024 Alapaca-zip
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -35,7 +35,7 @@ def __init__(self):
self.map_file_path = rospy.get_param("~map_file", "map.yaml")
self.test_folder_path = rospy.get_param("~test_folder", "test")
self.down_scale_factor = rospy.get_param("~down_scale_factor", 0.1)
self.clearance = rospy.get_param("~clearance", 0.1)
self.robot_radius = rospy.get_param("~robot_radius", 0.1)
self.odom_topic = rospy.get_param("~odom_topic", "/odom")
self.scan_topic = rospy.get_param("~scan_topic", "/scan")
self.vel_linear = rospy.get_param("~vel_linear", 0.1)
Expand Down Expand Up @@ -98,7 +98,7 @@ def change_image_resolution(self, image, factor):
black_pixels = self.find_black_pixels(image)

enlarged_image, black_pixels = self.enlarge_black_pixels(
image, black_pixels, self.clearance
image, black_pixels, self.robot_radius
)

down_scaled_image = enlarged_image.resize(
Expand Down Expand Up @@ -665,14 +665,14 @@ def send_stop(self):
rospy.sleep(0.1)

def check_obstacle(self):
if self.clearance < self.range_min:
if self.robot_radius < self.range_min:
rospy.logwarn(
"Clearance is smaller than range_min. Please check the parameters."
"robot_radius is smaller than range_min. Please check the parameters."
)
return False

for distance in self.scan_data:
if self.range_min < distance < self.clearance:
if self.range_min < distance < self.robot_radius:
return True

return False
Expand Down

0 comments on commit 2f3f6a8

Please sign in to comment.