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. More... | |
bool | getParams (const ros::NodeHandle &nh_p) |
Read the parameters from launch file. More... | |
bool | init (ros::NodeHandle &nh) |
Initialize publishers subscribers and RBPF slam. More... | |
void | laserCallback (const sensor_msgs::LaserScan &msg) |
Callback function for the laser scans. More... | |
void | odometryForCallback (mrpt::obs::CObservationOdometry::Ptr &odometry, const std_msgs::Header &msg_header) |
Get the odometry for received observation. More... | |
PFslamWrapper () | |
void | publishMapPose () |
Publish beacon or grid map and robot pose. More... | |
void | publishTF () |
Publish tf tree. More... | |
bool | rawlogPlay () |
Play rawlog file. More... | |
void | updateSensorPose (const std::string &frame_id) |
Update the pose of the sensor with respect to the robot. More... | |
void | vizBeacons () |
Correct visualization for ro slam. More... | |
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. More... | |
~PFslamWrapper ()=default | |
Public Member Functions inherited from mrpt_rbpf_slam::PFslam | |
void | init3Dwindow () |
void | initSlam (Options options) |
initialize the SLAM More... | |
void | observation (const mrpt::obs::CSensoryFrame::ConstPtr sensory_frame, const mrpt::obs::CObservationOdometry::ConstPtr odometry) |
Calculate the actions from odometry model for current observation. More... | |
PFslam ()=default | |
void | readIniFile (const std::string &ini_filename) |
Read ini file. More... | |
void | readRawlog (const std::string &rawlog_filename, std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame >> &data) |
Read pairs of actions and observations from rawlog file. More... | |
void | run3Dwindow () |
virtual | ~PFslam () |
Private Attributes | |
std::string | base_frame_id_ |
robot frame More... | |
std::map< std::string, mrpt::poses::CPose3D > | beacon_poses_ |
beacon poses with respect to the map More... | |
ros::Publisher | beacon_viz_pub_ |
publishers for map and pose particles More... | |
std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame > > | data_ |
std::string | global_frame_id_ |
/map frame More... | |
std::string | ini_filename_ |
name of ini file More... | |
std::map< std::string, mrpt::poses::CPose3D > | laser_poses_ |
laser scan poses with respect to the map More... | |
tf::TransformListener | listenerTF_ |
transform listener More... | |
std::string | odom_frame_id_ |
/odom frame More... | |
ros::Publisher | pub_map_ |
ros::Publisher | pub_metadata_ |
ros::Publisher | pub_particles_ |
ros::Publisher | pub_particles_beacons_ |
std::string | rawlog_filename_ |
name of rawlog file More... | |
bool | rawlog_play_ { false } |
true if rawlog file exists More... | |
double | rawlog_play_delay_ |
delay of replay from rawlog file More... | |
std::string | sensor_source_ |
2D laser scans More... | |
std::vector< ros::Subscriber > | sensorSub_ |
list of sensors topics More... | |
float | t_exec_ |
the time which take one SLAM update execution More... | |
tf::TransformBroadcaster | tf_broadcaster_ |
transform broadcaster More... | |
mrpt::utils::CTicTac | tictac_ |
std::vector< mrpt::opengl::CEllipsoid::Ptr > | viz_beacons_ |
Additional Inherited Members | |
Public Attributes inherited from mrpt_rbpf_slam::PFslam | |
struct mrpt_rbpf_slam::PFslam::Options | options_ |
Protected Attributes inherited from mrpt_rbpf_slam::PFslam | |
mrpt::obs::CActionCollection::Ptr | action_ |
actions More... | |
mrpt::poses::CPose3DPDFParticles | curPDF |
current robot pose More... | |
mrpt::slam::CMetricMapBuilderRBPF | mapBuilder_ |
map builder More... | |
const mrpt::maps::CMultiMetricMap * | metric_map_ |
receive map after iteration of SLAM to metric map More... | |
mrpt::poses::CPose2D | odomLastObservation_ |
last observation of odometry More... | |
mrpt::obs::CSensoryFrame::Ptr | sensory_frame_ |
observations More... | |
mrpt::system::TTimeStamp | timeLastUpdate_ |
last update of the pose and map More... | |
bool | use_motion_model_default_options_ |
used default odom_params More... | |
mrpt::gui::CDisplayWindow3D::Ptr | win3D_ |
MRPT window. More... | |
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.
mrpt_rbpf_slam::PFslamWrapper::PFslamWrapper | ( | ) |
Definition at line 16 of file mrpt_rbpf_slam_wrapper.cpp.
|
default |
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.
void mrpt_rbpf_slam::PFslamWrapper::publishMapPose | ( | ) |
Publish beacon or grid map and robot pose.
Definition at line 201 of file mrpt_rbpf_slam_wrapper.cpp.
void mrpt_rbpf_slam::PFslamWrapper::publishTF | ( | ) |
Publish tf tree.
Definition at line 444 of file mrpt_rbpf_slam_wrapper.cpp.
bool mrpt_rbpf_slam::PFslamWrapper::rawlogPlay | ( | ) |
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.
void mrpt_rbpf_slam::PFslamWrapper::vizBeacons | ( | ) |
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.
|
private |
robot frame
Definition at line 152 of file mrpt_rbpf_slam_wrapper.h.
|
private |
beacon poses with respect to the map
Definition at line 158 of file mrpt_rbpf_slam_wrapper.h.
|
private |
publishers for map and pose particles
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
|
private |
vector of pairs of actions and obsrvations from rawlog file
Definition at line 164 of file mrpt_rbpf_slam_wrapper.h.
|
private |
/map frame
Definition at line 150 of file mrpt_rbpf_slam_wrapper.h.
|
private |
name of ini file
Definition at line 149 of file mrpt_rbpf_slam_wrapper.h.
|
private |
laser scan poses with respect to the map
Definition at line 157 of file mrpt_rbpf_slam_wrapper.h.
|
private |
transform listener
Definition at line 173 of file mrpt_rbpf_slam_wrapper.h.
|
private |
/odom frame
Definition at line 151 of file mrpt_rbpf_slam_wrapper.h.
|
private |
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
|
private |
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
|
private |
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
|
private |
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
|
private |
name of rawlog file
Definition at line 148 of file mrpt_rbpf_slam_wrapper.h.
|
private |
true if rawlog file exists
Definition at line 146 of file mrpt_rbpf_slam_wrapper.h.
|
private |
delay of replay from rawlog file
Definition at line 145 of file mrpt_rbpf_slam_wrapper.h.
|
private |
2D laser scans
Definition at line 155 of file mrpt_rbpf_slam_wrapper.h.
|
private |
list of sensors topics
Definition at line 161 of file mrpt_rbpf_slam_wrapper.h.
|
private |
the time which take one SLAM update execution
Definition at line 180 of file mrpt_rbpf_slam_wrapper.h.
|
private |
transform broadcaster
Definition at line 174 of file mrpt_rbpf_slam_wrapper.h.
|
private |
Definition at line 178 of file mrpt_rbpf_slam_wrapper.h.
|
private |
Definition at line 168 of file mrpt_rbpf_slam_wrapper.h.