Go to the documentation of this file. 1 #ifndef SELF_LOCALIZER_H
2 #define SELF_LOCALIZER_H
8 #include <nav_msgs/OccupancyGrid.h>
9 #include <geometry_msgs/PoseArray.h>
10 #include <sensor_msgs/LaserScan.h>
29 LaserData(
const sensor_msgs::LaserScan::ConstPtr& scan);
49 void convertMap(
const nav_msgs::OccupancyGrid& map_msg);
51 void process(
const sensor_msgs::LaserScan::ConstPtr& scan);
void convertMap(const nav_msgs::OccupancyGrid &map_msg)
void process(const sensor_msgs::LaserScan::ConstPtr &scan)
ros::Publisher mParticlePublisher
void publishParticleCloud()
SelfLocalizer(bool publish=true)
static tf::StampedTransform mLastPose
static double sLamdaShort
static pf_vector_t sLaserPose
static double calculateLikelihoodFieldModel(LaserData *data, pf_sample_set_t *set)
static double sLikelihoodMaxDist
double(* pf_sensor_model_fn_t)(void *sensor_data, struct _pf_sample_set_t *set)
tf::Transform getBestPose()
LaserData(const sensor_msgs::LaserScan::ConstPtr &scan)
OdometryData(const tf::StampedTransform &pNewPose, const tf::StampedTransform &pLastPose)
pf_sensor_model_fn_t mSensorModelFunction
std::string mOdometryFrame
tf::TransformListener mTransformListener
static pf_vector_t distributeParticles(void *map)
static double calculateMoveModel(OdometryData *data, pf_sample_set_t *set)
void(* pf_action_model_fn_t)(void *action_data, struct _pf_sample_set_t *set)
tf::Transform mMapToOdometry
static double calculateBeamModel(LaserData *data, pf_sample_set_t *set)
pf_action_model_fn_t mActionModelFunction
tf::StampedTransform getMapToOdometry()
nav2d_localizer
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:18