Definition at line 103 of file mcl_3dl.cpp.
◆ PointType
◆ MCL3dlNode()
mcl_3dl::MCL3dlNode::MCL3dlNode |
( |
| ) |
|
|
inline |
◆ ~MCL3dlNode()
mcl_3dl::MCL3dlNode::~MCL3dlNode |
( |
| ) |
|
|
inline |
◆ accumClear()
void mcl_3dl::MCL3dlNode::accumClear |
( |
| ) |
|
|
inlineprotected |
◆ accumCloud()
bool mcl_3dl::MCL3dlNode::accumCloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbCloud()
void mcl_3dl::MCL3dlNode::cbCloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbExpansionReset()
bool mcl_3dl::MCL3dlNode::cbExpansionReset |
( |
std_srvs::TriggerRequest & |
request, |
|
|
std_srvs::TriggerResponse & |
response |
|
) |
| |
|
inlineprotected |
◆ cbGlobalLocalization()
bool mcl_3dl::MCL3dlNode::cbGlobalLocalization |
( |
std_srvs::TriggerRequest & |
request, |
|
|
std_srvs::TriggerResponse & |
response |
|
) |
| |
|
inlineprotected |
◆ cbImu()
void mcl_3dl::MCL3dlNode::cbImu |
( |
const sensor_msgs::Imu::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbLandmark()
void mcl_3dl::MCL3dlNode::cbLandmark |
( |
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbLoadPCD()
bool mcl_3dl::MCL3dlNode::cbLoadPCD |
( |
mcl_3dl_msgs::LoadPCD::Request & |
req, |
|
|
mcl_3dl_msgs::LoadPCD::Response & |
resp |
|
) |
| |
|
inlineprotected |
◆ cbMapcloud()
void mcl_3dl::MCL3dlNode::cbMapcloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbMapcloudUpdate()
void mcl_3dl::MCL3dlNode::cbMapcloudUpdate |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbMapUpdateTimer()
void mcl_3dl::MCL3dlNode::cbMapUpdateTimer |
( |
const ros::TimerEvent & |
event | ) |
|
|
inline |
◆ cbOdom()
void mcl_3dl::MCL3dlNode::cbOdom |
( |
const nav_msgs::Odometry::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbPosition()
void mcl_3dl::MCL3dlNode::cbPosition |
( |
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & |
msg | ) |
|
|
inlineprotected |
◆ cbResizeParticle()
bool mcl_3dl::MCL3dlNode::cbResizeParticle |
( |
mcl_3dl_msgs::ResizeParticleRequest & |
request, |
|
|
mcl_3dl_msgs::ResizeParticleResponse & |
response |
|
) |
| |
|
inlineprotected |
◆ configure()
bool mcl_3dl::MCL3dlNode::configure |
( |
| ) |
|
|
inline |
◆ diagnoseStatus()
◆ loadMapCloud()
◆ measure()
void mcl_3dl::MCL3dlNode::measure |
( |
| ) |
|
|
inlineprotected |
◆ publishParticles()
void mcl_3dl::MCL3dlNode::publishParticles |
( |
| ) |
|
|
inlineprotected |
◆ accum_
◆ cnt_measure_
size_t mcl_3dl::MCL3dlNode::cnt_measure_ |
|
protected |
◆ diag_updater_
◆ engine_
std::default_random_engine mcl_3dl::MCL3dlNode::engine_ |
|
protected |
◆ f_acc_
std::shared_ptr<FilterVec3> mcl_3dl::MCL3dlNode::f_acc_ |
|
protected |
◆ f_ang_
std::shared_ptr<FilterVec3> mcl_3dl::MCL3dlNode::f_ang_ |
|
protected |
◆ f_pos_
std::shared_ptr<FilterVec3> mcl_3dl::MCL3dlNode::f_pos_ |
|
protected |
◆ global_localization_fix_cnt_
size_t mcl_3dl::MCL3dlNode::global_localization_fix_cnt_ |
|
protected |
◆ has_imu_
bool mcl_3dl::MCL3dlNode::has_imu_ |
|
protected |
◆ has_map_
bool mcl_3dl::MCL3dlNode::has_map_ |
|
protected |
◆ has_odom_
bool mcl_3dl::MCL3dlNode::has_odom_ |
|
protected |
◆ imu_last_
◆ imu_measurement_model_
◆ imu_quat_
Quat mcl_3dl::MCL3dlNode::imu_quat_ |
|
protected |
◆ kdtree_
◆ lidar_measurements_
◆ localize_rate_
std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::localize_rate_ |
|
protected |
◆ localized_last_
ros::Time mcl_3dl::MCL3dlNode::localized_last_ |
|
protected |
◆ map_update_timer_
◆ match_output_last_
ros::Time mcl_3dl::MCL3dlNode::match_output_last_ |
|
protected |
◆ motion_prediction_model_
◆ nh_
◆ odom_
◆ odom_last_
◆ odom_prev_
◆ params_
◆ pc_accum_header_
◆ pc_all_accum_
◆ pc_local_accum_
◆ pc_map2_
◆ pc_map_
◆ pc_update_
◆ pf_
◆ pnh_
◆ point_rep_
MyPointRepresentation::Ptr mcl_3dl::MCL3dlNode::point_rep_ |
|
protected |
◆ pub_debug_marker_
◆ pub_mapcloud_
◆ pub_matched_
◆ pub_particle_
◆ pub_pose_
◆ pub_status_
◆ pub_unmatched_
◆ seed_gen_
std::random_device mcl_3dl::MCL3dlNode::seed_gen_ |
|
protected |
◆ srv_expansion_reset_
◆ srv_global_localization_
◆ srv_load_pcd_
◆ srv_particle_size_
◆ state_prev_
◆ status_
mcl_3dl_msgs::Status mcl_3dl::MCL3dlNode::status_ |
|
protected |
◆ sub_cloud_
◆ sub_imu_
◆ sub_landmark_
◆ sub_mapcloud_
◆ sub_mapcloud_update_
◆ sub_odom_
◆ sub_position_
◆ tf_tolerance_base_
◆ tfb_
◆ tfbuf_
◆ tfl_
The documentation for this class was generated from the following file: