Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
mcl_3dl::MCL3dlNode Class Reference

Classes

class  MyPointRepresentation
 

Public Member Functions

void cbMapUpdateTimer (const ros::TimerEvent &event)
 
bool configure ()
 
 MCL3dlNode ()
 
 ~MCL3dlNode ()
 

Protected Types

using PointType = mcl_3dl::PointXYZIL
 

Protected Member Functions

void accumClear ()
 
bool accumCloud (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
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)
 
bool cbLoadPCD (mcl_3dl_msgs::LoadPCD::Request &req, mcl_3dl_msgs::LoadPCD::Response &resp)
 
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 diagnoseStatus (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void loadMapCloud (const pcl::PointCloud< PointType >::Ptr &map_cloud)
 
void measure ()
 
void publishParticles ()
 

Protected Attributes

CloudAccumulationLogicBase::Ptr accum_
 
size_t cnt_measure_
 
diagnostic_updater::Updater diag_updater_
 
std::default_random_engine engine_
 
std::shared_ptr< FilterVec3f_acc_
 
std::shared_ptr< FilterVec3f_ang_
 
std::shared_ptr< FilterVec3f_pos_
 
size_t global_localization_fix_cnt_
 
bool has_imu_
 
bool has_map_
 
bool has_odom_
 
ros::Time imu_last_
 
ImuMeasurementModelBase::Ptr imu_measurement_model_
 
Quat imu_quat_
 
ChunkedKdtree< PointType >::Ptr kdtree_
 
std::map< std::string, LidarMeasurementModelBase::Ptrlidar_measurements_
 
std::shared_ptr< Filterlocalize_rate_
 
ros::Time localized_last_
 
ros::Timer map_update_timer_
 
ros::Time match_output_last_
 
MotionPredictionModelBase::Ptr motion_prediction_model_
 
ros::NodeHandle nh_
 
State6DOF odom_
 
ros::Time odom_last_
 
State6DOF odom_prev_
 
Parameters params_
 
std::vector< std_msgs::Headerpc_accum_header_
 
pcl::PointCloud< PointType >::Ptr pc_all_accum_
 
pcl::PointCloud< PointType >::Ptr pc_local_accum_
 
pcl::PointCloud< PointType >::Ptr pc_map2_
 
pcl::PointCloud< PointType >::Ptr pc_map_
 
pcl::PointCloud< PointType >::Ptr pc_update_
 
std::shared_ptr< pf::ParticleFilter< State6DOF, float, ParticleWeightedMeanQuat, std::default_random_engine > > pf_
 
ros::NodeHandle pnh_
 
MyPointRepresentation::Ptr point_rep_
 
ros::Publisher pub_debug_marker_
 
ros::Publisher pub_mapcloud_
 
ros::Publisher pub_matched_
 
ros::Publisher pub_particle_
 
ros::Publisher pub_pose_
 
ros::Publisher pub_status_
 
ros::Publisher pub_unmatched_
 
std::random_device seed_gen_
 
ros::ServiceServer srv_expansion_reset_
 
ros::ServiceServer srv_global_localization_
 
ros::ServiceServer srv_load_pcd_
 
ros::ServiceServer srv_particle_size_
 
State6DOF state_prev_
 
mcl_3dl_msgs::Status status_
 
ros::Subscriber sub_cloud_
 
ros::Subscriber sub_imu_
 
ros::Subscriber sub_landmark_
 
ros::Subscriber sub_mapcloud_
 
ros::Subscriber sub_mapcloud_update_
 
ros::Subscriber sub_odom_
 
ros::Subscriber sub_position_
 
ros::Duration tf_tolerance_base_
 
tf2_ros::TransformBroadcaster tfb_
 
tf2_ros::Buffer tfbuf_
 
tf2_ros::TransformListener tfl_
 

Detailed Description

Definition at line 103 of file mcl_3dl.cpp.

Member Typedef Documentation

◆ PointType

Definition at line 106 of file mcl_3dl.cpp.

Constructor & Destructor Documentation

◆ MCL3dlNode()

mcl_3dl::MCL3dlNode::MCL3dlNode ( )
inline

Definition at line 1196 of file mcl_3dl.cpp.

◆ ~MCL3dlNode()

mcl_3dl::MCL3dlNode::~MCL3dlNode ( )
inline

Definition at line 1346 of file mcl_3dl.cpp.

Member Function Documentation

◆ accumClear()

void mcl_3dl::MCL3dlNode::accumClear ( )
inlineprotected

Definition at line 267 of file mcl_3dl.cpp.

◆ accumCloud()

bool mcl_3dl::MCL3dlNode::accumCloud ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
inlineprotected

Definition at line 274 of file mcl_3dl.cpp.

◆ cbCloud()

void mcl_3dl::MCL3dlNode::cbCloud ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
inlineprotected

Definition at line 248 of file mcl_3dl.cpp.

◆ cbExpansionReset()

bool mcl_3dl::MCL3dlNode::cbExpansionReset ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
)
inlineprotected

Definition at line 1027 of file mcl_3dl.cpp.

◆ cbGlobalLocalization()

bool mcl_3dl::MCL3dlNode::cbGlobalLocalization ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
)
inlineprotected

Definition at line 1040 of file mcl_3dl.cpp.

◆ cbImu()

void mcl_3dl::MCL3dlNode::cbImu ( const sensor_msgs::Imu::ConstPtr &  msg)
inlineprotected

Definition at line 942 of file mcl_3dl.cpp.

◆ cbLandmark()

void mcl_3dl::MCL3dlNode::cbLandmark ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  msg)
inlineprotected

Definition at line 900 of file mcl_3dl.cpp.

◆ cbLoadPCD()

bool mcl_3dl::MCL3dlNode::cbLoadPCD ( mcl_3dl_msgs::LoadPCD::Request &  req,
mcl_3dl_msgs::LoadPCD::Response &  resp 
)
inlineprotected

Definition at line 1173 of file mcl_3dl.cpp.

◆ cbMapcloud()

void mcl_3dl::MCL3dlNode::cbMapcloud ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
inlineprotected

Definition at line 127 of file mcl_3dl.cpp.

◆ cbMapcloudUpdate()

void mcl_3dl::MCL3dlNode::cbMapcloudUpdate ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
inlineprotected

Definition at line 141 of file mcl_3dl.cpp.

◆ cbMapUpdateTimer()

void mcl_3dl::MCL3dlNode::cbMapUpdateTimer ( const ros::TimerEvent event)
inline

Definition at line 1356 of file mcl_3dl.cpp.

◆ cbOdom()

void mcl_3dl::MCL3dlNode::cbOdom ( const nav_msgs::Odometry::ConstPtr &  msg)
inlineprotected

Definition at line 200 of file mcl_3dl.cpp.

◆ cbPosition()

void mcl_3dl::MCL3dlNode::cbPosition ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  msg)
inlineprotected

Definition at line 155 of file mcl_3dl.cpp.

◆ cbResizeParticle()

bool mcl_3dl::MCL3dlNode::cbResizeParticle ( mcl_3dl_msgs::ResizeParticleRequest &  request,
mcl_3dl_msgs::ResizeParticleResponse &  response 
)
inlineprotected

Definition at line 1020 of file mcl_3dl.cpp.

◆ configure()

bool mcl_3dl::MCL3dlNode::configure ( )
inline

Definition at line 1205 of file mcl_3dl.cpp.

◆ diagnoseStatus()

void mcl_3dl::MCL3dlNode::diagnoseStatus ( diagnostic_updater::DiagnosticStatusWrapper stat)
inlineprotected

Definition at line 1128 of file mcl_3dl.cpp.

◆ loadMapCloud()

void mcl_3dl::MCL3dlNode::loadMapCloud ( const pcl::PointCloud< PointType >::Ptr &  map_cloud)
inlineprotected

Definition at line 1151 of file mcl_3dl.cpp.

◆ measure()

void mcl_3dl::MCL3dlNode::measure ( )
inlineprotected

Definition at line 304 of file mcl_3dl.cpp.

◆ publishParticles()

void mcl_3dl::MCL3dlNode::publishParticles ( )
inlineprotected

Definition at line 1102 of file mcl_3dl.cpp.

Member Data Documentation

◆ accum_

CloudAccumulationLogicBase::Ptr mcl_3dl::MCL3dlNode::accum_
protected

Definition at line 1446 of file mcl_3dl.cpp.

◆ cnt_measure_

size_t mcl_3dl::MCL3dlNode::cnt_measure_
protected

Definition at line 1432 of file mcl_3dl.cpp.

◆ diag_updater_

diagnostic_updater::Updater mcl_3dl::MCL3dlNode::diag_updater_
protected

Definition at line 1435 of file mcl_3dl.cpp.

◆ engine_

std::default_random_engine mcl_3dl::MCL3dlNode::engine_
protected

Definition at line 1458 of file mcl_3dl.cpp.

◆ f_acc_

std::shared_ptr<FilterVec3> mcl_3dl::MCL3dlNode::f_acc_
protected

Definition at line 1416 of file mcl_3dl.cpp.

◆ f_ang_

std::shared_ptr<FilterVec3> mcl_3dl::MCL3dlNode::f_ang_
protected

Definition at line 1415 of file mcl_3dl.cpp.

◆ f_pos_

std::shared_ptr<FilterVec3> mcl_3dl::MCL3dlNode::f_pos_
protected

Definition at line 1414 of file mcl_3dl.cpp.

◆ global_localization_fix_cnt_

size_t mcl_3dl::MCL3dlNode::global_localization_fix_cnt_
protected

Definition at line 1434 of file mcl_3dl.cpp.

◆ has_imu_

bool mcl_3dl::MCL3dlNode::has_imu_
protected

Definition at line 1427 of file mcl_3dl.cpp.

◆ has_map_

bool mcl_3dl::MCL3dlNode::has_map_
protected

Definition at line 1425 of file mcl_3dl.cpp.

◆ has_odom_

bool mcl_3dl::MCL3dlNode::has_odom_
protected

Definition at line 1426 of file mcl_3dl.cpp.

◆ imu_last_

ros::Time mcl_3dl::MCL3dlNode::imu_last_
protected

Definition at line 1431 of file mcl_3dl.cpp.

◆ imu_measurement_model_

ImuMeasurementModelBase::Ptr mcl_3dl::MCL3dlNode::imu_measurement_model_
protected

Definition at line 1454 of file mcl_3dl.cpp.

◆ imu_quat_

Quat mcl_3dl::MCL3dlNode::imu_quat_
protected

Definition at line 1433 of file mcl_3dl.cpp.

◆ kdtree_

ChunkedKdtree<PointType>::Ptr mcl_3dl::MCL3dlNode::kdtree_
protected

Definition at line 1444 of file mcl_3dl.cpp.

◆ lidar_measurements_

std::map< std::string, LidarMeasurementModelBase::Ptr> mcl_3dl::MCL3dlNode::lidar_measurements_
protected

Definition at line 1453 of file mcl_3dl.cpp.

◆ localize_rate_

std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::localize_rate_
protected

Definition at line 1417 of file mcl_3dl.cpp.

◆ localized_last_

ros::Time mcl_3dl::MCL3dlNode::localized_last_
protected

Definition at line 1418 of file mcl_3dl.cpp.

◆ map_update_timer_

ros::Timer mcl_3dl::MCL3dlNode::map_update_timer_
protected

Definition at line 1404 of file mcl_3dl.cpp.

◆ match_output_last_

ros::Time mcl_3dl::MCL3dlNode::match_output_last_
protected

Definition at line 1423 of file mcl_3dl.cpp.

◆ motion_prediction_model_

MotionPredictionModelBase::Ptr mcl_3dl::MCL3dlNode::motion_prediction_model_
protected

Definition at line 1455 of file mcl_3dl.cpp.

◆ nh_

ros::NodeHandle mcl_3dl::MCL3dlNode::nh_
protected

Definition at line 1387 of file mcl_3dl.cpp.

◆ odom_

State6DOF mcl_3dl::MCL3dlNode::odom_
protected

Definition at line 1428 of file mcl_3dl.cpp.

◆ odom_last_

ros::Time mcl_3dl::MCL3dlNode::odom_last_
protected

Definition at line 1424 of file mcl_3dl.cpp.

◆ odom_prev_

State6DOF mcl_3dl::MCL3dlNode::odom_prev_
protected

Definition at line 1429 of file mcl_3dl.cpp.

◆ params_

Parameters mcl_3dl::MCL3dlNode::params_
protected

Definition at line 1421 of file mcl_3dl.cpp.

◆ pc_accum_header_

std::vector<std_msgs::Header> mcl_3dl::MCL3dlNode::pc_accum_header_
protected

Definition at line 1448 of file mcl_3dl.cpp.

◆ pc_all_accum_

pcl::PointCloud<PointType>::Ptr mcl_3dl::MCL3dlNode::pc_all_accum_
protected

Definition at line 1443 of file mcl_3dl.cpp.

◆ pc_local_accum_

pcl::PointCloud<PointType>::Ptr mcl_3dl::MCL3dlNode::pc_local_accum_
protected

Definition at line 1447 of file mcl_3dl.cpp.

◆ pc_map2_

pcl::PointCloud<PointType>::Ptr mcl_3dl::MCL3dlNode::pc_map2_
protected

Definition at line 1441 of file mcl_3dl.cpp.

◆ pc_map_

pcl::PointCloud<PointType>::Ptr mcl_3dl::MCL3dlNode::pc_map_
protected

Definition at line 1440 of file mcl_3dl.cpp.

◆ pc_update_

pcl::PointCloud<PointType>::Ptr mcl_3dl::MCL3dlNode::pc_update_
protected

Definition at line 1442 of file mcl_3dl.cpp.

◆ pf_

std::shared_ptr<pf::ParticleFilter<State6DOF, float, ParticleWeightedMeanQuat, std::default_random_engine> > mcl_3dl::MCL3dlNode::pf_
protected

Definition at line 107 of file mcl_3dl.cpp.

◆ pnh_

ros::NodeHandle mcl_3dl::MCL3dlNode::pnh_
protected

Definition at line 1388 of file mcl_3dl.cpp.

◆ point_rep_

MyPointRepresentation::Ptr mcl_3dl::MCL3dlNode::point_rep_
protected

Definition at line 1438 of file mcl_3dl.cpp.

◆ pub_debug_marker_

ros::Publisher mcl_3dl::MCL3dlNode::pub_debug_marker_
protected

Definition at line 1402 of file mcl_3dl.cpp.

◆ pub_mapcloud_

ros::Publisher mcl_3dl::MCL3dlNode::pub_mapcloud_
protected

Definition at line 1398 of file mcl_3dl.cpp.

◆ pub_matched_

ros::Publisher mcl_3dl::MCL3dlNode::pub_matched_
protected

Definition at line 1400 of file mcl_3dl.cpp.

◆ pub_particle_

ros::Publisher mcl_3dl::MCL3dlNode::pub_particle_
protected

Definition at line 1397 of file mcl_3dl.cpp.

◆ pub_pose_

ros::Publisher mcl_3dl::MCL3dlNode::pub_pose_
protected

Definition at line 1399 of file mcl_3dl.cpp.

◆ pub_status_

ros::Publisher mcl_3dl::MCL3dlNode::pub_status_
protected

Definition at line 1403 of file mcl_3dl.cpp.

◆ pub_unmatched_

ros::Publisher mcl_3dl::MCL3dlNode::pub_unmatched_
protected

Definition at line 1401 of file mcl_3dl.cpp.

◆ seed_gen_

std::random_device mcl_3dl::MCL3dlNode::seed_gen_
protected

Definition at line 1457 of file mcl_3dl.cpp.

◆ srv_expansion_reset_

ros::ServiceServer mcl_3dl::MCL3dlNode::srv_expansion_reset_
protected

Definition at line 1407 of file mcl_3dl.cpp.

◆ srv_global_localization_

ros::ServiceServer mcl_3dl::MCL3dlNode::srv_global_localization_
protected

Definition at line 1406 of file mcl_3dl.cpp.

◆ srv_load_pcd_

ros::ServiceServer mcl_3dl::MCL3dlNode::srv_load_pcd_
protected

Definition at line 1408 of file mcl_3dl.cpp.

◆ srv_particle_size_

ros::ServiceServer mcl_3dl::MCL3dlNode::srv_particle_size_
protected

Definition at line 1405 of file mcl_3dl.cpp.

◆ state_prev_

State6DOF mcl_3dl::MCL3dlNode::state_prev_
protected

Definition at line 1430 of file mcl_3dl.cpp.

◆ status_

mcl_3dl_msgs::Status mcl_3dl::MCL3dlNode::status_
protected

Definition at line 1436 of file mcl_3dl.cpp.

◆ sub_cloud_

ros::Subscriber mcl_3dl::MCL3dlNode::sub_cloud_
protected

Definition at line 1390 of file mcl_3dl.cpp.

◆ sub_imu_

ros::Subscriber mcl_3dl::MCL3dlNode::sub_imu_
protected

Definition at line 1394 of file mcl_3dl.cpp.

◆ sub_landmark_

ros::Subscriber mcl_3dl::MCL3dlNode::sub_landmark_
protected

Definition at line 1396 of file mcl_3dl.cpp.

◆ sub_mapcloud_

ros::Subscriber mcl_3dl::MCL3dlNode::sub_mapcloud_
protected

Definition at line 1391 of file mcl_3dl.cpp.

◆ sub_mapcloud_update_

ros::Subscriber mcl_3dl::MCL3dlNode::sub_mapcloud_update_
protected

Definition at line 1392 of file mcl_3dl.cpp.

◆ sub_odom_

ros::Subscriber mcl_3dl::MCL3dlNode::sub_odom_
protected

Definition at line 1393 of file mcl_3dl.cpp.

◆ sub_position_

ros::Subscriber mcl_3dl::MCL3dlNode::sub_position_
protected

Definition at line 1395 of file mcl_3dl.cpp.

◆ tf_tolerance_base_

ros::Duration mcl_3dl::MCL3dlNode::tf_tolerance_base_
protected

Definition at line 1419 of file mcl_3dl.cpp.

◆ tfb_

tf2_ros::TransformBroadcaster mcl_3dl::MCL3dlNode::tfb_
protected

Definition at line 1412 of file mcl_3dl.cpp.

◆ tfbuf_

tf2_ros::Buffer mcl_3dl::MCL3dlNode::tfbuf_
protected

Definition at line 1410 of file mcl_3dl.cpp.

◆ tfl_

tf2_ros::TransformListener mcl_3dl::MCL3dlNode::tfl_
protected

Definition at line 1411 of file mcl_3dl.cpp.


The documentation for this class was generated from the following file:


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04