<> <> == Overview == This package contains two nodes that talk to [[https://code.google.com/p/fovis/|fovis]] (which is build by the [[fovis|fovis package]]): `mono_depth_odometer` and `stereo_odometer`. Both estimate camera motion based on incoming rectified images from calibrated cameras. The first one needs a registered depth image to associate a depth value to each pixel in the incoming image, the second one calculates this depth from a calibrated stereo system. Both odometers provide full 6DOF incremental motion estimates and should work out of the box. == Used tfs == Please read [[http://www.ros.org/reps/rep-0105.html|REP 105]] for an explanation of odometry frame ids. The chain of transforms relevant for visual odometry is as follows: `world` → `odom` → `base_link` → `camera` Visual odometry algorithms generally calculate ''camera motion''. To be able to calculate ''robot motion'' based on ''camera motion'', the transformation from the camera frame to the robot frame has to be known. Therefore this implementation needs to know the tf `base_link` → `camera` to be able to publish `odom` → `base_link`. The name of the camera frame is taken from the incoming images, so be sure your camera driver publishes it correctly. ''NOTE'': The coordinate frame of the camera is expected to be the ''optical'' frame, which means `x` is pointing right, `y` downwards and `z` from the camera into the scene. The origin is where the camera's principle axis hits the image plane (as given in <>). To learn how to publish the required tf `base_link` → `camera`, please refer to the [[tf/Tutorials|tf tutorials]]. If the required tf is not available, the odometer assumes it as the identity matrix which means the robot frame and the camera frame are identical. == Limitations == fovis was designed to estimate the motion of a MAV (micro aerial vehicle) using a Kinect sensor. As the used feature descriptors are not rotation invariant, the odometer needs to work at high frequencies to estimate in-plane rotations correctly. == Nodes == {{{ #!clearsilver CS/NodeAPI name = Common for mono_depth_odometer and stereo_odometer pub { 0.name = ~pose 0.type = geometry_msgs/PoseStamped 0.desc = The robot's current pose according to the odometer. 1.name = ~odometry 1.type = nav_msgs/Odometry 1.desc = Odometry information that was calculated, contains pose and twist. ''NOTE:'' pose and twist covariance is not published. 2.name = ~features 2.type = sensor_msgs/Image 2.desc = Image showing feature matches as well as some internal information. 3.name = ~info 3.type = fovis_ros/FovisInfo 3.desc = Message containing internal information such as number of features, matches, timing etc. } param { group.0 { name = tf related 0.name = ~odom_frame_id 0.type = string 0.desc = Name of the world-fixed frame where the odometer lives. 0.default = `/odom` 1.name = ~base_link_frame_id 1.type = string 1.desc = Name of the moving frame whose pose the odometer should report. 1.default = `/base_link` 2.name = ~publish_tf 2.type = bool 2.desc = If true, the odometer publishes tf's (see above). 2.default = true } group.1 { name = Odometry Parameters desc = Please see [[http://docs.fovis.googlecode.com/git/group__FovisCore.html#ga113578b67d3e37bc78f1fffd8440e1ff|this page]] for a list of all parameters and their meanings. ''NOTE:'' To comply with ROS naming standards you have to replace hyphens by underscore when setting the parameters through ROS. All parameters are ''strings'', even the numeric parameters have to be given as strings. } } req_tf { 0.from = ~base_link_frame_id 0.to = 0.desc = Transformation from the robot's reference point (`base_link` in most cases) to the camera's optical frame. } prov_tf { 0.from = ~odom_frame_id 0.to = ~base_link_frame_id 0.desc = Transformation from the odometry's origin (e.g. `odom`) to the robot's reference point (e.g. `base_link`) } }}} {{{ #!clearsilver CS/NodeAPI name = mono_depth_odometer sub { 0.name = /rgb/image_rect 0.type = sensor_msgs/Image 0.desc = The rectified input image. There must be a corresponding `camera_info` topic as well. 1.name = /depth_registered/image_rect 1.type = sensor_msgs/Image 1.desc = The corresponding depth image. There must be a corresponding `camera_info` topic as well. Values must be given in floating point format (distance in meters). } }}} {{{ #!clearsilver CS/NodeAPI name = stereo_odometer sub { 0.name = /left/ 0.type = sensor_msgs/Image 0.desc = Left rectified input image. 1.name = /right/ 1.type = sensor_msgs/Image 1.desc = Right rectified input image. 2.name = /left/camera_info 2.type = sensor_msgs/CameraInfo 2.desc = Camera info for left image. 3.name = /right/camera_info 3.type = sensor_msgs/CameraInfo 3.desc = Camera info for right image. } }}} == Troubleshoting == If you have a problem, please look on ROS Answers (FAQ link above) and post a question if you could not find an answer. == Feedback == Please use the stack's issue tracker at Github to submit bug reports and feature requests regarding the ROS wrapper of fovis: https://github.com/srv/fovis/issues/new. ## AUTOGENERATED DON'T DELETE ## CategoryPackage