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 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 ()
 

Protected Attributes

int cnt_accum_
 
int cnt_measure_
 
std::default_random_engine engine_
 
std::shared_ptr< Filterf_acc_ [3]
 
std::shared_ptr< Filterf_ang_ [3]
 
std::shared_ptr< Filterf_pos_ [3]
 
bool fake_imu_
 
bool fake_odom_
 
std::map< std::string, std::string > frame_ids_
 
size_t frame_num_
 
std::map< std::string, bool > frames_
 
std::vector< std::string > frames_v_
 
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_
 
bool output_pcd_
 
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 > > pf_
 
ros::NodeHandle pnh_
 
MyPointRepresentation 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_
 
bool publish_tf_
 
std::random_device seed_gen_
 
ros::ServiceServer srv_expansion_reset_
 
ros::ServiceServer srv_global_localization_
 
ros::ServiceServer srv_particle_size_
 
State6DOF state_prev_
 
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 95 of file mcl_3dl.cpp.

Member Typedef Documentation

Definition at line 98 of file mcl_3dl.cpp.

Constructor & Destructor Documentation

mcl_3dl::MCL3dlNode::MCL3dlNode ( )
inline

Definition at line 1080 of file mcl_3dl.cpp.

mcl_3dl::MCL3dlNode::~MCL3dlNode ( )
inline

Definition at line 1329 of file mcl_3dl.cpp.

Member Function Documentation

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

Definition at line 247 of file mcl_3dl.cpp.

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

Definition at line 974 of file mcl_3dl.cpp.

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

Definition at line 987 of file mcl_3dl.cpp.

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

Definition at line 887 of file mcl_3dl.cpp.

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

Definition at line 845 of file mcl_3dl.cpp.

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

Definition at line 118 of file mcl_3dl.cpp.

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

Definition at line 145 of file mcl_3dl.cpp.

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

Definition at line 1339 of file mcl_3dl.cpp.

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

Definition at line 199 of file mcl_3dl.cpp.

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

Definition at line 159 of file mcl_3dl.cpp.

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

Definition at line 967 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::configure ( )
inline

Definition at line 1088 of file mcl_3dl.cpp.

void mcl_3dl::MCL3dlNode::publishParticles ( )
inlineprotected

Definition at line 1054 of file mcl_3dl.cpp.

Member Data Documentation

int mcl_3dl::MCL3dlNode::cnt_accum_
protected

Definition at line 1421 of file mcl_3dl.cpp.

int mcl_3dl::MCL3dlNode::cnt_measure_
protected

Definition at line 1420 of file mcl_3dl.cpp.

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

Definition at line 1442 of file mcl_3dl.cpp.

std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::f_acc_[3]
protected

Definition at line 1397 of file mcl_3dl.cpp.

std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::f_ang_[3]
protected

Definition at line 1396 of file mcl_3dl.cpp.

std::shared_ptr<Filter> mcl_3dl::MCL3dlNode::f_pos_[3]
protected

Definition at line 1395 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::fake_imu_
protected

Definition at line 1407 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::fake_odom_
protected

Definition at line 1407 of file mcl_3dl.cpp.

std::map<std::string, std::string> mcl_3dl::MCL3dlNode::frame_ids_
protected

Definition at line 1403 of file mcl_3dl.cpp.

size_t mcl_3dl::MCL3dlNode::frame_num_
protected

Definition at line 1417 of file mcl_3dl.cpp.

std::map<std::string, bool> mcl_3dl::MCL3dlNode::frames_
protected

Definition at line 1415 of file mcl_3dl.cpp.

std::vector<std::string> mcl_3dl::MCL3dlNode::frames_v_
protected

Definition at line 1416 of file mcl_3dl.cpp.

size_t mcl_3dl::MCL3dlNode::global_localization_fix_cnt_
protected

Definition at line 1423 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::has_imu_
protected

Definition at line 1412 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::has_map_
protected

Definition at line 1410 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::has_odom_
protected

Definition at line 1411 of file mcl_3dl.cpp.

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

Definition at line 1419 of file mcl_3dl.cpp.

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

Definition at line 1438 of file mcl_3dl.cpp.

Quat mcl_3dl::MCL3dlNode::imu_quat_
protected

Definition at line 1422 of file mcl_3dl.cpp.

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

Definition at line 1432 of file mcl_3dl.cpp.

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

Definition at line 1437 of file mcl_3dl.cpp.

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

Definition at line 1398 of file mcl_3dl.cpp.

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

Definition at line 1399 of file mcl_3dl.cpp.

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

Definition at line 1386 of file mcl_3dl.cpp.

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

Definition at line 1408 of file mcl_3dl.cpp.

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

Definition at line 1439 of file mcl_3dl.cpp.

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

Definition at line 1369 of file mcl_3dl.cpp.

State6DOF mcl_3dl::MCL3dlNode::odom_
protected

Definition at line 1413 of file mcl_3dl.cpp.

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

Definition at line 1409 of file mcl_3dl.cpp.

State6DOF mcl_3dl::MCL3dlNode::odom_prev_
protected

Definition at line 1414 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::output_pcd_
protected

Definition at line 1404 of file mcl_3dl.cpp.

Parameters mcl_3dl::MCL3dlNode::params_
protected

Definition at line 1402 of file mcl_3dl.cpp.

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

Definition at line 1433 of file mcl_3dl.cpp.

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

Definition at line 1430 of file mcl_3dl.cpp.

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

Definition at line 1431 of file mcl_3dl.cpp.

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

Definition at line 1428 of file mcl_3dl.cpp.

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

Definition at line 1427 of file mcl_3dl.cpp.

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

Definition at line 1429 of file mcl_3dl.cpp.

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

Definition at line 99 of file mcl_3dl.cpp.

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

Definition at line 1370 of file mcl_3dl.cpp.

MyPointRepresentation mcl_3dl::MCL3dlNode::point_rep_
protected

Definition at line 1425 of file mcl_3dl.cpp.

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

Definition at line 1384 of file mcl_3dl.cpp.

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

Definition at line 1380 of file mcl_3dl.cpp.

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

Definition at line 1382 of file mcl_3dl.cpp.

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

Definition at line 1379 of file mcl_3dl.cpp.

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

Definition at line 1381 of file mcl_3dl.cpp.

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

Definition at line 1385 of file mcl_3dl.cpp.

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

Definition at line 1383 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::publish_tf_
protected

Definition at line 1405 of file mcl_3dl.cpp.

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

Definition at line 1441 of file mcl_3dl.cpp.

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

Definition at line 1389 of file mcl_3dl.cpp.

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

Definition at line 1388 of file mcl_3dl.cpp.

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

Definition at line 1387 of file mcl_3dl.cpp.

State6DOF mcl_3dl::MCL3dlNode::state_prev_
protected

Definition at line 1418 of file mcl_3dl.cpp.

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

Definition at line 1372 of file mcl_3dl.cpp.

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

Definition at line 1376 of file mcl_3dl.cpp.

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

Definition at line 1378 of file mcl_3dl.cpp.

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

Definition at line 1373 of file mcl_3dl.cpp.

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

Definition at line 1374 of file mcl_3dl.cpp.

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

Definition at line 1375 of file mcl_3dl.cpp.

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

Definition at line 1377 of file mcl_3dl.cpp.

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

Definition at line 1400 of file mcl_3dl.cpp.

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

Definition at line 1393 of file mcl_3dl.cpp.

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

Definition at line 1391 of file mcl_3dl.cpp.

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

Definition at line 1392 of file mcl_3dl.cpp.


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


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36