Skip to content

Commit 5be1b1a

Browse files
author
Helena Jäger
committed
changed default params
1 parent 77e515f commit 5be1b1a

File tree

2 files changed

+11
-8
lines changed

2 files changed

+11
-8
lines changed

bitbots_navigation/bitbots_path_planning/bitbots_path_planning/planner.py

+8-5
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ def step(self) -> Path:
4545

4646

4747
class VisibilityPlanner(Planner):
48-
def __init__(self, node: NodeWithConfig, buffer: tf2.Buffer) -> None:
48+
def __init__(self, node: NodeWithConfig, buffer: tf2.BufferInterface) -> None:
4949
self.node = node
5050
self.buffer = buffer
5151
self.robots = []
@@ -75,7 +75,7 @@ def set_ball(self, ball: PoseWithCovarianceStamped) -> None:
7575
point.point = ball.pose.pose.position
7676
try:
7777
tf_point = self.buffer.transform(point, self.frame).point
78-
self.ball = RoundObstacle(center=(tf_point.x, tf_point.y), radius=self.node.config.map.ball_diameter)
78+
self.ball = RoundObstacle(center=(tf_point.x, tf_point.y), radius=self.node.config.map.ball_diameter / 2.0)
7979
except (tf2.ConnectivityException, tf2.LookupException, tf2.ExtrapolationException) as e:
8080
self.ball = None
8181
self.node.get_logger().warn(str(e))
@@ -113,8 +113,8 @@ def step(self) -> Path:
113113
).transform.translation
114114
start = (my_position.x, my_position.y)
115115
config = ObstacleMapConfig(dilate=self.node.config.map.inflation.dilate, num_vertices=12)
116-
obstacles = self.robots
117-
if self.ball_obstacle_active and self.ball is not None:
116+
obstacles = self.robots.copy()
117+
if self.ball is not None:
118118
obstacles.append(self.ball)
119119
omap = ObstacleMap(config, obstacles)
120120
path = omap.shortest_path(start, goal)
@@ -124,8 +124,11 @@ def map_to_pose(position):
124124
pose.pose.position.x = position[0]
125125
pose.pose.position.y = position[1]
126126
return pose
127+
128+
poses = list(map(map_to_pose, path))
129+
poses.append(self.goal)
127130

128131
return Path(
129132
header=Header(frame_id=self.frame, stamp=self.node.get_clock().now().to_msg()),
130-
poses=list(map(map_to_pose, path)),
133+
poses=poses,
131134
)

bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ bitbots_path_planning:
6767
inflation:
6868
dilate:
6969
type: double
70-
default_value: 0.25
70+
default_value: 0.3
7171
description: 'The dilation value for the inflation'
7272
read_only: true
7373
blur:
@@ -79,7 +79,7 @@ bitbots_path_planning:
7979
controller:
8080
carrot_distance:
8181
type: int
82-
default_value: 4
82+
default_value: 1
8383
description: 'The distance to the carrot that we want to reach on the path'
8484
validation:
8585
bounds<>: [0, 100]
@@ -109,7 +109,7 @@ bitbots_path_planning:
109109
bounds<>: [0.0, 1.0]
110110
smoothing_tau:
111111
type: double
112-
default_value: 1.0
112+
default_value: 0.1
113113
description: 'This is the time constant of the exponential smoothing filter. The higher the value, the more smoothing is applied. It denotes the time after which a unit step function input signal reaches 63% (1-1/e) of its original strength. In other words, it denotes the time it takes for a new input to be 63% integrated into the output. It is update rate independent!'
114114
validation:
115115
bounds<>: [0.0, 1.0]

0 commit comments

Comments
 (0)