1 Star 0 Fork 0

chaosir1991/rbpf-gmapping

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
文件
该仓库未声明开源许可证文件(LICENSE),使用请关注具体项目描述及其代码上游依赖。
克隆/下载
Scan_Matching.m 1.29 KB
一键复制 编辑 原始数据 按行查看 历史
Adrian Llopart 提交于 2016-04-14 12:55 . Initial Update of all files
function p_zt = Scan_Matching( true_scan,pose,map,UsableArea)
%% Calculates the probability function for a specific location given it own map and the true scan that you should see
map=flipud(map);
%Extract Pose in grid coordinates
xg = round(pose(1));
yg = round(pose(2));
theta = pose(3);
gridsizex=size(map,1);
gridsizey=size(map,2);
theta_m=[theta*ones(1, size(true_scan, 2)); zeros(1, size(true_scan, 2))];
grid_pos= [xg*ones(1, size(true_scan, 2)) ; yg*ones(1, size(true_scan, 2))];
p_cell=zeros(1,size(true_scan, 2));
%Find indexes of scans that are close to max_range
find=true_scan(2,:)>UsableArea;
true_scan(:,(find==1))=[];
pos_scan=Polar2Cart(true_scan + repmat([-theta; 0], 1, size(true_scan, 2))) + repmat([xg; yg], 1, size(true_scan, 2));
pos_scan(pos_scan<=1)=1;
pos_scan(pos_scan(1,:)>gridsizey)=gridsizey;
pos_scan(pos_scan(2,:)>gridsizex)=gridsizex;
pos_scan=round(pos_scan);
for i=1:size(pos_scan,2)
p_cell(i)=map(pos_scan(1,i), pos_scan(2,i));
end
p_zt=sum(p_cell, 'omitnan');%/count;
% p_zt= prod(p_cell);
%% Visualize results:
figure(9)
hold on;
imagesc(map);
plot(pos_scan(1,:), pos_scan(2,:), '.r');
plot(xg, yg, 'dk');
hold off;
end
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
1
https://gitee.com/chaosir1991/rbpf-gmapping.git
git@gitee.com:chaosir1991/rbpf-gmapping.git
chaosir1991
rbpf-gmapping
rbpf-gmapping
master

搜索帮助

0d507c66 1850385 C8b1a773 1850385