30 mapper_ = std::make_unique<karto::Mapper>();
58 mapper_->ClearLocalizationBuffer();
75 new_pose.
setOrigin(tf2::Vector3(pose.GetX(), pose.GetY(), 0.));
77 q.
setRPY(0., 0., pose.GetHeading());
87 transformed_pose.
SetX(pose.getOrigin().x());
88 transformed_pose.
SetY(pose.getOrigin().y());
90 return transformed_pose;
97 bool use_scan_matching;
98 if(nh.
getParam(
"use_scan_matching", use_scan_matching))
100 mapper_->setParamUseScanMatching(use_scan_matching);
103 bool use_scan_barycenter;
104 if(nh.
getParam(
"use_scan_barycenter", use_scan_barycenter))
106 mapper_->setParamUseScanBarycenter(use_scan_barycenter);
109 double minimum_travel_distance = 0.5;
110 if(nh.
getParam(
"minimum_travel_distance", minimum_travel_distance))
112 mapper_->setParamMinimumTravelDistance(minimum_travel_distance);
115 double minimum_travel_heading;
116 if(nh.
getParam(
"minimum_travel_heading", minimum_travel_heading))
118 mapper_->setParamMinimumTravelHeading(minimum_travel_heading);
121 int scan_buffer_size;
122 if(nh.
getParam(
"scan_buffer_size", scan_buffer_size))
124 mapper_->setParamScanBufferSize(scan_buffer_size);
127 double scan_buffer_maximum_scan_distance;
128 if(nh.
getParam(
"scan_buffer_maximum_scan_distance",
129 scan_buffer_maximum_scan_distance))
131 mapper_->setParamScanBufferMaximumScanDistance(scan_buffer_maximum_scan_distance);
134 double link_match_minimum_response_fine;
135 if(nh.
getParam(
"link_match_minimum_response_fine",
136 link_match_minimum_response_fine))
138 mapper_->setParamLinkMatchMinimumResponseFine(link_match_minimum_response_fine);
141 double link_scan_maximum_distance;
142 if(nh.
getParam(
"link_scan_maximum_distance", link_scan_maximum_distance))
144 mapper_->setParamLinkScanMaximumDistance(link_scan_maximum_distance);
147 double loop_search_maximum_distance;
148 if(nh.
getParam(
"loop_search_maximum_distance", loop_search_maximum_distance))
150 mapper_->setParamLoopSearchMaximumDistance(loop_search_maximum_distance);
153 bool do_loop_closing;
154 if(nh.
getParam(
"do_loop_closing", do_loop_closing))
156 mapper_->setParamDoLoopClosing(do_loop_closing);
159 int loop_match_minimum_chain_size;
160 if(nh.
getParam(
"loop_match_minimum_chain_size",
161 loop_match_minimum_chain_size))
163 mapper_->setParamLoopMatchMinimumChainSize(loop_match_minimum_chain_size);
166 double loop_match_maximum_variance_coarse;
167 if(nh.
getParam(
"loop_match_maximum_variance_coarse",
168 loop_match_maximum_variance_coarse))
170 mapper_->setParamLoopMatchMaximumVarianceCoarse(loop_match_maximum_variance_coarse);
173 double loop_match_minimum_response_coarse;
174 if(nh.
getParam(
"loop_match_minimum_response_coarse",
175 loop_match_minimum_response_coarse))
177 mapper_->setParamLoopMatchMinimumResponseCoarse(loop_match_minimum_response_coarse);
180 double loop_match_minimum_response_fine;
181 if(nh.
getParam(
"loop_match_minimum_response_fine",
182 loop_match_minimum_response_fine))
184 mapper_->setParamLoopMatchMinimumResponseFine(loop_match_minimum_response_fine);
188 double correlation_search_space_dimension;
189 if(nh.
getParam(
"correlation_search_space_dimension",
190 correlation_search_space_dimension))
192 mapper_->setParamCorrelationSearchSpaceDimension(correlation_search_space_dimension);
195 double correlation_search_space_resolution;
196 if(nh.
getParam(
"correlation_search_space_resolution",
197 correlation_search_space_resolution))
199 mapper_->setParamCorrelationSearchSpaceResolution(correlation_search_space_resolution);
202 double correlation_search_space_smear_deviation;
203 if(nh.
getParam(
"correlation_search_space_smear_deviation",
204 correlation_search_space_smear_deviation))
206 mapper_->setParamCorrelationSearchSpaceSmearDeviation(
207 correlation_search_space_smear_deviation);
211 double loop_search_space_dimension;
212 if(nh.
getParam(
"loop_search_space_dimension", loop_search_space_dimension))
214 mapper_->setParamLoopSearchSpaceDimension(loop_search_space_dimension);
217 double loop_search_space_resolution;
218 if(nh.
getParam(
"loop_search_space_resolution", loop_search_space_resolution))
220 mapper_->setParamLoopSearchSpaceResolution(loop_search_space_resolution);
223 double loop_search_space_smear_deviation;
224 if(nh.
getParam(
"loop_search_space_smear_deviation",
225 loop_search_space_smear_deviation))
227 mapper_->setParamLoopSearchSpaceSmearDeviation(loop_search_space_smear_deviation);
231 double distance_variance_penalty;
232 if(nh.
getParam(
"distance_variance_penalty", distance_variance_penalty))
234 mapper_->setParamDistanceVariancePenalty(distance_variance_penalty);
237 double angle_variance_penalty;
238 if(nh.
getParam(
"angle_variance_penalty", angle_variance_penalty))
240 mapper_->setParamAngleVariancePenalty(angle_variance_penalty);
243 double fine_search_angle_offset;
244 if(nh.
getParam(
"fine_search_angle_offset", fine_search_angle_offset))
246 mapper_->setParamFineSearchAngleOffset(fine_search_angle_offset);
249 double coarse_search_angle_offset;
250 if(nh.
getParam(
"coarse_search_angle_offset", coarse_search_angle_offset))
252 mapper_->setParamCoarseSearchAngleOffset(coarse_search_angle_offset);
255 double coarse_angle_resolution;
256 if(nh.
getParam(
"coarse_angle_resolution", coarse_angle_resolution))
258 mapper_->setParamCoarseAngleResolution(coarse_angle_resolution);
261 double minimum_angle_penalty;
262 if(nh.
getParam(
"minimum_angle_penalty", minimum_angle_penalty))
264 mapper_->setParamMinimumAnglePenalty(minimum_angle_penalty);
267 double minimum_distance_penalty;
268 if(nh.
getParam(
"minimum_distance_penalty", minimum_distance_penalty))
270 mapper_->setParamMinimumDistancePenalty(minimum_distance_penalty);
273 bool use_response_expansion;
274 if(nh.
getParam(
"use_response_expansion", use_response_expansion))
276 mapper_->setParamUseResponseExpansion(use_response_expansion);