|
void | cbCloud (const sensor_msgs::PointCloud2::ConstPtr &msg) |
|
bool | cbExpansionReset (std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response) |
|
bool | cbGlobalLocalization (std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response) |
|
void | cbImu (const sensor_msgs::Imu::ConstPtr &msg) |
|
void | cbLandmark (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg) |
|
void | cbMapcloud (const sensor_msgs::PointCloud2::ConstPtr &msg) |
|
void | cbMapcloudUpdate (const sensor_msgs::PointCloud2::ConstPtr &msg) |
|
void | cbOdom (const nav_msgs::Odometry::ConstPtr &msg) |
|
void | cbPosition (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg) |
|
bool | cbResizeParticle (mcl_3dl_msgs::ResizeParticleRequest &request, mcl_3dl_msgs::ResizeParticleResponse &response) |
|
void | publishParticles () |
|
Definition at line 95 of file mcl_3dl.cpp.
mcl_3dl::MCL3dlNode::MCL3dlNode |
( |
| ) |
|
|
inline |
mcl_3dl::MCL3dlNode::~MCL3dlNode |
( |
| ) |
|
|
inline |
void mcl_3dl::MCL3dlNode::cbCloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
inlineprotected |
bool mcl_3dl::MCL3dlNode::cbExpansionReset |
( |
std_srvs::TriggerRequest & |
request, |
|
|
std_srvs::TriggerResponse & |
response |
|
) |
| |
|
inlineprotected |
bool mcl_3dl::MCL3dlNode::cbGlobalLocalization |
( |
std_srvs::TriggerRequest & |
request, |
|
|
std_srvs::TriggerResponse & |
response |
|
) |
| |
|
inlineprotected |
void mcl_3dl::MCL3dlNode::cbImu |
( |
const sensor_msgs::Imu::ConstPtr & |
msg | ) |
|
|
inlineprotected |
void mcl_3dl::MCL3dlNode::cbLandmark |
( |
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & |
msg | ) |
|
|
inlineprotected |
void mcl_3dl::MCL3dlNode::cbMapcloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
inlineprotected |
void mcl_3dl::MCL3dlNode::cbMapcloudUpdate |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
inlineprotected |
void mcl_3dl::MCL3dlNode::cbMapUpdateTimer |
( |
const ros::TimerEvent & |
event | ) |
|
|
inline |
void mcl_3dl::MCL3dlNode::cbOdom |
( |
const nav_msgs::Odometry::ConstPtr & |
msg | ) |
|
|
inlineprotected |
void mcl_3dl::MCL3dlNode::cbPosition |
( |
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & |
msg | ) |
|
|
inlineprotected |
bool mcl_3dl::MCL3dlNode::cbResizeParticle |
( |
mcl_3dl_msgs::ResizeParticleRequest & |
request, |
|
|
mcl_3dl_msgs::ResizeParticleResponse & |
response |
|
) |
| |
|
inlineprotected |
bool mcl_3dl::MCL3dlNode::configure |
( |
| ) |
|
|
inline |
void mcl_3dl::MCL3dlNode::publishParticles |
( |
| ) |
|
|
inlineprotected |
int mcl_3dl::MCL3dlNode::cnt_accum_ |
|
protected |
int mcl_3dl::MCL3dlNode::cnt_measure_ |
|
protected |
std::default_random_engine mcl_3dl::MCL3dlNode::engine_ |
|
protected |
std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::f_acc_[3] |
|
protected |
std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::f_ang_[3] |
|
protected |
std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::f_pos_[3] |
|
protected |
bool mcl_3dl::MCL3dlNode::fake_imu_ |
|
protected |
bool mcl_3dl::MCL3dlNode::fake_odom_ |
|
protected |
std::map<std::string, std::string> mcl_3dl::MCL3dlNode::frame_ids_ |
|
protected |
size_t mcl_3dl::MCL3dlNode::frame_num_ |
|
protected |
std::map<std::string, bool> mcl_3dl::MCL3dlNode::frames_ |
|
protected |
std::vector<std::string> mcl_3dl::MCL3dlNode::frames_v_ |
|
protected |
size_t mcl_3dl::MCL3dlNode::global_localization_fix_cnt_ |
|
protected |
bool mcl_3dl::MCL3dlNode::has_imu_ |
|
protected |
bool mcl_3dl::MCL3dlNode::has_map_ |
|
protected |
bool mcl_3dl::MCL3dlNode::has_odom_ |
|
protected |
Quat mcl_3dl::MCL3dlNode::imu_quat_ |
|
protected |
std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::localize_rate_ |
|
protected |
ros::Time mcl_3dl::MCL3dlNode::localized_last_ |
|
protected |
ros::Time mcl_3dl::MCL3dlNode::match_output_last_ |
|
protected |
bool mcl_3dl::MCL3dlNode::output_pcd_ |
|
protected |
bool mcl_3dl::MCL3dlNode::publish_tf_ |
|
protected |
std::random_device mcl_3dl::MCL3dlNode::seed_gen_ |
|
protected |
The documentation for this class was generated from the following file: