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 | |
void | get_param () |
read the parameters from launch file | |
void | init () |
initialize publishers subscribers and RBPF slam | |
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 | odometryForCallback (CObservationOdometryPtr &_odometry, const std_msgs::Header &_msg_header) |
get the odometry for received observation | |
PFslamWrapper () | |
constructor | |
void | publishMapPose () |
publish beacon or grid map and robot pose | |
void | publishTF () |
publis tf tree | |
bool | rawlogPlay () |
play rawlog file | |
void | updateSensorPose (std::string frame_id) |
update the pose of the sensor with respect to the robot | |
void | vizBeacons () |
correct visualization for ro slam (under development) | |
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 transfor between odometry frame and the robot frame | |
~PFslamWrapper () | |
destructor | |
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 < CActionCollection, 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 | |
ros::NodeHandle | n_ |
Node Handle. | |
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 |
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::Subscriber > | sensorSub_ |
list of sensors topics | |
float | t_exec |
the time which take one SLAM update execution | |
tf::TransformBroadcaster | tf_broadcaster_ |
transform broadcaster | |
CTicTac | tictac |
timer for SLAM performance evaluation | |
std::vector < mrpt::opengl::CEllipsoidPtr > | viz_beacons |
The PFslamWrapper class provides the ROS wrapper for Rao-Blackwellized Particle filter SLAM from MRPT libraries.
Definition at line 54 of file mrpt_rbpf_slam_wrapper.h.
constructor
Definition at line 3 of file mrpt_rbpf_slam_wrapper.cpp.
destructor
Definition at line 9 of file mrpt_rbpf_slam_wrapper.cpp.
void 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 170 of file mrpt_rbpf_slam_wrapper.cpp.
void PFslamWrapper::get_param | ( | ) |
read the parameters from launch file
Definition at line 19 of file mrpt_rbpf_slam_wrapper.cpp.
void PFslamWrapper::init | ( | ) |
initialize publishers subscribers and RBPF slam
Create publishers///
Create subscribers///
Definition at line 44 of file mrpt_rbpf_slam_wrapper.cpp.
bool PFslamWrapper::is_file_exists | ( | const std::string & | name | ) |
check the existance of the file
Definition at line 13 of file mrpt_rbpf_slam_wrapper.cpp.
void 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 132 of file mrpt_rbpf_slam_wrapper.cpp.
void PFslamWrapper::odometryForCallback | ( | CObservationOdometryPtr & | _odometry, |
const std_msgs::Header & | _msg_header | ||
) |
get the odometry for received observation
_odometry | odometry for received observation |
_msg_header | timestamp of the observation |
Definition at line 97 of file mrpt_rbpf_slam_wrapper.cpp.
void PFslamWrapper::publishMapPose | ( | ) |
publish beacon or grid map and robot pose
Definition at line 207 of file mrpt_rbpf_slam_wrapper.cpp.
void PFslamWrapper::publishTF | ( | ) |
publis tf tree
Definition at line 444 of file mrpt_rbpf_slam_wrapper.cpp.
bool PFslamWrapper::rawlogPlay | ( | ) |
play rawlog file
Definition at line 359 of file mrpt_rbpf_slam_wrapper.cpp.
void PFslamWrapper::updateSensorPose | ( | 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 PFslamWrapper::vizBeacons | ( | ) |
correct visualization for ro slam (under development)
Definition at line 268 of file mrpt_rbpf_slam_wrapper.cpp.
bool 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 transfor between odometry frame and the robot frame
des | position of the robot with respect to odometry frame |
target_frame | the odometry tf frame |
source_frame | the robot tf frame |
time | timestamp of the observation for which we want to retrieve the position of the robot |
timeout | timeout for odometry waiting |
polling_sleep_duration | timeout for transform wait |
Definition at line 112 of file mrpt_rbpf_slam_wrapper.cpp.
std::string PFslamWrapper::base_frame_id [private] |
robot frame
Definition at line 167 of file mrpt_rbpf_slam_wrapper.h.
std::map<std::string, mrpt::poses::CPose3D> PFslamWrapper::beacon_poses_ [private] |
beacon poses with respect to the map
Definition at line 173 of file mrpt_rbpf_slam_wrapper.h.
ros::Publisher PFslamWrapper::beacon_viz_pub_ [private] |
publishers for map and pose particles
Definition at line 184 of file mrpt_rbpf_slam_wrapper.h.
std::vector<std::pair<CActionCollection, CSensoryFrame> > PFslamWrapper::data [private] |
vector of pairs of actions and obsrvations from rawlog file
Definition at line 179 of file mrpt_rbpf_slam_wrapper.h.
std::string PFslamWrapper::global_frame_id [private] |
/map frame
Definition at line 165 of file mrpt_rbpf_slam_wrapper.h.
std::string PFslamWrapper::ini_filename [private] |
name of ini file
Definition at line 164 of file mrpt_rbpf_slam_wrapper.h.
std::map<std::string, mrpt::poses::CPose3D> PFslamWrapper::laser_poses_ [private] |
laser scan poses with respect to the map
Definition at line 172 of file mrpt_rbpf_slam_wrapper.h.
transform listener
Definition at line 187 of file mrpt_rbpf_slam_wrapper.h.
ros::NodeHandle PFslamWrapper::n_ [private] |
Node Handle.
Definition at line 159 of file mrpt_rbpf_slam_wrapper.h.
std::string PFslamWrapper::odom_frame_id [private] |
/odom frame
Definition at line 166 of file mrpt_rbpf_slam_wrapper.h.
ros::Publisher PFslamWrapper::pub_map_ [private] |
Definition at line 184 of file mrpt_rbpf_slam_wrapper.h.
ros::Publisher PFslamWrapper::pub_metadata_ [private] |
Definition at line 184 of file mrpt_rbpf_slam_wrapper.h.
ros::Publisher PFslamWrapper::pub_Particles_ [private] |
Definition at line 184 of file mrpt_rbpf_slam_wrapper.h.
Definition at line 184 of file mrpt_rbpf_slam_wrapper.h.
std::string PFslamWrapper::rawlog_filename [private] |
name of rawlog file
Definition at line 163 of file mrpt_rbpf_slam_wrapper.h.
bool PFslamWrapper::rawlog_play_ [private] |
true if rawlog file exists
Definition at line 161 of file mrpt_rbpf_slam_wrapper.h.
double PFslamWrapper::rawlog_play_delay [private] |
delay of replay from rawlog file
Definition at line 160 of file mrpt_rbpf_slam_wrapper.h.
std::string PFslamWrapper::sensor_source [private] |
2D laser scans
Definition at line 170 of file mrpt_rbpf_slam_wrapper.h.
std::vector<ros::Subscriber> PFslamWrapper::sensorSub_ [private] |
list of sensors topics
Definition at line 176 of file mrpt_rbpf_slam_wrapper.h.
float PFslamWrapper::t_exec [private] |
the time which take one SLAM update execution
Definition at line 191 of file mrpt_rbpf_slam_wrapper.h.
transform broadcaster
Definition at line 188 of file mrpt_rbpf_slam_wrapper.h.
CTicTac PFslamWrapper::tictac [private] |
timer for SLAM performance evaluation
Definition at line 190 of file mrpt_rbpf_slam_wrapper.h.
std::vector<mrpt::opengl::CEllipsoidPtr> PFslamWrapper::viz_beacons [private] |
Definition at line 182 of file mrpt_rbpf_slam_wrapper.h.