Public Member Functions | Protected Attributes
ICPslamWrapper Class Reference

The ICPslamWrapper class provides 2d icp based SLAM from MRPT libraries. More...

#include <mrpt_icp_slam_2d_wrapper.h>

List of all members.

Public Member Functions

void get_param ()
 read the parameters from launch file
 ICPslamWrapper ()
 constructor
void init ()
 initialize publishers subscribers and icp slam
void init3Dwindow ()
 init 3D window from mrpt lib
bool is_file_exists (const std::string &name)
 check the existance of the file
void laserCallback (const sensor_msgs::LaserScan &_msg)
 callback function for the laser scans
void publishMapPose ()
 publish point and/or grid map and robot pose
void publishTF ()
 publis tf tree
void publishTrajectoryTimerCallback (const ros::TimerEvent &event)
 the callback for publish trajectory
bool rawlogPlay ()
 play rawlog file
void read_iniFile (std::string ini_filename)
 read ini file
void run3Dwindow ()
 run 3D window update from mrpt lib
void updateSensorPose (std::string _frame_id)
 update the pose of the sensor with respect to the robot
void updateTrajectoryTimerCallback (const ros::TimerEvent &event)
 the callback for update trajectory
 ~ICPslamWrapper ()
 destructor

Protected Attributes

std::string base_frame_id
 robot frame
bool CAMERA_3DSCENE_FOLLOWS_ROBOT
std::string global_frame_id
 /map frame
std::string ini_filename
 name of ini file
bool isObsBasedRawlog
std::map< std::string,
mrpt::poses::CPose3D > 
laser_poses_
 laser scan poses with respect to the map
tf::TransformListener listenerTF_
 transform listener
std::vector
< CObservation2DRangeScan::Ptr > 
lst_current_laser_scans
CMetricMapBuilderICP mapBuilder
 icp slam class
const CMultiMetricMap * metric_map_
 receive map after iteration of SLAM to metric map
ros::NodeHandle n_
 Node Handle.
CObservation::Ptr observation
CSensoryFrame::Ptr observations
std::string odom_frame_id
 /odom frame
nav_msgs::Path path
 trajectory path
geometry_msgs::PoseStamped pose
 the robot pose
ros::Publisher pub_map_
ros::Publisher pub_metadata_
ros::Publisher pub_point_cloud_
 publishers for map and pose particles
ros::Publisher pub_pose_
ros::Timer publish_trajectory_timer
 timer for publish trajectory
std::string rawlog_filename
 name of rawlog file
bool rawlog_play_
 true if rawlog file exists
double rawlog_play_delay
 delay of replay from rawlog file
std::string sensor_source
 2D laser scans
std::vector< ros::SubscribersensorSub_
 list of sensors topics
bool SHOW_LASER_SCANS_3D
bool SHOW_PROGRESS_3D_REAL_TIME
int SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS
ros::Time stamp
 timestamp for observations
float t_exec
 the time which take one SLAM update execution
tf::TransformBroadcaster tf_broadcaster_
 transform broadcaster
CTicTac tictac
 timer for SLAM performance evaluation
mrpt::system::TTimeStamp timeLastUpdate_
 last update of the pose and map
ros::Publisher trajectory_pub_
 trajectory publisher
double trajectory_publish_rate
 trajectory publish rate(Hz)
double trajectory_update_rate
 trajectory update rate(Hz)
ros::Timer update_trajector_timer
 timer for update trajectory
mrpt::gui::CDisplayWindow3D::Ptr win3D_
 MRPT window.

Detailed Description

The ICPslamWrapper class provides 2d icp based SLAM from MRPT libraries.

Definition at line 92 of file mrpt_icp_slam_2d_wrapper.h.


Constructor & Destructor Documentation

constructor

Definition at line 22 of file mrpt_icp_slam_2d_wrapper.cpp.

destructor

Definition at line 32 of file mrpt_icp_slam_2d_wrapper.cpp.


Member Function Documentation

read the parameters from launch file

Definition at line 96 of file mrpt_icp_slam_2d_wrapper.cpp.

initialize publishers subscribers and icp slam

Create publishers///

Create subscribers///

Definition at line 270 of file mrpt_icp_slam_2d_wrapper.cpp.

init 3D window from mrpt lib

Definition at line 125 of file mrpt_icp_slam_2d_wrapper.cpp.

bool ICPslamWrapper::is_file_exists ( const std::string &  name)

check the existance of the file

Returns:
true if file exists

Definition at line 50 of file mrpt_icp_slam_2d_wrapper.cpp.

callback function for the laser scans

Given the laser scans, implement one SLAM update, publish map and pose.

Parameters:
_msgthe laser scan message

Definition at line 328 of file mrpt_icp_slam_2d_wrapper.cpp.

publish point and/or grid map and robot pose

Definition at line 354 of file mrpt_icp_slam_2d_wrapper.cpp.

publis tf tree

Definition at line 527 of file mrpt_icp_slam_2d_wrapper.cpp.

the callback for publish trajectory

Parameters:
eventthe event for publish trajectory

Definition at line 565 of file mrpt_icp_slam_2d_wrapper.cpp.

play rawlog file

Returns:
true if rawlog file exists and played

Definition at line 429 of file mrpt_icp_slam_2d_wrapper.cpp.

void ICPslamWrapper::read_iniFile ( std::string  ini_filename)

read ini file

Parameters:
ini_filenamethe name of the ini file to read

Definition at line 55 of file mrpt_icp_slam_2d_wrapper.cpp.

run 3D window update from mrpt lib

Definition at line 137 of file mrpt_icp_slam_2d_wrapper.cpp.

void ICPslamWrapper::updateSensorPose ( std::string  _frame_id)

update the pose of the sensor with respect to the robot

Parameters:
frame_idthe frame of the sensors

Definition at line 405 of file mrpt_icp_slam_2d_wrapper.cpp.

the callback for update trajectory

Parameters:
eventthe event for update trajectory

Definition at line 557 of file mrpt_icp_slam_2d_wrapper.cpp.


Member Data Documentation

std::string ICPslamWrapper::base_frame_id [protected]

robot frame

Definition at line 189 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 230 of file mrpt_icp_slam_2d_wrapper.h.

std::string ICPslamWrapper::global_frame_id [protected]

/map frame

Definition at line 187 of file mrpt_icp_slam_2d_wrapper.h.

std::string ICPslamWrapper::ini_filename [protected]

name of ini file

Definition at line 186 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 226 of file mrpt_icp_slam_2d_wrapper.h.

std::map<std::string, mrpt::poses::CPose3D> ICPslamWrapper::laser_poses_ [protected]

laser scan poses with respect to the map

Definition at line 203 of file mrpt_icp_slam_2d_wrapper.h.

transform listener

Definition at line 212 of file mrpt_icp_slam_2d_wrapper.h.

std::vector<CObservation2DRangeScan::Ptr> ICPslamWrapper::lst_current_laser_scans [protected]

Definition at line 225 of file mrpt_icp_slam_2d_wrapper.h.

CMetricMapBuilderICP ICPslamWrapper::mapBuilder [protected]

icp slam class

Definition at line 180 of file mrpt_icp_slam_2d_wrapper.h.

const CMultiMetricMap* ICPslamWrapper::metric_map_ [protected]

receive map after iteration of SLAM to metric map

Definition at line 208 of file mrpt_icp_slam_2d_wrapper.h.

Node Handle.

Definition at line 181 of file mrpt_icp_slam_2d_wrapper.h.

CObservation::Ptr ICPslamWrapper::observation [protected]

Definition at line 218 of file mrpt_icp_slam_2d_wrapper.h.

CSensoryFrame::Ptr ICPslamWrapper::observations [protected]

Definition at line 217 of file mrpt_icp_slam_2d_wrapper.h.

std::string ICPslamWrapper::odom_frame_id [protected]

/odom frame

Definition at line 188 of file mrpt_icp_slam_2d_wrapper.h.

nav_msgs::Path ICPslamWrapper::path [protected]

trajectory path

Definition at line 193 of file mrpt_icp_slam_2d_wrapper.h.

geometry_msgs::PoseStamped ICPslamWrapper::pose [protected]

the robot pose

Definition at line 190 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 210 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 210 of file mrpt_icp_slam_2d_wrapper.h.

publishers for map and pose particles

Definition at line 210 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 210 of file mrpt_icp_slam_2d_wrapper.h.

timer for publish trajectory

Definition at line 196 of file mrpt_icp_slam_2d_wrapper.h.

std::string ICPslamWrapper::rawlog_filename [protected]

name of rawlog file

Definition at line 185 of file mrpt_icp_slam_2d_wrapper.h.

bool ICPslamWrapper::rawlog_play_ [protected]

true if rawlog file exists

Definition at line 183 of file mrpt_icp_slam_2d_wrapper.h.

delay of replay from rawlog file

Definition at line 182 of file mrpt_icp_slam_2d_wrapper.h.

std::string ICPslamWrapper::sensor_source [protected]

2D laser scans

Definition at line 202 of file mrpt_icp_slam_2d_wrapper.h.

std::vector<ros::Subscriber> ICPslamWrapper::sensorSub_ [protected]

list of sensors topics

Definition at line 206 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 229 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 227 of file mrpt_icp_slam_2d_wrapper.h.

Definition at line 228 of file mrpt_icp_slam_2d_wrapper.h.

timestamp for observations

Definition at line 221 of file mrpt_icp_slam_2d_wrapper.h.

float ICPslamWrapper::t_exec [protected]

the time which take one SLAM update execution

Definition at line 216 of file mrpt_icp_slam_2d_wrapper.h.

transform broadcaster

Definition at line 213 of file mrpt_icp_slam_2d_wrapper.h.

CTicTac ICPslamWrapper::tictac [protected]

timer for SLAM performance evaluation

Definition at line 215 of file mrpt_icp_slam_2d_wrapper.h.

mrpt::system::TTimeStamp ICPslamWrapper::timeLastUpdate_ [protected]

last update of the pose and map

Definition at line 219 of file mrpt_icp_slam_2d_wrapper.h.

trajectory publisher

Definition at line 192 of file mrpt_icp_slam_2d_wrapper.h.

trajectory publish rate(Hz)

Definition at line 199 of file mrpt_icp_slam_2d_wrapper.h.

trajectory update rate(Hz)

Definition at line 198 of file mrpt_icp_slam_2d_wrapper.h.

timer for update trajectory

Definition at line 195 of file mrpt_icp_slam_2d_wrapper.h.

mrpt::gui::CDisplayWindow3D::Ptr ICPslamWrapper::win3D_ [protected]

MRPT window.

Definition at line 223 of file mrpt_icp_slam_2d_wrapper.h.


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


mrpt_icp_slam_2d
Author(s): Jose Luis Blanco Claraco, Vladislav Tananaev
autogenerated on Thu Jun 6 2019 21:40:33