29 #include <boost/bind.hpp> 30 #include <boost/thread/mutex.hpp> 47 #include "sensor_msgs/LaserScan.h" 48 #include "geometry_msgs/PoseWithCovarianceStamped.h" 49 #include "geometry_msgs/PoseArray.h" 50 #include "geometry_msgs/Pose.h" 51 #include "geometry_msgs/PoseStamped.h" 52 #include "nav_msgs/GetMap.h" 53 #include "nav_msgs/SetMap.h" 54 #include "std_srvs/Empty.h" 68 #include "dynamic_reconfigure/server.h" 69 #include "amcl/AMCLConfig.h" 74 #include <boost/foreach.hpp> 79 #define NEW_UNIFORM_SAMPLING 1 109 d2 = 2*M_PI - fabs(d1);
112 if(fabs(d1) < fabs(d2))
126 std::string out = in;
127 if ( ( !in.empty() ) && (in[0] ==
'/') )
144 void runFromBag(
const std::string &in_bag_fn,
bool trigger_global_localization =
false);
147 void savePoseToServer();
150 std::shared_ptr<tf2_ros::TransformBroadcaster>
tfb_;
151 std::shared_ptr<tf2_ros::TransformListener>
tfl_;
152 std::shared_ptr<tf2_ros::Buffer>
tf_;
161 static pf_vector_t uniformPoseGenerator(
void* arg);
162 #if NEW_UNIFORM_SAMPLING 166 bool globalLocalizationCallback(std_srvs::Empty::Request& req,
167 std_srvs::Empty::Response& res);
168 bool nomotionUpdateCallback(std_srvs::Empty::Request& req,
169 std_srvs::Empty::Response& res);
170 bool setMapCallback(nav_msgs::SetMap::Request& req,
171 nav_msgs::SetMap::Response& res);
173 void laserReceived(
const sensor_msgs::LaserScanConstPtr& laser_scan);
174 void initialPoseReceived(
const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
175 void handleInitialPoseMessage(
const geometry_msgs::PoseWithCovarianceStamped& msg);
176 void mapReceived(
const nav_msgs::OccupancyGridConstPtr& msg);
178 void handleMapMessage(
const nav_msgs::OccupancyGrid& msg);
179 void freeMapDependentMemory();
180 map_t* convertMap(
const nav_msgs::OccupancyGrid& map_msg );
181 void updatePoseFromServer();
182 void applyInitialPose();
241 bool getOdomPose(geometry_msgs::PoseStamped&
pose,
242 double& x,
double& y,
double& yaw,
243 const ros::Time& t,
const std::string& f);
270 dynamic_reconfigure::Server<amcl::AMCLConfig> *
dsrv_;
275 double alpha1_, alpha2_, alpha3_, alpha4_,
alpha5_;
277 double z_hit_,
z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_;
283 double init_pose_[3];
289 void reconfigureCB(amcl::AMCLConfig &config, uint32_t level);
296 #if NEW_UNIFORM_SAMPLING 300 #define USAGE "USAGE: amcl" 307 amcl_node_ptr->savePoseToServer();
321 amcl_node_ptr.reset(
new AmclNode());
328 else if ((argc >= 3) && (std::string(argv[1]) ==
"--run-from-bag"))
332 amcl_node_ptr->runFromBag(argv[2]);
334 else if ((argc == 4) && (std::string(argv[3]) ==
"--global-localization"))
336 amcl_node_ptr->runFromBag(argv[2],
true);
341 amcl_node_ptr.reset();
348 sent_first_transform_(false),
349 latest_tf_valid_(false),
356 initial_pose_hyp_(NULL),
357 first_map_received_(false),
358 first_reconfigure_call_(true)
404 std::string tmp_model_type;
405 private_nh_.
param(
"laser_model_type", tmp_model_type, std::string(
"likelihood_field"));
406 if(tmp_model_type ==
"beam")
408 else if(tmp_model_type ==
"likelihood_field")
410 else if(tmp_model_type ==
"likelihood_field_prob"){
415 ROS_WARN(
"Unknown laser model type \"%s\"; defaulting to likelihood_field model",
416 tmp_model_type.c_str());
421 if(tmp_model_type ==
"diff")
423 else if(tmp_model_type ==
"omni")
425 else if(tmp_model_type ==
"diff-corrected")
427 else if(tmp_model_type ==
"omni-corrected")
431 ROS_WARN(
"Unknown odom model type \"%s\"; defaulting to diff model",
432 tmp_model_type.c_str());
457 double bag_scan_period;
494 ROS_INFO(
"Subscribed to map topic.");
501 dynamic_reconfigure::Server<amcl::AMCLConfig>::CallbackType cb = boost::bind(&
AmclNode::reconfigureCB,
this, _1, _2);
502 dsrv_->setCallback(cb);
526 if(config.restore_defaults) {
529 config.restore_defaults =
false;
552 z_hit_ = config.laser_z_hit;
554 z_max_ = config.laser_z_max;
560 if(config.laser_model_type ==
"beam")
562 else if(config.laser_model_type ==
"likelihood_field")
564 else if(config.laser_model_type ==
"likelihood_field_prob")
567 if(config.odom_model_type ==
"diff")
569 else if(config.odom_model_type ==
"omni")
571 else if(config.odom_model_type ==
"diff-corrected")
573 else if(config.odom_model_type ==
"omni-corrected")
576 if(config.min_particles > config.max_particles)
578 ROS_WARN(
"You've set min_particles to be greater than max particles, this isn't allowed so they'll be set to be equal.");
579 config.max_particles = config.min_particles;
608 pf_z_ = config.kld_z;
621 pf_init(
pf_, pf_init_pose_mean, pf_init_pose_cov);
638 ROS_INFO(
"Initializing likelihood field model; this can take some time on large maps...");
643 ROS_INFO(
"Done initializing likelihood field model with probabilities.");
646 ROS_INFO(
"Initializing likelihood field model; this can take some time on large maps...");
649 ROS_INFO(
"Done initializing likelihood field model.");
674 std::vector<std::string> topics;
675 topics.push_back(std::string(
"tf"));
676 std::string scan_topic_name =
"base_scan";
677 topics.push_back(scan_topic_name);
703 if (trigger_global_localization)
705 std_srvs::Empty empty_srv;
719 tf2_msgs::TFMessage::ConstPtr tf_msg = msg.
instantiate<tf2_msgs::TFMessage>();
723 for (
size_t ii=0; ii<tf_msg->transforms.size(); ++ii)
725 tf_->setTransform(tf_msg->transforms[ii],
"rosbag_authority");
730 sensor_msgs::LaserScan::ConstPtr base_scan = msg.
instantiate<sensor_msgs::LaserScan>();
731 if (base_scan != NULL)
748 ROS_INFO(
"Bag complete, took %.1f seconds to process, shutting down", runtime);
751 double yaw, pitch, roll;
753 ROS_INFO(
"Final location %.3f, %.3f, %.3f with stamp=%f",
794 init_cov_[2] = (M_PI/12.0) * (M_PI/12.0);
798 if(!std::isnan(tmp_pos))
801 ROS_WARN(
"ignoring NAN in initial pose X position");
803 if(!std::isnan(tmp_pos))
806 ROS_WARN(
"ignoring NAN in initial pose Y position");
808 if(!std::isnan(tmp_pos))
811 ROS_WARN(
"ignoring NAN in initial pose Yaw");
813 if(!std::isnan(tmp_pos))
816 ROS_WARN(
"ignoring NAN in initial covariance XX");
818 if(!std::isnan(tmp_pos))
821 ROS_WARN(
"ignoring NAN in initial covariance YY");
823 if(!std::isnan(tmp_pos))
826 ROS_WARN(
"ignoring NAN in initial covariance AA");
835 ROS_WARN(
"No laser scan received (and thus no pose updates have been published) for %f seconds. Verify that data is being published on the %s topic.",
847 nav_msgs::GetMap::Request req;
848 nav_msgs::GetMap::Response resp;
852 ROS_WARN(
"Request for map failed; trying again...");
876 ROS_INFO(
"Received a %d X %d map @ %.3f m/pix\n",
879 msg.info.resolution);
882 ROS_WARN(
"Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could cause issues with reading published topics",
883 msg.header.frame_id.c_str(),
895 #if NEW_UNIFORM_SAMPLING 922 pf_init(
pf_, pf_init_pose_mean, pf_init_pose_cov);
939 ROS_INFO(
"Initializing likelihood field model; this can take some time on large maps...");
944 ROS_INFO(
"Done initializing likelihood field model.");
948 ROS_INFO(
"Initializing likelihood field model; this can take some time on large maps...");
951 ROS_INFO(
"Done initializing likelihood field model.");
987 map->
size_x = map_msg.info.width;
988 map->
size_y = map_msg.info.height;
989 map->
scale = map_msg.info.resolution;
997 if(map_msg.data[i] == 0)
999 else if(map_msg.data[i] == 100)
1019 double& x,
double& y,
double& yaw,
1020 const ros::Time& t,
const std::string& f)
1023 geometry_msgs::PoseStamped ident;
1025 ident.header.stamp = t;
1033 ROS_WARN(
"Failed to compute odom pose, skipping scan (%s)", e.what());
1036 x = odom_pose.pose.position.x;
1037 y = odom_pose.pose.position.y;
1048 #if NEW_UNIFORM_SAMPLING 1052 p.
v[0] =
MAP_WXGX(map, free_point.first);
1053 p.
v[1] =
MAP_WYGY(map, free_point.second);
1054 p.
v[2] =
drand48() * 2 * M_PI - M_PI;
1056 double min_x, max_x, min_y, max_y;
1065 ROS_DEBUG(
"Generating new uniform sample");
1068 p.
v[0] = min_x +
drand48() * (max_x - min_x);
1069 p.
v[1] = min_y +
drand48() * (max_y - min_y);
1070 p.
v[2] =
drand48() * 2 * M_PI - M_PI;
1084 std_srvs::Empty::Response& res)
1086 if(
map_ == NULL ) {
1090 ROS_INFO(
"Initializing with uniform distribution");
1093 ROS_INFO(
"Global initialisation done!");
1101 std_srvs::Empty::Response& res)
1110 nav_msgs::SetMap::Response& res)
1121 std::string laser_scan_frame_id =
stripSlash(laser_scan->header.frame_id);
1123 if(
map_ == NULL ) {
1127 int laser_index = -1;
1137 geometry_msgs::PoseStamped ident;
1138 ident.header.frame_id = laser_scan_frame_id;
1142 geometry_msgs::PoseStamped laser_pose;
1149 ROS_ERROR(
"Couldn't transform from %s to %s, " 1150 "even though the message notifier is in use",
1151 laser_scan_frame_id.c_str(),
1157 laser_pose_v.
v[0] = laser_pose.pose.position.x;
1158 laser_pose_v.
v[1] = laser_pose.pose.position.y;
1160 laser_pose_v.
v[2] = 0;
1161 lasers_[laser_index]->SetLaserPose(laser_pose_v);
1162 ROS_DEBUG(
"Received laser's pose wrt robot: %.3f %.3f %.3f",
1178 ROS_ERROR(
"Couldn't determine robot's pose associated with laser scan");
1206 bool force_publication =
false;
1219 force_publication =
true;
1234 odata.
delta = delta;
1243 bool resampled =
false;
1256 q.
setRPY(0.0, 0.0, laser_scan->angle_min);
1257 geometry_msgs::QuaternionStamped min_q, inc_q;
1258 min_q.header.stamp = laser_scan->header.stamp;
1259 min_q.header.frame_id =
stripSlash(laser_scan->header.frame_id);
1262 q.
setRPY(0.0, 0.0, laser_scan->angle_min + laser_scan->angle_increment);
1263 inc_q.header = min_q.header;
1272 ROS_WARN(
"Unable to transform min/max laser angles into base frame: %s",
1278 double angle_increment =
tf2::getYaw(inc_q.quaternion) - angle_min;
1281 angle_increment = fmod(angle_increment + 5*M_PI, 2*M_PI) - M_PI;
1283 ROS_DEBUG(
"Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min, angle_increment);
1289 ldata.
range_max = laser_scan->range_max;
1294 range_min = laser_scan->range_min;
1302 if(laser_scan->ranges[i] <= range_min)
1305 ldata.
ranges[i][0] = laser_scan->ranges[i];
1307 ldata.
ranges[i][1] = angle_min +
1308 (i * angle_increment);
1331 geometry_msgs::PoseArray cloud_msg;
1334 cloud_msg.poses.resize(
set->sample_count);
1335 for(
int i=0;i<
set->sample_count;i++)
1337 cloud_msg.poses[i].position.x =
set->samples[i].pose.v[0];
1338 cloud_msg.poses[i].position.y =
set->samples[i].pose.v[1];
1339 cloud_msg.poses[i].position.z = 0;
1341 q.
setRPY(0, 0,
set->samples[i].pose.v[2]);
1348 if(resampled || force_publication)
1351 double max_weight = 0.0;
1352 int max_weight_hyp = -1;
1353 std::vector<amcl_hyp_t> hyps;
1355 for(
int hyp_count = 0;
1363 ROS_ERROR(
"Couldn't get stats on cluster %d", hyp_count);
1367 hyps[hyp_count].weight = weight;
1368 hyps[hyp_count].pf_pose_mean = pose_mean;
1369 hyps[hyp_count].pf_pose_cov = pose_cov;
1371 if(hyps[hyp_count].weight > max_weight)
1373 max_weight = hyps[hyp_count].weight;
1374 max_weight_hyp = hyp_count;
1378 if(max_weight > 0.0)
1380 ROS_DEBUG(
"Max weight pose: %.3f %.3f %.3f",
1381 hyps[max_weight_hyp].pf_pose_mean.v[0],
1382 hyps[max_weight_hyp].pf_pose_mean.v[1],
1383 hyps[max_weight_hyp].pf_pose_mean.v[2]);
1391 geometry_msgs::PoseWithCovarianceStamped p;
1394 p.header.stamp = laser_scan->header.stamp;
1396 p.pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
1397 p.pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
1400 q.
setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
1404 for(
int i=0; i<2; i++)
1406 for(
int j=0; j<2; j++)
1411 p.pose.covariance[6*i+j] =
set->cov.m[i][j];
1417 p.pose.covariance[6*5+5] =
set->cov.m[2][2];
1432 ROS_DEBUG(
"New pose: %6.3f %6.3f %6.3f",
1433 hyps[max_weight_hyp].pf_pose_mean.v[0],
1434 hyps[max_weight_hyp].pf_pose_mean.v[1],
1435 hyps[max_weight_hyp].pf_pose_mean.v[2]);
1438 geometry_msgs::PoseStamped odom_to_map;
1442 q.
setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
1443 tf2::Transform tmp_tf(q, tf2::Vector3(hyps[max_weight_hyp].pf_pose_mean.v[0],
1444 hyps[max_weight_hyp].pf_pose_mean.v[1],
1447 geometry_msgs::PoseStamped tmp_tf_stamped;
1449 tmp_tf_stamped.header.stamp = laser_scan->header.stamp;
1456 ROS_DEBUG(
"Failed to subtract base to odom transform");
1467 ros::Time transform_expiration = (laser_scan->header.stamp +
1469 geometry_msgs::TransformStamped tmp_tf_stamped;
1471 tmp_tf_stamped.header.stamp = transform_expiration;
1475 this->
tfb_->sendTransform(tmp_tf_stamped);
1490 ros::Time transform_expiration = (laser_scan->header.stamp +
1492 geometry_msgs::TransformStamped tmp_tf_stamped;
1494 tmp_tf_stamped.header.stamp = transform_expiration;
1497 this->
tfb_->sendTransform(tmp_tf_stamped);
1523 if(msg.header.frame_id ==
"")
1526 ROS_WARN(
"Received initial pose with empty frame_id. You should always supply a frame_id.");
1531 ROS_WARN(
"Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
1539 geometry_msgs::TransformStamped tx_odom;
1555 ROS_WARN(
"Failed to transform initial pose in time (%s)", e.what());
1563 pose_new = pose_old * tx_odom_tf2;
1567 ROS_INFO(
"Setting pose (%.6f): %.3f %.3f %.3f",
1574 pf_init_pose_mean.
v[0] = pose_new.
getOrigin().x();
1575 pf_init_pose_mean.
v[1] = pose_new.
getOrigin().y();
1579 for(
int i=0; i<2; i++)
1581 for(
int j=0; j<2; j++)
1583 pf_init_pose_cov.m[i][j] = msg.pose.covariance[6*i+j];
1586 pf_init_pose_cov.m[2][2] = msg.pose.covariance[6*5+5];
1620 diagnostic_status.
add(
"std_x", std_x);
1621 diagnostic_status.
add(
"std_y", std_y);
1622 diagnostic_status.
add(
"std_yaw", std_yaw);
1629 diagnostic_status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Too large");
1633 diagnostic_status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"OK");
ros::ServiceServer set_map_srv_
bool globalLocalizationCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
double beam_skip_distance_
static pf_vector_t uniformPoseGenerator(void *arg)
ros::Time last_laser_received_ts_
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
double beam_skip_error_threshold_
boost::shared_ptr< AmclNode > amcl_node_ptr
std::string global_frame_id_
dynamic_reconfigure::Server< amcl::AMCLConfig > * dsrv_
void open(std::string const &filename, uint32_t mode=bagmode::Read)
ros::Subscriber initial_pose_sub_
std::map< std::string, int > frame_to_laser_
#define MAP_VALID(map, i, j)
void summary(unsigned char lvl, const std::string s)
ros::Publisher particlecloud_pub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
geometry_msgs::PoseStamped latest_odom_pose_
pf_vector_t(* pf_init_model_fn_t)(void *init_data)
tf2::Transform latest_tf_
void setHardwareID(const std::string &hwid)
void checkLaserReceived(const ros::TimerEvent &event)
bool call(const std::string &service_name, MReq &req, MRes &res)
std::string base_frame_id_
double std_warn_level_yaw_
void SetModelBeam(double z_hit, double z_short, double z_max, double z_rand, double sigma_hit, double lambda_short, double chi_outlier)
static double normalize(double z)
void mapReceived(const nav_msgs::OccupancyGridConstPtr &msg)
pf_vector_t pf_vector_zero()
double beam_skip_threshold_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
pf_t * pf_alloc(int min_samples, int max_samples, double alpha_slow, double alpha_fast, pf_init_model_fn_t random_pose_fn, void *random_pose_data)
static double drand48(void)
#define MAP_INDEX(map, i, j)
void add(const std::string &name, TaskFunction f)
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ros::Time last_cloud_pub_time
void updatePoseFromServer()
int main(int argc, char **argv)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void sigintHandler(int sig)
virtual bool UpdateAction(pf_t *pf, AMCLSensorData *data)
odom_model_t odom_model_type_
void SetModel(odom_model_t type, double alpha1, double alpha2, double alpha3, double alpha4, double alpha5=0)
void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::vector< AMCLLaser *> lasers_
void getEulerYPR(tf2Scalar &yaw, tf2Scalar &pitch, tf2Scalar &roll, unsigned int solution_number=1) const
int pf_get_cluster_stats(pf_t *pf, int cluster, double *weight, pf_vector_t *mean, pf_matrix_t *cov)
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
bool selective_resampling_
void add(const MEvent &evt)
ros::Subscriber initial_pose_sub_old_
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::ServiceServer nomotion_update_srv_
void publish(const boost::shared_ptr< M > &message) const
std::string odom_frame_id_
bool first_reconfigure_call_
Duration & fromSec(double t)
void handleMapMessage(const nav_msgs::OccupancyGrid &msg)
std::vector< bool > lasers_update_
static double angle_diff(double a, double b)
static std::vector< std::pair< int, int > > free_space_indices
ros::Duration cloud_pub_interval
pf_matrix_t pf_matrix_zero()
void laserReceived(const sensor_msgs::LaserScanConstPtr &laser_scan)
amcl_hyp_t * initial_pose_hyp_
void standardDeviationDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &diagnostic_status)
std::shared_ptr< tf2_ros::TransformListener > tfl_
std::shared_ptr< tf2_ros::TransformBroadcaster > tfb_
ros::Duration transform_tolerance_
ros::Time save_pose_last_time
void pf_set_selective_resampling(pf_t *pf, int selective_resampling)
map_t * convertMap(const nav_msgs::OccupancyGrid &map_msg)
std::shared_ptr< tf2_ros::Buffer > tf_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void SetModelLikelihoodField(double z_hit, double z_rand, double sigma_hit, double max_occ_dist)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
bool sent_first_transform_
void pf_init_model(pf_t *pf, pf_init_model_fn_t init_fn, void *init_data)
ros::WallDuration bag_scan_period_
static const std::string scan_topic_
#define ROS_WARN_STREAM(args)
bool hasParam(const std::string &key) const
boost::shared_ptr< T > instantiate() const
double getYaw(const A &a)
ros::ServiceServer global_loc_srv_
ros::Timer check_laser_timer_
geometry_msgs::PoseWithCovarianceStamped last_published_pose
boost::recursive_mutex configuration_mutex_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void pf_update_resample(pf_t *pf)
void map_free(map_t *map)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void freeMapDependentMemory()
diagnostic_updater::Updater diagnosic_updater_
ros::Duration gui_publish_period
laser_model_t laser_model_type_
amcl::AMCLConfig default_config_
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
ros::Duration save_pose_period
bool nomotionUpdateCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void convert(const A &a, B &b)
ROSCPP_DECL void shutdown()
void reconfigureCB(amcl::AMCLConfig &config, uint32_t level)
void runFromBag(const std::string &in_bag_fn, bool trigger_global_localization=false)
Uses TF and LaserScan messages from bag file to drive AMCL instead.
ros::NodeHandle private_nh_
void add(const std::string &key, const T &val)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
message_filters::Subscriber< sensor_msgs::LaserScan > * laser_scan_sub_
void handleInitialPoseMessage(const geometry_msgs::PoseWithCovarianceStamped &msg)
std::string const & getTopic() const
ros::Duration laser_check_interval_
std::string stripSlash(const std::string &in)
void SetModelLikelihoodFieldProb(double z_hit, double z_rand, double sigma_hit, double max_occ_dist, bool do_beamskip, double beam_skip_distance, double beam_skip_threshold, double beam_skip_error_threshold)
tf2_ros::MessageFilter< sensor_msgs::LaserScan > * laser_scan_filter_
bool getOdomPose(geometry_msgs::PoseStamped &pose, double &x, double &y, double &yaw, const ros::Time &t, const std::string &f)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
double laser_likelihood_max_dist_
pf_vector_t pf_odom_pose_
bool setMapCallback(nav_msgs::SetMap::Request &req, nav_msgs::SetMap::Response &res)
void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
Connection registerCallback(const C &callback)