navigate jackal in gazebo 2 - ori-systems/work_experience GitHub Wiki
In this section you will learn how to create your own navigation script, generate maps and save them.
The first thing you will need for a robot to navigate is the ability to move around without crashing into everything. For this you will learn:
- How to move the robot
- How to navigate without a map.
- How to map the environment
- How to set the navigation stack to be able to send him a location and be able to reach that destination.
- How to send it a sequence of waypoints and execute those movements. This is not present in the document
To move Jackal, as you saw in the introduction you can do it many ways, but in reality all do the same thing: publish into the /cmd_vel
topic.
Publish through the terminal in the mentioned topic and see if you can make Jackal move forwards, backwards, left, right and in circles.
You should have done something like this: In a terminal:
rostopic pub /cmd_vel geometry_msgs/Twist [TAB][TAB]
With this command you can then fill in the structure that appears after hitting TAB key two consecutive times, to publish the message.
Create a package where you can have all your programs. Use the name my_jackal_tools
for future reference.
In a terminal:
cd ~/work_experience_ws/src/work_experience
catkin_create_pkg my_jackal_tools std_msgs geometry_msgs rospy roscpp
cd my_jackal_tools/
mkdir launch
mkdir scripts
mkdir maps
mkdir params
cd ~/work_experience_ws/
catkin_make
Create a program that moves jackal around publishing in the /cmd_vel
topic. See how it moves. Play with the program, see if you can make Jackal move forwards, backwards, left, right and in circles. This is crucial to know what you can do with your robot.
-
Inside
my_jackal_tools/scripts
create the filemove.py
(copy the solution given below) move.py#!/usr/bin/env python import rospy from geometry_msgs.msg import Twist def move(): # Starts a new node rospy.init_node(‘robot_move’, anonymous=True) velocity_publisher = rospy.Publisher(’/cmd_vel’, Twist, queue_size=10) vel_msg = Twist() #Receiveing the user's input print("Let's move your robot") speed = float(input("Input your speed: ")) distance = float(input("Type your distance: ")) isForward = int(input("Forward?: True(1) / False(0): "))#True or False #Checking if the movement is forward or backwards if(isForward==1): vel_msg.linear.x = abs(speed) else: vel_msg.linear.x = -abs(speed) #Since we are moving just in x-axis vel_msg.linear.y = 0 vel_msg.linear.z = 0 vel_msg.angular.x = 0 vel_msg.angular.y = 0 vel_msg.angular.z = 0 current_distance = 0 while not rospy.is_shutdown(): #Setting the current time for distance calculus t0 = rospy.Time.now().to_sec() #Loop to move the turtle in an specified distance while(current_distance < distance): #Publish the velocity velocity_publisher.publish(vel_msg) #Takes actual time to velocity calculus t1=rospy.Time.now().to_sec() #Calculates distancePoseStamped current_distance= speed*(t1-t0) #After the loop, stops the robot vel_msg.linear.x = 0 #Force the robot to stop velocity_publisher.publish(vel_msg) if __name__ == '__main__': try: #Testing our function move() except rospy.ROSInterruptException: pass
-
Make your node executable: Execute in a terminal:
chmod u+x ~/work_experience_ws/src/work_experience/my_jackal_tools/scripts/move.py
-
Run the program: In a new terminal, run:
rosrun my_jackal_tools move.py
Here you will learn how to reproduce the system that you launched in the Introduction to make Jackal navigate only with the map generated locally by the detection of obstacles.
Here we will go over the files and only point out particular elements for Jackal. If you want to know more details on how navigation is performed in ROS, have a look here: http://wiki.ros.org/navigation. To learn how the different components in the navigation stack interact, please have a look at http://wiki.ros.org/move_base#move_base-1.
Create the launch file for move base
This is the core of how to make Jackal move around. The package move_base
makes all the path planning for you.
You will use move_base
for all the navigation, but here it only has Jackals sensors to detect obstacles.
Here you have an example of how move_base
should be launched.
odom_navigation.launch
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find my_jackal_tools)/params/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find my_jackal_tools)/params/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find my_jackal_tools)/params/global_costmap_params.yaml" command="load" />
<rosparam file="$(find my_jackal_tools)/params/local_costmap_params.yaml" command="load" />
<rosparam file="$(find my_jackal_tools)/params/base_local_planner_params.yaml" command="load" />
<rosparam file="$(find my_jackal_tools)/params/move_base_params.yaml" command="load" />
<param name="base_global_planner" type="string" value="navfn/NavfnROS" />
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS"/>
<remap from="odom" to="odometry/filtered" />
</node>
</launch>
Here we have some elements to comment on:
Basically move_base
takes in configuration files of .yaml
format that define everything. From which planner it's going to use, to how the maps are used or sensors.
costmap_common_params.yaml
map_type: costmap
origin_z: 0.0
z_resolution: 1
z_voxels: 2
obstacle_range: 2.5
raytrace_range: 3.0
publish_voxel_map: false
transform_tolerance: 0.5
meter_scoring: true
footprint: [[-0.21, -0.165], [-0.21, 0.165], [0.21, 0.165], [0.21, -0.165]]
footprint_padding: 0.1
plugins:
- {name: obstacles_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflater_layer, type: "costmap_2d::InflationLayer"}
obstacles_layer:
observation_sources: scan
scan: {sensor_frame: front_laser, data_type: LaserScan, topic: front/scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 2.5, raytrace_range: 5.0}
inflater_layer:
inflation_radius: 0.30
Note the obstacles_layer
, that uses the topic /front/scan
to read the laser readings.
Also note the ray trace range is only 5 metres. This is just to make detections faster and not have in mind areas that aren't close enough.
global_costmap_params.yaml
global_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 20
publish_frequency: 5
width: 40.0
height: 40.0
resolution: 0.05
origin_x: -20.0
origin_y: -20.0
static_map: true
rolling_window: false
local_costmap_params.yaml
local_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 20.0
publish_frequency: 5.0
width: 10.0
height: 10.0
resolution: 0.05
static_map: false
rolling_window: true
base_local_planner_params.yaml
TrajectoryPlannerROS:
# Robot Configuration Parameters
acc_lim_x: 10.0
acc_lim_theta: 20.0
max_vel_x: 0.5
min_vel_x: 0.1
max_vel_theta: 1.57
min_vel_theta: -1.57
min_in_place_vel_theta: 0.314
holonomic_robot: false
escape_vel: -0.5
# Goal Tolerance Parameters
yaw_goal_tolerance: 0.157
xy_goal_tolerance: 0.25
latch_xy_goal_tolerance: false
# Forward Simulation Parameters
sim_time: 2.0
sim_granularity: 0.02
angular_sim_granularity: 0.02
vx_samples: 6
vtheta_samples: 20
controller_frequency: 20.0
# Trajectory scoring parameters
meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of metres or cells. Cells are assumed by default (false).
occdist_scale: 0.1 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01
pdist_scale: 0.75 # The weighting for how much the controller should stay close to the path it was given . default 0.6
gdist_scale: 1.0 # The weighting for how much the controller should attempt to reach its local goal, also controls speed default 0.8
heading_lookahead: 0.325 #How far to look ahead in metres when scoring different in-place-rotation trajectories
heading_scoring: false #Whether to score based on the robot's heading to the path or its distance from the path. default false
heading_scoring_timestep: 0.8 #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)
dwa: false #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout
simple_attractor: false
publish_cost_grid_pc: true
#Oscillation Prevention Parameters
oscillation_reset_dist: 0.05 #How far the robot must travel in metres before oscillation flags are reset (double, default: 0.05)
escape_reset_dist: 0.1
escape_reset_theta: 0.1
Note some parameters like:
-
holonomic_robot
: Jackal is non holonomic -
yaw_goal_tolerance
andxy_goal_tolerance
are relatively low
move_base_params.yaml
shutdown_costmaps: false
controller_frequency: 20.0
controller_patience: 15.0
planner_frequency: 20.0
planner_patience: 5.0
oscillation_timeout: 0.0
oscillation_distance: 0.5
recovery_behavior_enabled: true
clearing_rotation_allowed: true
Here the clearing_rotation_allowed
which means that it will turn around to clear space if for some reason it gets lost to try and recover itself. It's also useful for situations when a moving obstacle was detected in its path. By turning it gives time to the obstacle to move out the way and therefore clear the localcostmap.
For localPlanner
the TrajectoryPlannerROS
is used.
For globalPlanner
the navfn/NavfnROS
is used.
-
Inside
my_jackal_tools
package, create the files given below:- Inside
my_jackal_tools/launch
odom_navigation.launch
- Inside
my_jackal_tools/params
costmap_common_params.yaml
global_costmap_params.yaml
base_local_planner_params.yaml
local_costmap_params.yaml
move_base_params.yaml
- Inside
-
Launch odom_navigation.launch Execute in a terminal:
roslaunch my_jackal_tools odom_navigation.launch
-
Launch RVIZ for visualisation: Execute in a terminal:
roslaunch jackal_viz view_robot.launch config:=navigation
You should get the same result as in the Introduction. Use “2D Nav Goal” to give a goal position to the robot.
Now before we learn how to navigate with a map, we first have to generate that map:
To create a Map you need to launch two elements: GMapping and MoveBase.
- GMapping: in the one in charge of generating and saving the map. More info here.
- MoveBase: The one in charge of sending the commands to /cmd_vel to move the robot.
You can create a launch file that launches both:
start_mapping.launch
<launch>
<!--- Run gmapping -->
<include file="$(find my_jackal_tools)/launch/gmapping.launch" />
<!--- Run Move Base -->
<include file="$(find my_jackal_tools)/launch/with_map_move_base.launch" />
</launch>
Now we can create gmapping.launch
. It should be something similar to this:
gmapping.launch
<launch>
<arg name="scan_topic" default="front/scan" />
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<param name="odom_frame" value="odom"/>
<param name="base_frame" value="base_link"/>
<param name="map_frame" value="map"/>
<!-- Process 1 out of every this many scans (set it to a higher number to skip more scans) -->
<param name="throttle_scans" value="1"/>
<param name="map_update_interval" value="5.0"/> <!-- default: 5.0 -->
<!-- The maximum usable range of the laser. A beam is cropped to this value. -->
<param name="maxUrange" value="5.0"/>
<!-- The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free space in the map, set maxUrange < maximum range of the real sensor <= maxRange -->
<param name="maxRange" value="10.0"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="minimumScore" value="0.0"/>
<!-- Number of beams to skip in each scan. -->
<param name="lskip" value="0"/>
<param name="srr" value="0.01"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.01"/>
<param name="stt" value="0.02"/>
<!-- Process a scan each time the robot translates this far -->
<param name="linearUpdate" value="0.1"/>
<!-- Process a scan each time the robot rotates this far -->
<param name="angularUpdate" value="0.05"/>
<param name="temporalUpdate" value="-1.0"/>
<param name="resampleThreshold" value="0.5"/>
<!-- Number of particles in the filter. default 30 -->
<param name="particles" value="10"/>
<!-- Initial map size -->
<param name="xmin" value="-10.0"/>
<param name="ymin" value="-10.0"/>
<param name="xmax" value="10.0"/>
<param name="ymax" value="10.0"/>
<!-- Processing parameters (resolution of the map) -->
<param name="delta" value="0.02"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
</launch>
Here are basically all the parameters related to the map generation defined. Note the maxUrange = 5.0 metres and maxRange = 10 metres. As you see here the laser is also cut off to improve performance.
with_map_move_base.launch
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find my_jackal_tools)/params/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find my_jackal_tools)/params/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find my_jackal_tools)/params/local_costmap_map_params.yaml" command="load" />
<rosparam file="$(find my_jackal_tools)/params/global_costmap_map_params.yaml" command="load" />
<rosparam file="$(find my_jackal_tools)/params/base_local_planner_params.yaml" command="load" />
<rosparam file="$(find my_jackal_tools)/params/move_base_params.yaml" command="load" />
<param name="base_global_planner" type="string" value="navfn/NavfnROS" />
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS"/>
<remap from="odom" to="odometry/filtered" />
</node>
</launch>
local_costmap_map_params.yaml
local_costmap:
global_frame: map
robot_base_frame: base_link
update_frequency: 20.0
publish_frequency: 5.0
width: 10.0
height: 10.0
resolution: 0.05
static_map: false
rolling_window: true
global_costmap_map_params.yaml
global_costmap:
global_frame: map
robot_base_frame: base_link
update_frequency: 20.0
publish_frequency: 5.0
width: 40.0
height: 40.0
resolution: 0.05
origin_x: -20.0
origin_y: -20.0
static_map: true
rolling_window: false
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacles_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflater_layer, type: "costmap_2d::InflationLayer"}
-
Inside
my_jackal_tools
package, create the files given above:- Inside
my_jackal_tools/launch
start_mapping.launch
gmapping.launch
with_map_move_base.launch
- Inside
-
Inside
my_jackal_tools/params
local_costmap_map_params.yaml
global_costmap_map_params.yaml
-
Launch start_mapping.launch Execute in a terminal:
roslaunch my_jackal_tools start_mapping.launch
-
Launch RVIZ for visualisation: Execute in a terminal:
roslaunch jackal_viz view_robot.launch config:=gmapping
You should get something similar to this if everything is ok:
You see that instantly it started to generate the map. Now it's time to move Jackal around.
You can move it through the start_teleop.launch
used in the Introduction, or through poses in the map (using 2D Nav Goal) as shown above in the GIF.
This works because you are navigating in the same way as you were in the No Map navigation. So you can use 2D Poses to generate the map. Just Be Careful not to give very far away poses, because remember you don't have a map and the path planning is not as good.
Once you have all the map as you would like, then you have to save it to be able to use it for navigation. For this you have to execute the following command:
Execute in a terminal:
roscd my_jackal_tools
cd maps
rosrun map_server map_saver -f mymap
This should have generated two files: mymap.pgm
and mymap.yaml
.
You will use the pgm image for cleaning the map generated, and the yaml is the file directly used by the PathPLanning afterwards.
- Close RVIZ
- Stop
start_mapping.launch
with Ctrl+c in the terminal where the launch is running.
Now, you are able to localise the robot within the map.We will use package amcl and the map created before to to localise the Jackal.
Create the following launch:
start_navigation_with_map.launch
<launch>
<!-- Run the map server -->
<arg name="map_file" default="$(find jackal_tools)/maps/mymap.yaml"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />
<!--- Run AMCL -->
<include file="$(find jackal_tools)/launch/amcl.launch" />
<!--- Run Move Base -->
<include file="$(find jackal_tools)/launch/with_map_move_base.launch" />
</launch>
Here we have three main parts:
-
map_server
: The Node that publishes the map saved. -
amcl
: The node that localises Jackal based on map readings -
move_base
: This move base has the configuration of moving with a map.
amcl.launch
<launch>
<arg name="use_map_topic" default="false"/>
<arg name="scan_topic" default="front/scan" />
<node pkg="amcl" type="amcl" name="amcl">
<param name="use_map_topic" value="$(arg use_map_topic)"/>
<!-- Publish scans from best pose at a max of 10 Hz -->
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha5" value="0.1"/>
<param name="gui_publish_rate" value="10.0"/>
<param name="laser_max_beams" value="720"/>
<param name="laser_min_range" value="0.1"/>
<param name="laser_max_range" value="30.0"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="2000"/>
<!-- Maximum error between the true distribution and the estimated distribution. -->
<param name="kld_err" value="0.05"/>
<param name="kld_z" value="0.99"/>
<param name="odom_alpha1" value="0.2"/>
<param name="odom_alpha2" value="0.2"/>
<!-- translation std dev, m -->
<param name="odom_alpha3" value="0.2"/>
<param name="odom_alpha4" value="0.2"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.5"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_model_type" value="likelihood_field"/>
<!-- Maximum distance to do obstacle inflation on map, for use in likelihood_field model. -->
<param name="laser_likelihood_max_dist" value="2.0"/>
<!-- Translational movement required before performing a filter update. -->
<param name="update_min_d" value="0.1"/>
<!--Rotational movement required before performing a filter update. -->
<param name="update_min_a" value="0.314"/>
<param name="odom_frame_id" value="odom"/>
<param name="base_frame_id" value="base_link"/>
<param name="global_frame_id" value="map"/>
<!-- Number of filter updates required before resampling. -->
<param name="resample_interval" value="1"/>
<!-- Increase tolerance because the computer can get quite busy -->
<param name="transform_tolerance" value="1.0"/>
<!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.001. -->
<param name="recovery_alpha_slow" value="0.0"/>
<!--Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.1. -->
<param name="recovery_alpha_fast" value="0.1"/>
<!-- Initial pose mean -->
<param name="initial_pose_x" value="0.0" />
<param name="initial_pose_y" value="0.0" />
<param name="initial_pose_a" value="0.0" />
<!-- When set to true, AMCL will subscribe to the map topic rather than making a service call to receive its map.-->
<param name="receive_map_topic" value="true"/>
<!-- When set to true, AMCL will only use the first map it subscribes to, rather than updating each time a new one is received. -->
<param name="first_map_only" value="false"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
</launch>
-
Inside
my_jackal_tools
package, create the files given above:- Inside
my_jackal_tools/launch
start_navigation_with_map.launch
amcl.launch
- Inside
-
Launch start_navigation_with_map.launch Execute in a terminal:
roslaunch my_jackal_tools start_navigation_with_map.launch
-
Launch RVIZ for visualisation: Execute in a terminal:
roslaunch jackal_viz view_robot.launch config:=localization
-
Send a goal to the robot using 2D Nav Goal icon
Note: When launching, the initial localisation of the robot can be wrong (check the GIF below)
This is because the Jackal doesn't know where it is initially, so you have to indicate the position and orientation with the 2D Estimate Pose icon. Once done, it should navigate without problems. It will localise itself after a few seconds of movement. You know it is well localised because all the arrows (PoseArray)are concentrated into the position of the robot.
Sending Goals to the Navigation Stack with Python ROS
Here below, you will find an example Python code for sending a goal pose (desired position and orientation) to a robot (Jackal), exploiting the ROS Navigation Stack. In order for an autonomous mobile robot to reach a goal location, it must gather and integrate various information sources. This includes having a map of its environment, perceiving its surroundings, localising itself, and planning its movements. The ROS Navigation Stack is responsible for guiding the mobile base towards the goal pose, avoiding obstacles, and combining all available information.
Using code, we can send a desired pose to the navigation stack for the robot to reach. The code example below has been written following the “Sending Goals to the Navigation Stack” C++ node tutorial.
my_send_goal.py
#!/usr/bin/env python
import rospy
# Brings in the SimpleActionClient
import actionlib
# Brings in the .action file and messages used by the move base action
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
def movebase_client():
# Create an action client called "move_base" with action definition file "MoveBaseAction"
client = actionlib.SimpleActionClient('move_base',MoveBaseAction)
# Waits until the action server has started up and started listening for goals.
client.wait_for_server()
# Creates a new goal with the MoveBaseGoal constructor
goal = MoveBaseGoal()
goal.target_pose.header.frame_id = "map"
goal.target_pose.header.stamp = rospy.Time.now()
# goal position <x,y,z> axis of the "map" coordinate frame
goal.target_pose.pose.position.x = -4.5
goal.target_pose.pose.position.y = -1.5
goal.target_pose.pose.position.z = 0.0
# Rotation of the mobile base frame w.r.t. map frame expresed in quaternion <x, y, z, w>
goal.target_pose.pose.orientation.x = 0.0
goal.target_pose.pose.orientation.y = 0.0
goal.target_pose.pose.orientation.z = 1.0
goal.target_pose.pose.orientation.w = 0.0
# Sends the goal to the action server.
client.send_goal(goal)
# Waits for the server to finish performing the action.
wait = client.wait_for_result()
# If the result doesn't arrive, assume the Server is not available
if not wait:
rospy.logerr("Action server not available!")
rospy.signal_shutdown("Action server not available!")
else:
# Result of executing the action
return client.get_result()
# If the python node is executed as main process (sourced directly)
if __name__ == '__main__':
try:
# Initializes a rospy node to let the SimpleActionClient publish and subscribe
rospy.init_node('movebase_client_py')
result = movebase_client()
if result:
rospy.loginfo("Goal execution done!")
except rospy.ROSInterruptException:
rospy.loginfo("Navigation test finished.")
-
Inside
my_jackal_tools
package, create the file give above:- Inside
my_jackal_tools/scripts
my_send_goal.py
- Inside
-
Launch start_navigation_with_map.launch Execute in a terminal:
roslaunch my_jackal_tools start_navigation_with_map.launch
-
Launch RVIZ for visualisation: Execute in a terminal:
roslaunch jackal_viz view_robot.launch config:=localization
-
Make your node executable: Execute in a terminal:
chmod u+x ~/work_experience_ws/src/work_experience/my_jackal_tools/scripts/my_send_goal.py
-
Run the program: In a terminal, run:
rosrun my_jackal_tools my_send_goal.py
Here are some things you can try:
- Familiarise yourself with the code.
- Run the program and observe how it executes. Play with it.
- Collaborate with others to gather feedback and brainstorm ideas.
- Once you're comfortable with the basic functionality, consider modifying the code to send multiple pose goals. You may need to introduce data structures or adjust existing variables and functions.
- Make the necessary changes to the code and save the file.
- Recompile or restart the program to apply the modifications.
- Evaluate the behaviour and determine if any further adjustments or improvements are needed.
- Continue experimenting with different modifications to explore the code capabilities fully.
- Document any changes you make and keep track of the modifications for future reference.
- Have fun exploring and pushing the boundaries of what the code can do!