The PFslamWrapper class provides the ROS wrapper for Rao-Blackwellized Particle filter SLAM from MRPT libraries. More...
#include <mrpt_rbpf_slam_wrapper.h>

Public Member Functions | |
| void | callbackBeacon (const mrpt_msgs::ObservationRangeBeacon &msg) |
| Callback function for the beacons. | |
| bool | getParams (const ros::NodeHandle &nh_p) |
| Read the parameters from launch file. | |
| bool | init (ros::NodeHandle &nh) |
| Initialize publishers subscribers and RBPF slam. | |
| void | laserCallback (const sensor_msgs::LaserScan &msg) |
| Callback function for the laser scans. | |
| void | odometryForCallback (mrpt::obs::CObservationOdometry::Ptr &odometry, const std_msgs::Header &msg_header) |
| Get the odometry for received observation. | |
| PFslamWrapper () | |
| void | publishMapPose () |
| Publish beacon or grid map and robot pose. | |
| void | publishTF () |
| Publish tf tree. | |
| bool | rawlogPlay () |
| Play rawlog file. | |
| void | updateSensorPose (const std::string &frame_id) |
| Update the pose of the sensor with respect to the robot. | |
| void | vizBeacons () |
| Correct visualization for ro slam. | |
| bool | waitForTransform (mrpt::poses::CPose3D &des, const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01)) |
| Wait for transform between odometry frame and the robot frame. | |
| ~PFslamWrapper () | |
Private Attributes | |
| std::string | base_frame_id_ |
| robot frame | |
| std::map< std::string, mrpt::poses::CPose3D > | beacon_poses_ |
| beacon poses with respect to the map | |
| ros::Publisher | beacon_viz_pub_ |
| publishers for map and pose particles | |
| std::vector< std::pair < mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame > > | data_ |
| std::string | global_frame_id_ |
| /map frame | |
| std::string | ini_filename_ |
| name of ini file | |
| std::map< std::string, mrpt::poses::CPose3D > | laser_poses_ |
| laser scan poses with respect to the map | |
| tf::TransformListener | listenerTF_ |
| transform listener | |
| std::string | odom_frame_id_ |
| /odom frame | |
| ros::Publisher | pub_map_ |
| ros::Publisher | pub_metadata_ |
| ros::Publisher | pub_particles_ |
| ros::Publisher | pub_particles_beacons_ |
| std::string | rawlog_filename_ |
| 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::Subscriber > | sensorSub_ |
| list of sensors topics | |
| float | t_exec_ |
| the time which take one SLAM update execution | |
| tf::TransformBroadcaster | tf_broadcaster_ |
| transform broadcaster | |
| mrpt::utils::CTicTac | tictac_ |
| std::vector < mrpt::opengl::CEllipsoid::Ptr > | viz_beacons_ |
The PFslamWrapper class provides the ROS wrapper for Rao-Blackwellized Particle filter SLAM from MRPT libraries.
Definition at line 49 of file mrpt_rbpf_slam_wrapper.h.
Definition at line 16 of file mrpt_rbpf_slam_wrapper.cpp.
| void mrpt_rbpf_slam::PFslamWrapper::callbackBeacon | ( | const mrpt_msgs::ObservationRangeBeacon & | msg | ) |
Callback function for the beacons.
Given the range only observation wait for odometry, create the pair of action and observation, implement one SLAM update, publish map and pose.
| msg | the beacon message |
Definition at line 171 of file mrpt_rbpf_slam_wrapper.cpp.
| bool mrpt_rbpf_slam::PFslamWrapper::getParams | ( | const ros::NodeHandle & | nh_p | ) |
Read the parameters from launch file.
Definition at line 20 of file mrpt_rbpf_slam_wrapper.cpp.
| bool mrpt_rbpf_slam::PFslamWrapper::init | ( | ros::NodeHandle & | nh | ) |
Initialize publishers subscribers and RBPF slam.
Create publishers///
Create subscribers///
Definition at line 52 of file mrpt_rbpf_slam_wrapper.cpp.
| void mrpt_rbpf_slam::PFslamWrapper::laserCallback | ( | const sensor_msgs::LaserScan & | msg | ) |
Callback function for the laser scans.
Given the laser scans wait for odometry, create the pair of action and observation, implement one SLAM update, publish map and pose.
| msg | the laser scan message |
Definition at line 141 of file mrpt_rbpf_slam_wrapper.cpp.
| void mrpt_rbpf_slam::PFslamWrapper::odometryForCallback | ( | mrpt::obs::CObservationOdometry::Ptr & | odometry, |
| const std_msgs::Header & | msg_header | ||
| ) |
Get the odometry for received observation.
| [out] | odometry | odometry for received observation |
| [in] | msg_header | timestamp of the observation |
Definition at line 106 of file mrpt_rbpf_slam_wrapper.cpp.
Publish beacon or grid map and robot pose.
Definition at line 201 of file mrpt_rbpf_slam_wrapper.cpp.
Publish tf tree.
Definition at line 444 of file mrpt_rbpf_slam_wrapper.cpp.
Play rawlog file.
Definition at line 355 of file mrpt_rbpf_slam_wrapper.cpp.
| void mrpt_rbpf_slam::PFslamWrapper::updateSensorPose | ( | const std::string & | frame_id | ) |
Update the pose of the sensor with respect to the robot.
| frame_id | the frame of the sensors |
Definition at line 329 of file mrpt_rbpf_slam_wrapper.cpp.
Correct visualization for ro slam.
Definition at line 271 of file mrpt_rbpf_slam_wrapper.cpp.
| bool mrpt_rbpf_slam::PFslamWrapper::waitForTransform | ( | mrpt::poses::CPose3D & | des, |
| const std::string & | target_frame, | ||
| const std::string & | source_frame, | ||
| const ros::Time & | time, | ||
| const ros::Duration & | timeout, | ||
| const ros::Duration & | polling_sleep_duration = ros::Duration(0.01) |
||
| ) |
Wait for transform between odometry frame and the robot frame.
| [out] | des | position of the robot with respect to odometry frame |
| [in] | target_frame | the odometry tf frame |
| [in] | source_frame | the robot tf frame |
| [in] | time | timestamp of the observation for which we want to retrieve the position of the robot |
| [in] | timeout | timeout for odometry waiting |
| [in] | polling_sleep_duration | timeout for transform wait |
Definition at line 122 of file mrpt_rbpf_slam_wrapper.cpp.
std::string mrpt_rbpf_slam::PFslamWrapper::base_frame_id_ [private] |
robot frame
Definition at line 152 of file mrpt_rbpf_slam_wrapper.h.
std::map<std::string, mrpt::poses::CPose3D> mrpt_rbpf_slam::PFslamWrapper::beacon_poses_ [private] |
beacon poses with respect to the map
Definition at line 158 of file mrpt_rbpf_slam_wrapper.h.
publishers for map and pose particles
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
std::vector<std::pair<mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame> > mrpt_rbpf_slam::PFslamWrapper::data_ [private] |
vector of pairs of actions and obsrvations from rawlog file
Definition at line 164 of file mrpt_rbpf_slam_wrapper.h.
std::string mrpt_rbpf_slam::PFslamWrapper::global_frame_id_ [private] |
/map frame
Definition at line 150 of file mrpt_rbpf_slam_wrapper.h.
std::string mrpt_rbpf_slam::PFslamWrapper::ini_filename_ [private] |
name of ini file
Definition at line 149 of file mrpt_rbpf_slam_wrapper.h.
std::map<std::string, mrpt::poses::CPose3D> mrpt_rbpf_slam::PFslamWrapper::laser_poses_ [private] |
laser scan poses with respect to the map
Definition at line 157 of file mrpt_rbpf_slam_wrapper.h.
transform listener
Definition at line 173 of file mrpt_rbpf_slam_wrapper.h.
std::string mrpt_rbpf_slam::PFslamWrapper::odom_frame_id_ [private] |
/odom frame
Definition at line 151 of file mrpt_rbpf_slam_wrapper.h.
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
std::string mrpt_rbpf_slam::PFslamWrapper::rawlog_filename_ [private] |
true if rawlog file exists
name of rawlog file
Definition at line 146 of file mrpt_rbpf_slam_wrapper.h.
double mrpt_rbpf_slam::PFslamWrapper::rawlog_play_delay_ [private] |
delay of replay from rawlog file
Definition at line 145 of file mrpt_rbpf_slam_wrapper.h.
std::string mrpt_rbpf_slam::PFslamWrapper::sensor_source_ [private] |
2D laser scans
Definition at line 155 of file mrpt_rbpf_slam_wrapper.h.
std::vector<ros::Subscriber> mrpt_rbpf_slam::PFslamWrapper::sensorSub_ [private] |
list of sensors topics
Definition at line 161 of file mrpt_rbpf_slam_wrapper.h.
float mrpt_rbpf_slam::PFslamWrapper::t_exec_ [private] |
the time which take one SLAM update execution
Definition at line 180 of file mrpt_rbpf_slam_wrapper.h.
transform broadcaster
Definition at line 174 of file mrpt_rbpf_slam_wrapper.h.
mrpt::utils::CTicTac mrpt_rbpf_slam::PFslamWrapper::tictac_ [private] |
Definition at line 178 of file mrpt_rbpf_slam_wrapper.h.
std::vector<mrpt::opengl::CEllipsoid::Ptr> mrpt_rbpf_slam::PFslamWrapper::viz_beacons_ [private] |
Definition at line 168 of file mrpt_rbpf_slam_wrapper.h.