Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

local costmap long and narrow. local inflation lower. rosparam for cl… #42

Open
wants to merge 1 commit into
base: simple_plan
Choose a base branch
from
Open
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
8 changes: 4 additions & 4 deletions src/grudsby_costmap/config/local_costmap.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@ local_costmap:
rolling_window: true
track_unknown_space: false
inf_is_valid: true
height: 6.0
width: 6.0
height: 2.0
width: 11

plugins:
- {name: obstacles_laser_local, type: "costmap_2d::ObstacleLayer"}
- {name: inflation, type: "costmap_2d::InflationLayer"}
- {name: obstacles_laser_local, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_dymamic, type: "costmap_2d::InflationLayer"}
4 changes: 4 additions & 0 deletions src/grudsby_costmap/config/shared_costmap.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -89,3 +89,7 @@ obstacles_laser_local:
inflation:
inflation_radius: 1.0
cost_scaling_factor: 1.0

inflation_dynamic:
inflation_radius: 0.1
cost_scaling_factor: 1.0
5 changes: 4 additions & 1 deletion src/grudsby_launch/launch/dynamic.launch
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ Grudsby will stop if an obstacle is encountered
<!-- GPS launch file-->
<!--<include file="$(find nmea_navsat_driver)/launch/launch_nmea_driver.launch"/> -->
<node pkg="grudsby_tools" type="gps_spoofer.py" name="gps_spoofer"/>
<node pkg="grudsby_costmap" type="obstacles.py" name="obstacles"/> -->
<node pkg="grudsby_costmap" type="obstacles.py" name="obstacles"/> -->

<!-- Navigation nodes -->
<include file="$(find grudsby_localization)/launch/grudsby_localization_ekf.launch"/>
Expand Down Expand Up @@ -68,6 +68,9 @@ Grudsby will stop if an obstacle is encountered
</node>

<node pkg="scan_filter" type="scan_inf_repeater.py" name="scan_inf_repeater"/>
<rosparam>
clip_scan : True
</rosparam>
<!--
<node name="gucci_gang" pkg="gucci_gang" type="gucci_gang"/>
-->
Expand Down
9 changes: 7 additions & 2 deletions src/grudsby_vision/scan_filter/scripts/scan_inf_repeater.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,12 @@

from sensor_msgs.msg import LaserScan

MAX_RANGE = 8
MAX_RANGE = 4.1

class DiffTf:
def __init__(self):
rospy.init_node("scan_repeater")
self.clip_range = rospy.get_param("clip_scan",False)
self.nodename = rospy.get_name()
rospy.loginfo("-I- %s started" % self.nodename)
self.rate = 100
Expand Down Expand Up @@ -51,7 +52,11 @@ def laserResponseCallback(self, msg):
for i in range ( window_size , len ( fix_nans )-window_size ):
neighborhood = fix_nans [ i-window_size : i + window_size + 1]
neighborhood.sort ( )
output [ i ] = neighborhood [ int ( math.floor ( window_size / 2 ) ) ]
if self.clip_range:
output [ i ] = min ( MAX_RANGE ,
neighborhood [ int ( math.floor ( window_size / 2 ) ) ] )
else:
output [ i ] = neighborhood [ int ( math.floor ( window_size / 2 ) ) ]

cloud_out.ranges = tuple (output)
self.laserPub.publish(cloud_out)
Expand Down