Skip to content

Commit

Permalink
Fix benchmark nan issue and widen random hparam window
Browse files Browse the repository at this point in the history
  • Loading branch information
itskalvik committed Sep 16, 2024
1 parent 961e0b3 commit cdcb095
Show file tree
Hide file tree
Showing 2 changed files with 57 additions and 54 deletions.
45 changes: 30 additions & 15 deletions benchmarks/benchmark.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,8 +101,9 @@ def run_aipp(X_train, ipp_model, Xu_init, path2data,
if len(data_X_batch) == 0:
continue

# Skip param and path update for the last waypoint
if time_step == num_waypoints:
break # Skip param and path update for the last waypoint
break

# Init/update hyperparameters model
start_time = time()
Expand All @@ -115,6 +116,7 @@ def run_aipp(X_train, ipp_model, Xu_init, path2data,
print_params=False,
optimizer='scipy',
method='CG')
# Clip to avoid floats being interpreted as NANs
noise_variance = np.clip(noise_variance.numpy(), 1e-4, 5.0)
elif param_method=='SSGP':
param_model.update((np.array(data_X_batch),
Expand Down Expand Up @@ -160,7 +162,7 @@ def run_aipp(X_train, ipp_model, Xu_init, path2data,
total_time_ipp += end_time - start_time

budget_constraint = ipp_model.transform.constraints(curr_sol.reshape(-1, 2))
slack = -10 if num_robots==1 else -300
slack = -10 if num_robots==1 else -300 # Use larger slack for multi-robot case
budget_satisfied = budget_constraint > slack

return np.array(sol_data_X), np.array(sol_data_y), total_time_param, total_time_ipp, budget_satisfied
Expand All @@ -182,6 +184,9 @@ def main(dataset_path,
print(f'Dataset Path: {dataset_path}')
print(f'Range: {xrange}')
print(f'Distance Budget: {distance_budget}')
print('Methods:')
for method in methods:
print(f'-{method}')

fname = f'{dataset}_{num_robots}R_{sampling_rate}S'
if distance_budget:
Expand Down Expand Up @@ -220,16 +225,17 @@ def main(dataset_path,
max_steps=0,
print_params=False)

# Set lower and upper limits on the hyperparameters
# Sample random hyperparameters and
# set lower and upper limits on the hyperparameters
kernel.variance = gpflow.Parameter(
np.random.normal(1.0, 0.1),
np.random.normal(1.0, 0.25),
transform=tfp.bijectors.SoftClip(
gpflow.utilities.to_default_float(0.1),
gpflow.utilities.to_default_float(20.0),
),
)
kernel.lengthscales = gpflow.Parameter(
np.random.normal(1.0, 0.1),
np.random.normal(1.0, 0.25),
transform=tfp.bijectors.SoftClip(
gpflow.utilities.to_default_float(0.1),
gpflow.utilities.to_default_float(20.0),
Expand All @@ -251,6 +257,7 @@ def main(dataset_path,
print(f"Path length(s): {distances}")

if distance_budget:
# Set the distance budget to the length of the shortest path minus 5.0
budget = np.min(distances)-5.0
print(f'Distance Budget: {budget:.4f}')
transform.distance_budget = budget
Expand Down Expand Up @@ -456,12 +463,14 @@ def main(dataset_path,
results[num_waypoints][method]['ParamTime'].append(param_time)
results[num_waypoints][method]['IPPTime'].append(ipp_time)
results[num_waypoints][method]['RMSE'].append(rmse)
results[num_waypoints][method]['Constraint'].append(bool(budget_satisfied))
if distance_budget:
results[num_waypoints][method]['Constraint'].append(bool(budget_satisfied))

print(f'\n{method} Param Time: {param_time:.4f}')
print(f'{method} IPP Time: {ipp_time:.4f}')
print(f'{method} RMSE: {rmse:.4f}')
print(f'{method} Constraint: {budget_satisfied}')
if distance_budget:
print(f'{method} Constraint: {budget_satisfied}')

# Log the results to a json file
with open(f'{fname}.json', 'w', encoding='utf-8') as f:
Expand All @@ -473,27 +482,33 @@ def main(dataset_path,
parser.add_argument("--num_mc", type=int, default=10)
parser.add_argument("--num_robots", type=int, default=1)
parser.add_argument("--sampling_rate", type=int, default=2)
parser.add_argument("--distance_budget", type=bool, default=False)
parser.add_argument("--distance_budget", action='store_true')
parser.add_argument("--benchmark_discrete", action='store_true')
parser.add_argument("--dataset_path", type=str,
default='../datasets/bathymetry/bathymetry.tif')
args=parser.parse_args()

# Set the maximum distance (for each path) for the TSP solver
max_dist = 350 if args.num_robots==1 else 150

# Limit maximum waypoints/placements for multi robot case
max_range = 101 if args.num_robots==1 and args.sampling_rate==2 else 51
xrange = range(5, max_range, 5)

# Methods to benchmark
methods = ['Adaptive-SGP',
'Adaptive-CMA-ES',
'SGP',
'CMA-ES']

if args.sampling_rate == 2 and \
args.num_robots == 1 and \
not args.distance_budget:
methods.append('BO')
methods.append('Greedy-MI')
methods.append('Greedy-SGP')
methods.append('Discrete-SGP')
# Benchmark BO & discrete methods if benchmark_discrete is True
# and the remaining parameters are in their base cases
if args.sampling_rate == 2 and args.num_robots == 1 and \
not args.distance_budget and args.benchmark_discrete:
methods = ['BO',
'Greedy-MI',
'Greedy-SGP',
'Discrete-SGP']

main(args.dataset_path,
args.num_mc,
Expand Down
66 changes: 27 additions & 39 deletions benchmarks/plots.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -18,18 +18,38 @@
"metadata": {},
"outputs": [],
"source": [
"num_robots = 4\n",
"sampling_rate = 5\n",
"num_robots = 1\n",
"sampling_rate = 2\n",
"dataset = 'bathymetry'\n",
"budget = True\n",
"budget = False\n",
"benchmark = 2\n",
"\n",
"# Adaptive Methods\n",
"benchmark = ['Adaptive', 'Discrete', 'Continuous'][benchmark]\n",
"if benchmark=='Adaptive':\n",
" colors = ['C2', 'C3', 'C0', 'C1']\n",
" methods = ['Adaptive-SGP', \n",
" 'Adaptive-CMA-ES', \n",
" 'SGP', \n",
" 'CMA-ES']\n",
"# Discrete Methods\n",
"elif benchmark=='Discrete':\n",
" colors = ['C2', 'C3', 'C1']\n",
" methods = ['Discrete-SGP',\n",
" 'Greedy-MI', \n",
" 'Greedy-SGP']\n",
"# Continuous Methods\n",
"elif benchmark=='Continuous':\n",
" colors = ['C2', 'C3', 'C0']\n",
" methods = ['SGP', \n",
" 'CMA-ES', \n",
" 'BO']\n",
"\n",
"if budget:\n",
" budget = '_B'\n",
"else:\n",
" budget = ''\n",
"\n",
"remove_online = False\n",
"\n",
"filename = f'results/{dataset}_{num_robots}R_{sampling_rate}S{budget}.json'\n",
"save_filename = filename[:-5] + '-{}.pdf'\n",
"results = json.load(open(filename, 'r'))\n",
Expand All @@ -44,7 +64,6 @@
"ipp_time_std = defaultdict(list)\n",
"\n",
"xrange = np.array(list(results.keys())).astype(int)\n",
"\n",
"for num_sensors in results.keys():\n",
" for method in results[num_sensors].keys():\n",
" for metric in results[num_sensors][method].keys():\n",
Expand All @@ -64,38 +83,10 @@
" ipp_time[method].append(np.mean(data))\n",
" ipp_time_std[method].append(np.std(data))\n",
"\n",
"colors = ['C2', 'C3', 'C0', 'C1', 'C4', 'C5', 'C6', 'C7', 'C8', 'C9']\n",
"methods = ['Adaptive-SGP', \n",
" 'Adaptive-CMA-ES', \n",
" 'Online-SGP', \n",
" 'Online-CMA-ES']\n",
"\n",
"if sampling_rate == 2 and num_robots == 1 and len(budget) == 0:\n",
" methods.append('Online-BO')\n",
" methods.append('Online-Greedy-MI')\n",
" methods.append('Online-Greedy-SGP')\n",
" methods.append('Online-Discrete-SGP')\n",
"\n",
"'''\n",
"# Discrete Online Methods\n",
"colors = ['C2', 'C3', 'C1']\n",
"methods = ['Online-Discrete-SGP',\n",
" 'Online-Greedy-MI', \n",
" 'Online-Greedy-SGP']\n",
"\n",
"# Continuous Online Methods\n",
"methods = ['Online-SGP', \n",
" 'Online-CMA-ES', \n",
" 'Online-BO']\n",
"'''\n",
"\n",
"plt.figure()\n",
"for i, key in enumerate(methods):\n",
" xrange_ = xrange[:len(rmse[key])]\n",
" label = key.strip().replace('Adaptive-SGP', 'Adaptive-SGP (Ours)')\n",
" label = label.replace('CMA-ES', 'CIPP')\n",
" if remove_online:\n",
" label = label.replace('Online-', '')\n",
" plt.plot(xrange_, rmse[key], label=label, c=colors[i])\n",
" plt.fill_between(xrange_,\n",
" np.array(rmse[key])+rmse_std[key], \n",
Expand All @@ -105,16 +96,13 @@
"plt.legend(loc='upper right')\n",
"plt.xlabel(\"Number of Waypoints\")\n",
"plt.ylabel(\"RMSE\")\n",
"plt.savefig(f'{dataset}_{num_robots}R_{sampling_rate}S{budget}-RMSE.pdf', bbox_inches='tight')\n",
"plt.savefig(f'{dataset}_{num_robots}R_{sampling_rate}S{budget}-RMSE.png', bbox_inches='tight', dpi=500)\n",
"plt.show()\n",
"\n",
"plt.figure()\n",
"for i, key in enumerate(methods):\n",
" xrange_ = xrange[:len(ipp_time[key])]\n",
" label = key.strip().replace('Adaptive-SGP', 'Adaptive-SGP (Ours)')\n",
" label = label.replace('CMA-ES', 'CIPP')\n",
" if remove_online:\n",
" label = label.replace('Online-', '')\n",
" plt.plot(xrange_, ipp_time[key], label=label, c=colors[i])\n",
" plt.fill_between(xrange_,\n",
" np.array(ipp_time[key])+ipp_time_std[key], \n",
Expand All @@ -124,7 +112,7 @@
"plt.legend(loc='upper left')\n",
"plt.xlabel(\"Number of Waypoints\")\n",
"plt.ylabel(\"IPP Runtime (s)\")\n",
"plt.savefig(f'{dataset}_{num_robots}R_{sampling_rate}S{budget}-IPP.pdf', bbox_inches='tight')\n",
"plt.savefig(f'{dataset}_{num_robots}R_{sampling_rate}S{budget}-IPP.png', bbox_inches='tight', dpi=500)\n",
"plt.show()"
]
}
Expand Down

0 comments on commit cdcb095

Please sign in to comment.