leo_navigation
package first. To do this, start by accessing a remote terminal session on the Rover by logging via ssh:leo_navigation
package to the source space:rosdep
to install dependencies:~/.bashrc
file. base_link
to frame ids associated with the sensor messages, available in the tf tree.<distribution>
with the ROS distribution you have installed on your computer (either kinetic
or melodic
). leo_navigation
package and how to use them.ekf_localization_node
which implements Extended Kalman Filter algorithm and the ukf_localization_node
which implements Unscented Kalman Filter. We will use the first option as it is less computationally expensive but the latter is a more stable alternative.odometry.launch
file and the connections between them:leo_navigation
package provides the message_filter
node which:/wheel_odom
topic, publishes a message on the /wheel_odom_with_covariance
topic which contains the same data but with an added covariance matrix,/imu/accel
and /imu/gyro
messages, publishes a message on /imu/data_raw
topic which combines the two messages and adds covariance matrices.ekf_localization_node
listens for the base_link->imu
tf transform to transform IMU readings to a common reference frame (base_link
in this case)./odometry/filtered
topic and the pose is also broadcasted as the odom->base_link
transform. That's why, having the Fixed Frame set to odom
in RViz, you can see the model moving.three_d
argument set to true
: odometry.launch
file now changes a little:/imu_filter_node
which takes messages from the /imu/data_raw
topic (gyroscope and accelerometer data), calculates the orientation of the sensor and publishes the data with added orientation quaternion on the /imu/data
topic. The node can also optionally incorporate the /imu/mag
topic (magnetometer data)./ekf_localization_node
now uses different configuration which takes the data from /imu/data
topic and uses the orientation quaternion in the state estimation./message_filter
node, there is the config/message_filter.yaml file in which you can change the values on the diagonals of the covariance matrices, which represent the variances (the uncertainty) of the measurements./ekf_localization_node
can be found in the config/ekf_localization_node/ directory. There are two files: ekf_2d.yaml and ekf_3d.yaml. The appropriate file is chosen depending on the value of 3d
argument passed to the launch file.use_mag
parameter to true
. use_mag
parameter and want use the heading information (compass) in /ekf_localization_node
, just modify the imu0_config
parameter so that the yaw value is fused into the state estimate:slam
configuration: gmapping.launch
file is pretty straightforward:/slam_gmapping
node takes as the input:/scan
topic),base_link->laser_frame
transform),odom->base_link
transform)./map
and /map_metadata
topics),map->odom
transform).map
, odom
and base_link
are coordinate frame names commonly used in mobile platforms. To learn about their semantic meaning, you can read REP105./slam_gmapping
node tries to correct robot's position within the map, it does not broadcast the position as the map->base_link
transform, because that would make 2 root coordinate frames (map
and odom
). Instead, it provides the map->odom
transform which marks the difference between the odometry position and the actual position of the robot within the map (the odometry drift). /gmapping
node can draw unnecessary resources for its mapping part. When map is no longer updated, it is more efficient to just use an algorithm that will only track robot's position against the map you have generated.map_saver
script:gmapping.launch
instance by clicking Ctrl+C on the terminal session it is running on. Then start amcl.launch
by typing:<path_to_the_map_file>
with the absolute path to the mymap.yaml file. If the file is in your current working directory, you can instead type:/slam_gmapping
node, /amcl
takes the laser range data (/scan
topic) as input and provides the odometry drift information by broadcasting the map->odom
transform. The difference is that instead of publishing to the /map
topic, it receives the (previously generated) map from the /map_server
node./amcl
node:/amcl_pose
− estimated pose of the robot within a map, with covariance,/particlecloud
− a set of pose estimates being maintained by the Monte Carlo localization algorithm.AMCL Pose
and/or the AMCL Particle Cloud
displays in RViz./slam_gmapping
node is loaded from the config/slam_gmapping.yaml file. For description of each parameter, visit the gmapping ROS wiki page.map_update_interval
− control how often to update the map. linearUpdate
, angularUpdate
, temporalUpdate
− control when to process new laser scans.particles
− increasing this number may improve the quality of the map at the cost of greater computational load.minimumScore
− you can experiment with this parameter if you are experiencing jumping pose estimates in large open spaces.maxUrange
, maxRange
− try to set these parameters like this:
maxUrange
< maximum range of your LiDAR sensor <= maxRange
.delta
− increasing this will lower the resolution of the map but may improve performance./amcl
node, there is the config/amcl.yaml file with the parameters that are described in the amcl ROS wiki page.min_particles
, max_particles
− higher number of particles may increase the accuracy of the estimates at the cost of computational load.update_min_d
,update_min_a
− control when to perform filter updates.initial_pose_x
, initial_pose_y
, initial_pose_a
− initial mean pose used to initialize the filter.laser_max_beams
− you can experiment with this parameter. Higher number may increase the accuracy at the cost of computational load.twist_mux.launch
and move_base.launch
files.navigation
configuration:/cmd_vel
topic).navigation.launch
file:/move_base
node's inputs include:/scan
topic),base_link->laser_frame
transform),/map
topic),/ekf_localization_node
(/odometry/filtered
topic),odom->base_link
and map->odom
transforms)./move_base
node can receive navigation goals in 2 ways:/move_base_simple/goal
topic − upon receiving a PoseStamped message on this topic, the node will cancel any running operation and try to reach the new destination. This is how the 2D Nav Goal tool in RViz sends the pose selected by the user./nav_cmd
topic./twist_mux
node chooses which topic with velocity commands to forward to the /cmd_vel
topic. If no messages are sent on /ui_vel
and /joy_vel
topics, the /nav_cmd
will be selected. To utilize the other topics when using a joystick or the Web UI, you need to make sure the velocity commands from these components are published on corresponding topics. cmd_vel_topic
argument to the launch file:cmd_vel
to ui_vel
in the /opt/leo_ui/js/leo.js file on your rover. You might also need to clear the cache data on your browser./move_base
node as a black box to which we send navigation goals and get velocity commands in return. This is fine to start with, but if you want to fine-tune configuration for your environment, you might need to know about various components of move_base
and how do they work with each other. This will help you to understand the meaning behind the parameters./map
topic) and marks cells in the costmap as either "Unknown", "Freespace" or "Lethal" depending on the value of corresponding pixels on the map.global_costmap
− used for creating long-term plans over the entire environment. Combines all 3 defined layers and runs in the map
coordinate frame.local_costmap
− used for local planning and obstacle avoidance. Utilizes only the Obstacle and Inflation layers. Uses the "Rolling Window", meaning that it will remain centered around the robot as it moves to represent only the local surroundings. Runs in the odom
coordinate frame to guarantee that the pose of the robot in the map will be continuous.global_costmap
. Upon receiving a navigation goal, finds a safe path from the current position of the robot to the goal position. Our configuration uses the implementation from the global_planner package which utilizes Dijkstra's algorithm.local_costmap
. Given a path to follow and the costmap, it produces velocity commands to send to the robot. We use the implementation from the base_local_planner package which uses the Dynamic Window Approach./move_base
node uses components that have their own ROS APIs, the configuration has been split into multiple files to make it more modular. There is a total of 6 files under the config/move_base/ directory. Here is a short description of each file and some parameters you can try to adjust:/move_base
node.controller_frequency
– increasing this may improve the response time, but be careful not to violate the real-time constraint.clearing_rotation_allowed
– you may want to disable clearing rotations when debugging the local planner.conservative_reset_dist
– smaller values will clean more space on Conservative reset.footprint
– if you have mounted additional equipment to your rover that expands the outer dimensions of the robot, you should modify this parameter. obstacle_layer/obstacle_range
– set it to the usable range of your LiDAR sensor.obstacle_layer/raytrace_range
– set it slightly larger than the usable range of your sensor but smaller than the maximum range.obstacle_layer/scan/expected_update_rate
– set it slightly larger than the update rate of your sensor (time between scan messages).inflation_layer/inflation_radius
– larger values will make the planners prefer paths more distant from the obstacles but can make it difficult to travel through narrow corridors.inflation_layer/cost_scaling_factor
– let's you control how the cost values decrease with distance. Larger values will make the cost decay function more steeper.update_frequency
– increasing it improves the response time to obstacles but affects performance.publish_frequency
– higher values will make RViz visualization more responsive at the cost of increased network throughput.update_frequency
– as above.publish_frequency
– as above.width
, height
– let's you control how much of the local surroundings to remember.resolution
– smaller values will make the map more precise at the cost of increased size.default_tolerance
– you can set it if there is a possibility of an obstacle in the goal position.use_dijkstra
– setting this to false
will make the Global Planner use A* algorithm for path searching which is more efficient than Dijktra but may not find the optimal path. Useful in very large maps.xy_goal_tolerance
– a too small value can make the robot oscillate in goal position.yaw_goal_tolerance
– you can increase it if you don't care that much about the resulting orientation of the rover.pdist_scale
, gdist_scale
, occdist_scale
– these parameters may require some trial and error to fine-tune them to your environment.