The main slam class. Contains the main functionalities of CRSM slam. More...
#include <crsm_slam.h>
Public Member Functions | |
void | calculateCriticalRays (void) |
Chooses important rays for RRHC. | |
CrsmSlam (int argc, char **argv) | |
Default costructor. | |
void | findTransformation (void) |
Calculates the transformation (translation & rotation) with RRHC. | |
void | fixNewScans (const sensor_msgs::LaserScanConstPtr &msg) |
Serves the laser scan messages. | |
std::string | getBaseFootprintFrame (void) |
Gets the base_footprint_frame of CRSM_SlamParameters. | |
std::string | getBaseFrame (void) |
Gets the base_frame of CRSM_SlamParameters. | |
double | getDensity (void) |
Gets the density of CRSM_SlamParameters. | |
int | getDesiredNumberOfPickedRays (void) |
Gets the desired_number_of_picked_rays of CRSM_SlamParameters. | |
int | getDisparity (void) |
Gets the disparity of CRSM_SlamParameters. | |
double | getDxLaserRobotCenter (void) |
Gets the dx_laser_robotCenter of CRSM_SlamParameters. | |
int | getInitialMapSize (void) |
Gets the map_size of CRSM_SlamParameters. | |
std::string | getLaserFrame (void) |
Gets the laser_frame of CRSM_SlamParameters. | |
CrsmLaserInfo | getLaserInfo (void) |
Returns the laser info in a CrsmLaserInfo structure. | |
std::string | getLaserSubscriberTopic (void) |
Gets the laser_subscriber_topic of CRSM_SlamParameters. | |
std::string | getMapFrame (void) |
Gets the map_frame of CRSM_SlamParameters. | |
CrsmMapInfo | getMapInfo (void) |
Returns the map info in a CrsmMapInfo structure. | |
char | getMapProbability (int x, int y) |
Returns the map occupancy probability of coordinates (x,y) ranging from 0-255 (0 is occupied, 255 is free) | |
int | getMaxHillClimbingIterations (void) |
Gets the max_hill_climbing_iterations of CRSM_SlamParameters. | |
double | getObstacleDensity (void) |
Gets the obstacle_density of CRSM_SlamParameters. | |
double | getOccupancyGridMapFreq (void) |
Gets the occupancy_grid_map_freq of CRSM_SlamParameters. | |
std::string | getOccupancyGridPublishTopic (void) |
Gets the occupancy_grid_publish_topic of CRSM_SlamParameters. | |
double | getOcgd (void) |
Gets the ocgd of CRSM_SlamParameters. | |
double | getRobotLength (void) |
Gets the robot_length of CRSM_SlamParameters. | |
CrsmPose | getRobotPose (void) |
Returns the robot pose in a CrsmPose structure. | |
double | getRobotPoseTfFreq (void) |
Gets the robot_pose_tf_freq of CRSM_SlamParameters. | |
std::string | getRobotTrajectoryPublishTopic (void) |
Gets the robot_trajectory_publish_topic of CRSM_SlamParameters. | |
double | getRobotWidth (void) |
Gets the robot_width of CRSM_SlamParameters. | |
double | getScanSelectionMeters (void) |
Gets the scan_selection_meters of CRSM_SlamParameters. | |
std::vector< CrsmPose > | getTrajectory (void) |
Returns the robot trajectory in a vector of CrsmPose structures. | |
double | getTrajectoryFreq (void) |
Gets the trajectory_freq of CRSM_SlamParameters. | |
std::string | getTrajectoryPublisherFrameId (void) |
Gets the trajectory_publisher_frame_id of CRSM_SlamParameters. | |
std::string | getWorldFrame (void) |
Gets the world_frame of CRSM_SlamParameters. | |
void | publishOGM (const ros::TimerEvent &e) |
Publishes the OccupancyGrid map as nav_msgs::OccupancyGrid, posting with occupancy_grid_map_freq Hz from parameters. | |
void | publishRobotPoseTf (const ros::TimerEvent &e) |
Publishes the Tf robot pose, posting with robot_pose_tf_freq Hz from parameters. | |
void | publishTrajectory (const ros::TimerEvent &e) |
Publishes the robot trajectory as nav_msgs::Path, posting with trajectory_freq Hz from parameters. | |
void | setBaseFootprintFrame (std::string frame) |
Sets the base_footprint_frame of CRSM_SlamParameters. | |
void | setBaseFrame (std::string frame) |
Sets the base_frame of CRSM_SlamParameters. | |
void | setDensity (double density) |
Sets the density of CRSM_SlamParameters. | |
void | setDesiredNumberOfPickedRays (int rays) |
Sets the desired_number_of_picked_rays of CRSM_SlamParameters. | |
void | setDisparity (int disparity) |
Sets the disparity of CRSM_SlamParameters. | |
void | setDxLaserRobotCenter (double dx) |
Sets the dx_laser_robotCenter of CRSM_SlamParameters. | |
void | setInitialMapSize (int size) |
Sets the map_size of CRSM_SlamParameters. | |
void | setLaserFrame (std::string frame) |
Sets the laser_frame of CRSM_SlamParameters. | |
void | setLaserSubscriberTopic (std::string topic) |
Sets the laser_subscriber_topic of CRSM_SlamParameters. | |
void | setMapFrame (std::string frame) |
Sets the map_frame of CRSM_SlamParameters. | |
void | setMaxHillClimbingIterations (int iterations) |
Sets the max_hill_climbing_iterations of CRSM_SlamParameters. | |
void | setObstacleDensity (double ob_density) |
Sets the obstacle_density of CRSM_SlamParameters. | |
void | setOccupancyGridMapFreq (double freq) |
Sets the occupancy_grid_map_freq of CRSM_SlamParameters. | |
void | setOccupancyGridPublishTopic (std::string topic) |
Sets the occupancy_grid_publish_topic of CRSM_SlamParameters. | |
void | setOcgd (double ocgd) |
Sets the ocgd of CRSM_SlamParameters. | |
void | setRobotLength (double length) |
Sets the robot_length of CRSM_SlamParameters. | |
void | setRobotPoseTfFreq (double freq) |
Sets the robot_pose_tf_freq of CRSM_SlamParameters. | |
void | setRobotTrajectoryPublishTopic (std::string topic) |
Sets the robot_trajectory_publish_topic of CRSM_SlamParameters. | |
void | setRobotWidth (double width) |
Sets the robot_width of CRSM_SlamParameters. | |
void | setScanSelectionMeters (double scan_selection_meters) |
Sets the scan_selection_meters of CRSM_SlamParameters. | |
void | setTrajectoryFreq (double freq) |
Sets the trajectory_freq of CRSM_SlamParameters. | |
void | setTrajectoryPublisherFrameId (std::string frame_id) |
Sets the trajectory_publisher_frame_id of CRSM_SlamParameters. | |
void | setWorldFrame (std::string frame) |
Sets the world_frame of CRSM_SlamParameters. | |
void | startLaserSubscriber (void) |
Starts the laser subscriber, listening to laser_subscriber_topic from parameters. | |
void | startOGMPublisher (void) |
Starts the OccupancyGrid publisher, posting to occupancy_grid_publish_topic from parameters. | |
void | startTrajectoryPublisher (void) |
Starts the Trajectory publisher, posting to robot_trajectory_publish_topic from parameters, with trajectory_publisher_frame_id as frame ID. | |
void | stopLaserSubscriber (void) |
Stops the laser subscriber. | |
void | stopOGMPublisher (void) |
Stops the OccupancyGrid publisher. | |
void | stopTrajectoryPublisher (void) |
Stops the Trajectory publisher. | |
void | updateMapProbabilities (void) |
Updates map after finding the new robot pose. | |
~CrsmSlam () | |
Destructor. | |
Public Attributes | |
ros::NodeHandle | n |
The ROS node handle. | |
Private Member Functions | |
bool | checkExpansion (int x, int y, bool update) |
void | expandMap (void) |
void | updateParameters (void) |
Reads the CRSM slam parameters from the yaml file and fills the CrsmSlamParameters structure. | |
Private Attributes | |
tf::TransformListener | _listener |
Tf listener to aquire the transformation between the laser and the robot center. | |
ros::Timer | _mapPublishingTimer |
The map publishing timer. | |
ros::Publisher | _occupancyGridPublisher |
The occupancy grid map publisher. | |
ros::Publisher | _pathPublisher |
The robot trajectory publisher. | |
ros::Timer | _pathPublishingTimer |
The trajectory publishing timer. | |
ros::Timer | _robotPosePublishingTimer |
The robot pose publishing timer. | |
tf::TransformBroadcaster | _slamFrameBroadcaster |
The tf robpt pose broadcaster. | |
int | argc |
Number of input arguments. | |
char ** | argv |
The input arguments. | |
float | bestFitness |
The best RRHC fitness for a specific iteration. | |
CrsmTransformation | bestTransformation |
The best RRHC transformation for a specific iteration. | |
std::set< int > | bigChanges |
Holds the irregularities of a specific scan in terms of distance. | |
ros::Subscriber | clientLaserValues |
The laser subscriber. | |
unsigned int | counter |
Slam iterations counter. | |
CrsmExpansion | expansion |
CrsmLaser | laser |
The laser container. | |
CrsmMap | map |
The OGM container. | |
float | meanDensity |
The mean laser scan density for a specific iteration. | |
CrsmPose | robotPose |
The robot pose. | |
std::vector< CrsmPose > | robotTrajectory |
Container for the robot trajectory. | |
std::set< int > | scanSelections |
Holds the critical rays, on which the scan matching is performed. | |
CrsmSlamParameters | slamParams |
The slam parameters. |
The main slam class. Contains the main functionalities of CRSM slam.
Definition at line 50 of file crsm_slam.h.
crsm_slam::CrsmSlam::CrsmSlam | ( | int | argc, |
char ** | argv | ||
) |
Default costructor.
argc | [int] The number of input arguments |
argv | [char **] The input arguments |
Definition at line 32 of file crsm_slam.cpp.
crsm_slam::CrsmSlam::~CrsmSlam | ( | ) | [inline] |
void crsm_slam::CrsmSlam::calculateCriticalRays | ( | void | ) |
bool crsm_slam::CrsmSlam::checkExpansion | ( | int | x, |
int | y, | ||
bool | update | ||
) | [private] |
Definition at line 468 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::expandMap | ( | void | ) | [private] |
Definition at line 501 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::findTransformation | ( | void | ) |
Calculates the transformation (translation & rotation) with RRHC.
Definition at line 239 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::fixNewScans | ( | const sensor_msgs::LaserScanConstPtr & | msg | ) |
Serves the laser scan messages.
msg | [sensor_msgs::LaserScanConstPtr&] : The laser rays distances |
< Check if laser measurement is in nominal values
Definition at line 399 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getBaseFootprintFrame | ( | void | ) |
Gets the base_footprint_frame of CRSM_SlamParameters.
Definition at line 1096 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getBaseFrame | ( | void | ) |
Gets the base_frame of CRSM_SlamParameters.
Definition at line 1104 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getDensity | ( | void | ) |
Gets the density of CRSM_SlamParameters.
Definition at line 968 of file crsm_slam.cpp.
int crsm_slam::CrsmSlam::getDesiredNumberOfPickedRays | ( | void | ) |
Gets the desired_number_of_picked_rays of CRSM_SlamParameters.
Definition at line 1032 of file crsm_slam.cpp.
int crsm_slam::CrsmSlam::getDisparity | ( | void | ) |
Gets the disparity of CRSM_SlamParameters.
Definition at line 944 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getDxLaserRobotCenter | ( | void | ) |
Gets the dx_laser_robotCenter of CRSM_SlamParameters.
Definition at line 1000 of file crsm_slam.cpp.
int crsm_slam::CrsmSlam::getInitialMapSize | ( | void | ) |
Gets the map_size of CRSM_SlamParameters.
Definition at line 952 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getLaserFrame | ( | void | ) |
Gets the laser_frame of CRSM_SlamParameters.
Definition at line 1120 of file crsm_slam.cpp.
Returns the laser info in a CrsmLaserInfo structure.
Definition at line 664 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getLaserSubscriberTopic | ( | void | ) |
Gets the laser_subscriber_topic of CRSM_SlamParameters.
Definition at line 1080 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getMapFrame | ( | void | ) |
Gets the map_frame of CRSM_SlamParameters.
Definition at line 1112 of file crsm_slam.cpp.
Returns the map info in a CrsmMapInfo structure.
Definition at line 648 of file crsm_slam.cpp.
char crsm_slam::CrsmSlam::getMapProbability | ( | int | x, |
int | y | ||
) |
Returns the map occupancy probability of coordinates (x,y) ranging from 0-255 (0 is occupied, 255 is free)
x | [int] : The x coordinate |
y | [int] : The y coordinate |
Definition at line 640 of file crsm_slam.cpp.
int crsm_slam::CrsmSlam::getMaxHillClimbingIterations | ( | void | ) |
Gets the max_hill_climbing_iterations of CRSM_SlamParameters.
Definition at line 992 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getObstacleDensity | ( | void | ) |
Gets the obstacle_density of CRSM_SlamParameters.
Definition at line 976 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getOccupancyGridMapFreq | ( | void | ) |
Gets the occupancy_grid_map_freq of CRSM_SlamParameters.
Definition at line 1008 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getOccupancyGridPublishTopic | ( | void | ) |
Gets the occupancy_grid_publish_topic of CRSM_SlamParameters.
Definition at line 1056 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getOcgd | ( | void | ) |
Gets the ocgd of CRSM_SlamParameters.
Definition at line 960 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getRobotLength | ( | void | ) |
Gets the robot_length of CRSM_SlamParameters.
Definition at line 1048 of file crsm_slam.cpp.
Returns the robot pose in a CrsmPose structure.
Definition at line 656 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getRobotPoseTfFreq | ( | void | ) |
Gets the robot_pose_tf_freq of CRSM_SlamParameters.
Definition at line 1016 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getRobotTrajectoryPublishTopic | ( | void | ) |
Gets the robot_trajectory_publish_topic of CRSM_SlamParameters.
Definition at line 1064 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getRobotWidth | ( | void | ) |
Gets the robot_width of CRSM_SlamParameters.
Definition at line 1040 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getScanSelectionMeters | ( | void | ) |
Gets the scan_selection_meters of CRSM_SlamParameters.
Definition at line 984 of file crsm_slam.cpp.
std::vector< CrsmPose > crsm_slam::CrsmSlam::getTrajectory | ( | void | ) |
Returns the robot trajectory in a vector of CrsmPose structures.
Definition at line 672 of file crsm_slam.cpp.
double crsm_slam::CrsmSlam::getTrajectoryFreq | ( | void | ) |
Gets the trajectory_freq of CRSM_SlamParameters.
Definition at line 1024 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getTrajectoryPublisherFrameId | ( | void | ) |
Gets the trajectory_publisher_frame_id of CRSM_SlamParameters.
Definition at line 1072 of file crsm_slam.cpp.
std::string crsm_slam::CrsmSlam::getWorldFrame | ( | void | ) |
Gets the world_frame of CRSM_SlamParameters.
Definition at line 1088 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::publishOGM | ( | const ros::TimerEvent & | e | ) |
Publishes the OccupancyGrid map as nav_msgs::OccupancyGrid, posting with occupancy_grid_map_freq Hz from parameters.
e | [const ros::TimerEvent&] The timer event |
Definition at line 609 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::publishRobotPoseTf | ( | const ros::TimerEvent & | e | ) |
Publishes the Tf robot pose, posting with robot_pose_tf_freq Hz from parameters.
e | [const ros::TimerEvent&] The timer event |
Definition at line 681 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::publishTrajectory | ( | const ros::TimerEvent & | e | ) |
Publishes the robot trajectory as nav_msgs::Path, posting with trajectory_freq Hz from parameters.
e | [const ros::TimerEvent&] The timer event |
Definition at line 714 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setBaseFootprintFrame | ( | std::string | frame | ) |
Sets the base_footprint_frame of CRSM_SlamParameters.
frame | [std::string] Holds the base footprint frame - (x,y,yaw) |
Definition at line 907 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setBaseFrame | ( | std::string | frame | ) |
Sets the base_frame of CRSM_SlamParameters.
frame | [std::string] Holds the base frame |
Definition at line 916 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setDensity | ( | double | density | ) |
Sets the density of CRSM_SlamParameters.
density | [double] Map update density (0-127) |
Definition at line 763 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setDesiredNumberOfPickedRays | ( | int | rays | ) |
Sets the desired_number_of_picked_rays of CRSM_SlamParameters.
rays | [int] The desired number of picked rays [algorithm specific] |
Definition at line 835 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setDisparity | ( | int | disparity | ) |
Sets the disparity of CRSM_SlamParameters.
disparity | [int] Disparity of mutation in pixels at hill climbing |
Definition at line 736 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setDxLaserRobotCenter | ( | double | dx | ) |
Sets the dx_laser_robotCenter of CRSM_SlamParameters.
dx | [double] Translation in x axis of laser in comparison to robot center |
Definition at line 799 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setInitialMapSize | ( | int | size | ) |
Sets the map_size of CRSM_SlamParameters.
size | [int] Map size of initial allocated map |
Definition at line 745 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setLaserFrame | ( | std::string | frame | ) |
Sets the laser_frame of CRSM_SlamParameters.
frame | [std::string] Holds the laser frame |
Definition at line 934 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setLaserSubscriberTopic | ( | std::string | topic | ) |
Sets the laser_subscriber_topic of CRSM_SlamParameters.
topic | [std::string] The laser subscriber topic |
Definition at line 889 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setMapFrame | ( | std::string | frame | ) |
Sets the map_frame of CRSM_SlamParameters.
frame | [std::string] Holds the map frame |
Definition at line 925 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setMaxHillClimbingIterations | ( | int | iterations | ) |
Sets the max_hill_climbing_iterations of CRSM_SlamParameters.
iterations | [int] Maximum RRHC iterations |
Definition at line 790 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setObstacleDensity | ( | double | ob_density | ) |
Sets the obstacle_density of CRSM_SlamParameters.
ob_density | [double] Coefficient for obstacle update density (0+) |
Definition at line 772 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setOccupancyGridMapFreq | ( | double | freq | ) |
Sets the occupancy_grid_map_freq of CRSM_SlamParameters.
freq | [double] The occupancy grid map publishing frequency |
Definition at line 808 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setOccupancyGridPublishTopic | ( | std::string | topic | ) |
Sets the occupancy_grid_publish_topic of CRSM_SlamParameters.
topic | [std::string] The occupancy grid publishing topic |
Definition at line 862 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setOcgd | ( | double | ocgd | ) |
Sets the ocgd of CRSM_SlamParameters.
ocgd | [double] [OC]cupancy [G]rid [D]imentionality - the width and height in meters of a pixel |
Definition at line 754 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setRobotLength | ( | double | length | ) |
Sets the robot_length of CRSM_SlamParameters.
length | [double] The robot length |
Definition at line 853 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setRobotPoseTfFreq | ( | double | freq | ) |
Sets the robot_pose_tf_freq of CRSM_SlamParameters.
freq | [double] The robot pose publishing frequency |
Definition at line 817 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setRobotTrajectoryPublishTopic | ( | std::string | topic | ) |
Sets the robot_trajectory_publish_topic of CRSM_SlamParameters.
topic | [std::string] The trajectory publishing topic |
Definition at line 871 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setRobotWidth | ( | double | width | ) |
Sets the robot_width of CRSM_SlamParameters.
width | [double] The robot width |
Definition at line 844 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setScanSelectionMeters | ( | double | scan_selection_meters | ) |
Sets the scan_selection_meters of CRSM_SlamParameters.
scan_selection_meters | [double] Scan density lower boundary for a scan-part identification |
Definition at line 781 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setTrajectoryFreq | ( | double | freq | ) |
Sets the trajectory_freq of CRSM_SlamParameters.
freq | [double] The trajectory publishing frequency |
Definition at line 826 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setTrajectoryPublisherFrameId | ( | std::string | frame_id | ) |
Sets the trajectory_publisher_frame_id of CRSM_SlamParameters.
frame_id | [std::string] The trajectory frame ID |
Definition at line 880 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::setWorldFrame | ( | std::string | frame | ) |
Sets the world_frame of CRSM_SlamParameters.
frame | [std::string] Holds the world frame |
Definition at line 898 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::startLaserSubscriber | ( | void | ) |
Starts the laser subscriber, listening to laser_subscriber_topic from parameters.
Definition at line 573 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::startOGMPublisher | ( | void | ) |
Starts the OccupancyGrid publisher, posting to occupancy_grid_publish_topic from parameters.
Definition at line 590 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::startTrajectoryPublisher | ( | void | ) |
Starts the Trajectory publisher, posting to robot_trajectory_publish_topic from parameters, with trajectory_publisher_frame_id as frame ID.
Definition at line 695 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::stopLaserSubscriber | ( | void | ) |
void crsm_slam::CrsmSlam::stopOGMPublisher | ( | void | ) |
void crsm_slam::CrsmSlam::stopTrajectoryPublisher | ( | void | ) |
void crsm_slam::CrsmSlam::updateMapProbabilities | ( | void | ) |
Updates map after finding the new robot pose.
Definition at line 515 of file crsm_slam.cpp.
void crsm_slam::CrsmSlam::updateParameters | ( | void | ) | [private] |
Reads the CRSM slam parameters from the yaml file and fills the CrsmSlamParameters structure.
Definition at line 65 of file crsm_slam.cpp.
Tf listener to aquire the transformation between the laser and the robot center.
Definition at line 57 of file crsm_slam.h.
The map publishing timer.
Definition at line 93 of file crsm_slam.h.
The occupancy grid map publisher.
Definition at line 54 of file crsm_slam.h.
The robot trajectory publisher.
Definition at line 55 of file crsm_slam.h.
The trajectory publishing timer.
Definition at line 91 of file crsm_slam.h.
The robot pose publishing timer.
Definition at line 92 of file crsm_slam.h.
The tf robpt pose broadcaster.
Definition at line 56 of file crsm_slam.h.
int crsm_slam::CrsmSlam::argc [private] |
Number of input arguments.
Definition at line 64 of file crsm_slam.h.
char** crsm_slam::CrsmSlam::argv [private] |
The input arguments.
Definition at line 65 of file crsm_slam.h.
float crsm_slam::CrsmSlam::bestFitness [private] |
The best RRHC fitness for a specific iteration.
Definition at line 69 of file crsm_slam.h.
The best RRHC transformation for a specific iteration.
Definition at line 72 of file crsm_slam.h.
std::set<int> crsm_slam::CrsmSlam::bigChanges [private] |
Holds the irregularities of a specific scan in terms of distance.
Definition at line 79 of file crsm_slam.h.
The laser subscriber.
Definition at line 53 of file crsm_slam.h.
unsigned int crsm_slam::CrsmSlam::counter [private] |
Slam iterations counter.
Definition at line 67 of file crsm_slam.h.
CrsmExpansion crsm_slam::CrsmSlam::expansion [private] |
Definition at line 59 of file crsm_slam.h.
CrsmLaser crsm_slam::CrsmSlam::laser [private] |
The laser container.
Definition at line 62 of file crsm_slam.h.
CrsmMap crsm_slam::CrsmSlam::map [private] |
The OGM container.
Definition at line 61 of file crsm_slam.h.
float crsm_slam::CrsmSlam::meanDensity [private] |
The mean laser scan density for a specific iteration.
Definition at line 70 of file crsm_slam.h.
The ROS node handle.
Definition at line 97 of file crsm_slam.h.
CrsmPose crsm_slam::CrsmSlam::robotPose [private] |
The robot pose.
Definition at line 73 of file crsm_slam.h.
std::vector<CrsmPose> crsm_slam::CrsmSlam::robotTrajectory [private] |
Container for the robot trajectory.
Definition at line 76 of file crsm_slam.h.
std::set<int> crsm_slam::CrsmSlam::scanSelections [private] |
Holds the critical rays, on which the scan matching is performed.
Definition at line 78 of file crsm_slam.h.
The slam parameters.
Definition at line 74 of file crsm_slam.h.