By default mbs_slam nodes requires
/mbs/points(sensor_msgs/PointCloud2) to be published. All other
sensor informations are optional. Indepth information on the
configuration parameters can be found in koide3
GPS
enable_gps: True in case gps readings are provided. The mbs_slam
node needs typically supports 3 types of GPS messages:
/mbs/geopoint (geographic_msgs/GeoPointStamped)
/mbs/navsat (sensor_msgs/NavSatFix)
/mbs/nmea_sentence (nmea_msgs/Sentence)
From all of the above mentioned topics only longitude, latitude, and
altitude are used and rest of the fields in the messages are ignored.
IMU Acceleration
enable_imu_acc: By default acceleration resulting from sensor motion
is ignored therefore it is useful to provide this paramter (Do not set
bigger values for this constraint.)
IMU Orientation
enable_imu_ori: In case the provided IMU has a reliable magentic
sensor, orientation can be added as a 3d orientation constraint. In case
of external magentic disturbances this paramter should be set to false.
Floor detection
For largescale flat indoor environments, this constraints can be
specified. It will reduce the effect of accumulated rotation error.
3D-Localization
The node first does sensor localization using the onboard imu on the
lidar. Odomerty prediction based on external imu is optional, if not set
constant velocity model is used internally.
You may provide a list of GPS coordinates directly via
gps_waypoints.yaml file located in the waypoints folder in the
mbs_waypoint_follower package.
In it orientation represents the the quaternions of the final
goal position and the position represents the latitude,
longtitude, and altitude resepectively.
Without an auxiliary sensor such as a LiDAR, obstacle avoidance in navigation cannot be performed
nor localization.
Software Requirements
Ubuntu 18.04/Ubuntu 20.04
ROS-melodic/ROS-noetic
MYBOTSHOP GPS package
GPS package dependencies
Warning
The provided MYBOTSHOP GPS package allows for point to point navigation
utilizing GPS coordinates. It integrates the MoveBase package which in
turn allows for collision avoidance. This GPS package is currently designed
for 2D planes with a planned expansion for 3D planes. Caution must be
exercised when using the package around people and or in an
un-constrained environment as any fault in sensors or misconfiguration
may lead to an accident.
Configuration
In the provided package, several configuration have to be adjusted which
are:
Localization
GPS localization config file
Odom localization config file
MoveBase
Base local planner params
Costmap common params
Global costmap params
Local costmap params
Movebase params
In-depth information is documented by the authors of the robot
localization package.
Quick Tuning
Quick tuning and configuration can be performed via rqt_reconfigure
rosrunrqt_reconfigurerqt_reconfigure
GPS Localization Config
In this configuration file, we combine three sensor readings, which are
the robots odom, imu, and the gps.
frequency: 20
The frequency depicts the rate at which the node publishes
information.
two_d_mode: true
It tells to ignore the height readings from the incoming sensors
as we are navigating in 2D.
publish_tf: true
Publishes a transform from the map frame to the odom frame
transform_time_offset: 2
Offsets the transform as some packages require transforms to be
future off-set by a few seconds.
Setting the sequence of transforms for this localization node.
odom_frame: odom
base_link_frame: base_link
world_frame: map
map_frame: map
It is important to change the odom to the odom published by your robot.
odom0: /your_robot/odom
This is typically published by the robots controller
The boolean values are (X, Y, Z, roll, pitch, yaw, Xv, Yv, Zv,
rollv, pitchv, yawv, Xa, Ya, Za).
v is velocity and a is acceleration
odom1_differential: false
It is highly important to tune the process noises.
process_noise_covariance:
This determines on how much to trust the incoming data. Each line
represents X, Y, Z, roll, pitch, yaw, Xv, Yv, Zv, rollv, pitchv,
yawv, Xa, Ya, Za. Values for these are assigned along the
diagonals.
initial_estimate_covariance:
This determines on how much to trust the initial data. Each line
represents X, Y, Z, roll, pitch, yaw, Xv, Yv, Zv, rollv, pitchv,
yawv, Xa, Ya, Za. Values for these are assigned along the
diagonals.
For more information, the following repository by MethylDragon has a
great explanatory guide.
Odom Localization Config
In this configuration file, we combine two sensor readings, which are
the robots odom, and imu.
frequency: 20
The frequency depicts the rate at which the node publishes
information.
two_d_mode: true
It tells to ignore the height readings from the incoming sensors
as we are navigating in 2D.
publish_tf: true
Publishes a transform from the odom frame to the map frame
transform_time_offset: 1
Offsets the transform as some packages require transforms to be
future off-set by a few seconds.
Setting the sequence of transforms for this localization node.
odom_frame: odom
base_link_frame: base_link
world_frame: odom
It is important to change the odom to the odom published by your robot.
odom0: /your_robot/odom
This is typically published by the robots controller
It is important to note that the DWA planner is no longer used and we use the TEB planner.
Configuration for the teb planner can be found in the TEB planner wiki. An excellent resource
for tuning your TEB planner is vailable in TEB planner tuning.
It is recommended to configure the move base planner to ensure correct
movement. Several important ones are:
meter_scoring: true
When true distance is measured in meters.
yaw_goal_tolerance: 0.157
Tolerance in radians for movebase.
xy_goal_tolerance: 0.25
Tolerance in xy coordinates for movebase.
path_distance_bias: 0.35
Weighting factor of how close the robot should stay to the path.
goal_distance_bias: 1.0
Weighting factor of how close the robot should attempt to reach
the goal.
heading_lookahead: 0.325
Tolerance of looking ahead for available space for turning.
For more information, the following MoveBase Wiki has a brief
explanation.
Costmap Common Params
The costmap will be used to integrate and utilize your existing sensor
for collision avoidance.Important parameters for this are:
The footprint defines a square size for the robot. The robots mid
point is taken as 0,0 and the the corner points are the distance
from the mid point.
footprint_padding: 0.1
Safety-gap that inflates the original footprint.
obstacle_layer:
Sensors that are utilized for sensing. Typically, scan is used
for LiDARs and the sort. Important is to change the sensor_frame
to match the URDF and the topic to match the input message of the
LiDAR.
For more information, the following Costmap Wiki has a brief
explanation.
Global Costmap Params
The global costmap of movebase node, as the name states publishes the
global costmap. It takes the map, provided by the map server as a static
layer. An important point to note is that some warning messages may
occur if the on board computer system do not compute the transforms fast
enough. These warnings can be ignored.
Local Costmap Params
The local costmap of movebase node publishes the local costmap. It
ypically requires the odom frame to operate. However, as we want to
depend solely on our GPS, we utilize the map frame for the local costmap
as well.
MoveBase Params
The movebase params are important for changing the planner frequency and
controller frequency. Usually the default settings are sufficient.
recovery_behavior_enabled: true
It rotates the robot to recover from faulty planning failures or
positioning, at times this is not desirable and may need to be
turned off.