Classes | Public Member Functions | Protected Member Functions | Protected Attributes
mcl_3dl::MCL3dlNode Class Reference

List of all members.

Classes

class  MyPointRepresentation

Public Member Functions

void cbMapUpdateTimer (const ros::TimerEvent &event)
 MCL3dlNode (int argc, char *argv[])
 ~MCL3dlNode ()

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)

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]
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::Ptr > 
lidar_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.


Constructor & Destructor Documentation

mcl_3dl::MCL3dlNode::MCL3dlNode ( int  argc,
char *  argv[] 
) [inline]

Definition at line 1037 of file mcl_3dl.cpp.

Definition at line 1269 of file mcl_3dl.cpp.


Member Function Documentation

void mcl_3dl::MCL3dlNode::cbCloud ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [inline, protected]

Definition at line 234 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::cbExpansionReset ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
) [inline, protected]

Definition at line 957 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::cbGlobalLocalization ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
) [inline, protected]

Definition at line 969 of file mcl_3dl.cpp.

void mcl_3dl::MCL3dlNode::cbImu ( const sensor_msgs::Imu::ConstPtr &  msg) [inline, protected]

Definition at line 883 of file mcl_3dl.cpp.

void mcl_3dl::MCL3dlNode::cbLandmark ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  msg) [inline, protected]

Definition at line 852 of file mcl_3dl.cpp.

void mcl_3dl::MCL3dlNode::cbMapcloud ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [inline, protected]

Definition at line 118 of file mcl_3dl.cpp.

void mcl_3dl::MCL3dlNode::cbMapcloudUpdate ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [inline, protected]

Definition at line 145 of file mcl_3dl.cpp.

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

Definition at line 1279 of file mcl_3dl.cpp.

void mcl_3dl::MCL3dlNode::cbOdom ( const nav_msgs::Odometry::ConstPtr &  msg) [inline, protected]

Definition at line 197 of file mcl_3dl.cpp.

void mcl_3dl::MCL3dlNode::cbPosition ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  msg) [inline, protected]

Definition at line 159 of file mcl_3dl.cpp.

bool mcl_3dl::MCL3dlNode::cbResizeParticle ( mcl_3dl_msgs::ResizeParticleRequest &  request,
mcl_3dl_msgs::ResizeParticleResponse &  response 
) [inline, protected]

Definition at line 951 of file mcl_3dl.cpp.


Member Data Documentation

Definition at line 1360 of file mcl_3dl.cpp.

Definition at line 1359 of file mcl_3dl.cpp.

std::default_random_engine mcl_3dl::MCL3dlNode::engine_ [protected]

Definition at line 1381 of file mcl_3dl.cpp.

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

Definition at line 1337 of file mcl_3dl.cpp.

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

Definition at line 1336 of file mcl_3dl.cpp.

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

Definition at line 1335 of file mcl_3dl.cpp.

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

Definition at line 1343 of file mcl_3dl.cpp.

size_t mcl_3dl::MCL3dlNode::frame_num_ [protected]

Definition at line 1356 of file mcl_3dl.cpp.

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

Definition at line 1354 of file mcl_3dl.cpp.

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

Definition at line 1355 of file mcl_3dl.cpp.

Definition at line 1362 of file mcl_3dl.cpp.

Definition at line 1351 of file mcl_3dl.cpp.

Definition at line 1349 of file mcl_3dl.cpp.

Definition at line 1350 of file mcl_3dl.cpp.

Definition at line 1358 of file mcl_3dl.cpp.

ImuMeasurementModelBase::Ptr mcl_3dl::MCL3dlNode::imu_measurement_model_ [protected]

Definition at line 1377 of file mcl_3dl.cpp.

Definition at line 1361 of file mcl_3dl.cpp.

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

Definition at line 1371 of file mcl_3dl.cpp.

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

Definition at line 1376 of file mcl_3dl.cpp.

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

Definition at line 1338 of file mcl_3dl.cpp.

Definition at line 1339 of file mcl_3dl.cpp.

Definition at line 1326 of file mcl_3dl.cpp.

Definition at line 1347 of file mcl_3dl.cpp.

MotionPredictionModelBase::Ptr mcl_3dl::MCL3dlNode::motion_prediction_model_ [protected]

Definition at line 1378 of file mcl_3dl.cpp.

Definition at line 1309 of file mcl_3dl.cpp.

Definition at line 1352 of file mcl_3dl.cpp.

Definition at line 1348 of file mcl_3dl.cpp.

Definition at line 1353 of file mcl_3dl.cpp.

Definition at line 1344 of file mcl_3dl.cpp.

Definition at line 1342 of file mcl_3dl.cpp.

Definition at line 1372 of file mcl_3dl.cpp.

Definition at line 1369 of file mcl_3dl.cpp.

Definition at line 1370 of file mcl_3dl.cpp.

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

Definition at line 1367 of file mcl_3dl.cpp.

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

Definition at line 1366 of file mcl_3dl.cpp.

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

Definition at line 1368 of file mcl_3dl.cpp.

Definition at line 99 of file mcl_3dl.cpp.

Definition at line 1310 of file mcl_3dl.cpp.

Definition at line 1364 of file mcl_3dl.cpp.

Definition at line 1324 of file mcl_3dl.cpp.

Definition at line 1320 of file mcl_3dl.cpp.

Definition at line 1322 of file mcl_3dl.cpp.

Definition at line 1319 of file mcl_3dl.cpp.

Definition at line 1321 of file mcl_3dl.cpp.

Definition at line 1325 of file mcl_3dl.cpp.

Definition at line 1323 of file mcl_3dl.cpp.

Definition at line 1345 of file mcl_3dl.cpp.

std::random_device mcl_3dl::MCL3dlNode::seed_gen_ [protected]

Definition at line 1380 of file mcl_3dl.cpp.

Definition at line 1329 of file mcl_3dl.cpp.

Definition at line 1328 of file mcl_3dl.cpp.

Definition at line 1327 of file mcl_3dl.cpp.

Definition at line 1357 of file mcl_3dl.cpp.

Definition at line 1312 of file mcl_3dl.cpp.

Definition at line 1316 of file mcl_3dl.cpp.

Definition at line 1318 of file mcl_3dl.cpp.

Definition at line 1313 of file mcl_3dl.cpp.

Definition at line 1314 of file mcl_3dl.cpp.

Definition at line 1315 of file mcl_3dl.cpp.

Definition at line 1317 of file mcl_3dl.cpp.

Definition at line 1340 of file mcl_3dl.cpp.

Definition at line 1333 of file mcl_3dl.cpp.

Definition at line 1331 of file mcl_3dl.cpp.

Definition at line 1332 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 Jun 20 2019 20:04:43