<<PackageHeader(tuw_marker_slam)>> <<TOC(4)>> == Overview == {{{ #!clearsilver CS/NodeAPI node { no_header=True 0.name= tuw_marker_slam_node 0.desc= This C++ ROS node implements the SLAM framework. It listens for commands executed by the vehicle for the prediction step and receives the detected markers for the update step. At the end of each SLAM cycle it publishes the currently explored marker map and the vehicles estimated pose in it. Furthermore a transformation from the established map to odom is provided. } }}} <<Youtube(SZuM3l5PQlw)>> == Related papers == * '''Mobile Robotics: EKF-SLAM using Visual Markers for Vehicle Pose Estimation''' * Macsek, M., ''"Masters Thesis at Vienna University of Technology"'', 2016 ([[http://www.tuwien.ac.at|PDF]]) == Usage == {{{ rosrun tuw_marker_slam tuw_marker_slam_node }}} === Examples === Start SLAM framework in EKF-SLAM mode with a predefined measurement noise model: {{{ roslaunch tuw_marker_slam slam.launch }}} Start SLAM framework in EKF-SLAM mode with a predefined measurement noise model using the simulation environment Stage (https://github.com/tuw-robotics/stage_ros): {{{ roslaunch tuw_marker_slam slam_demo_stage.launch }}} Start SLAM framework in EKF-SLAM mode with a predefined measurement noise model using the simulation environment Gazebo (https://github.com/tuw-robotics/tuw_gazebo) and the tuw_aruco marker detection {{{ roslaunch tuw_marker_slam slam_demo_gazebo.launch }}} === Node === {{{ #!clearsilver CS/NodeAPI sub { 0.name= cmd 0.type= geometry_msgs/Twist 0.desc= Velocity and angular rate commands of the vehicle will be retrieved via this latched topic. 1.name= marker 1.type= marker_msgs/MarkerDetection 1.desc= Pose measurements of detected markers will be retrieved via this latched topic. } pub { 0.name= xt 0.type= geometry_msgs/PoseWithCovarianceStamped 0.desc= Receive the vehicles pose in the currently explored marker map via this latched topic. 1.name= mt 1.type= marker_msgs/MarkerWithCovarianceArray 1.desc= Receive the currently explored marker map via this latched topic. } req_tf { 0.from = base 0.to = odom 0.desc = Transform from the estimated pose to odom 1.from = <frame in which measurements are taken> 1.to = base 1.desc = Transform incoming measurements into the base frame } prov_tf { 0.from = map 0.to = odom 0.desc = Transform from the estimated map to odom } param{ 0.name = mode 0.type = int 0.default = 0 0.desc = Indicates the used SLAM technique: 0 - EKF-SLAM 1.name = xzplane 1.type = boolean 1.default = `false` 1.desc = Indicates whether the measurements are taken in the XZ-plane (e.g. Gazebo) or in the XY-plane (e.g. Stage) 2.name = frame_id_map 2.type = string 2.default = `"map"` 2.desc = Name of frame inserted into header of published map and vehicle pose respectively but also used as source frame in the provided transformation from map to odom. 3.name = frame_id_odom 3.type = string 3.default = `"odom"` 3.desc = Name of destination frame used in the provided transformation from map to odom. 4.name = frame_id_base 4.type = string 4.default = `"base_link"` 4.desc = Name of vehicles frame. 5.name = beta_1/18 5.type = double 5.desc = Parameters of the used measurement noise model in EKF SLAM. } }}}