Rosbot Pro

Gazebo + Docker

Real World

Configuration

costmap_common.yaml
# Reff: http://wiki.ros.org/costmap_2d
global_frame: map
robot_base_frame: base_link
footprint: [[0.14, 0.14], [0.14, -0.14], [-0.14, -0.14], [-0.14, 0.14]]
rolling_window: true

inflation_radius: 0.5
cost_scaling_factor: 4.0

track_unknown_space: true
observation_sources: scan
scan: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
costmap_global.yaml
# Reff: http://wiki.ros.org/costmap_2d
global_costmap:
    update_frequency: 2.0
    publish_frequency: 1.0

    obstacle_range: 5.0
    raytrace_range: 5.0
    static_map: true

    width: 15.0
    height: 15.0
costmap_local.yaml
# Reff: http://wiki.ros.org/costmap_2d
local_costmap:
    update_frequency: 5.0
    publish_frequency: 2.0

    obstacle_range: 2.5
    raytrace_range: 2.5
    static_map: false

    width: 2.5
    height: 2.5
    resolution: 0.02
planner_local.yaml
# Reff: http://wiki.ros.org/base_local_planner
base_local_planner: base_local_planner/TrajectoryPlannerROS

TrajectoryPlannerROS:
    min_vel_x: 0.1
    max_vel_x: 0.3
    min_vel_theta: -0.7
    max_vel_theta: 0.7
    min_in_place_vel_theta: 0.4
    escape_vel: -0.1

    acc_lim_theta: 1.0
    acc_lim_x: 1.0

    holonomic_robot: false

    xy_goal_tolerance: 0.1
    yaw_goal_tolerance: 0.2

    meter_scoring: true
    path_distance_bias: 20
    goal_distance_bias: 15
    occdist_scale:  0.01

    sim_time: 2.0
    

  • TrajectoryPlannerROS - namespace depends on the type of planner.

  • min_vel_x - defines minimum linear velocity that will be set by trajectory planner. This should be adjusted to overcome rolling resistance and other forces that may suppress robot from moving.

  • max_vel_x - defines maximum linear velocity that will be set by trajectory planner.

  • max_vel_theta & min_vel_theta - defines maximum and minimum angular velocity that will be set by trajectory planner.

  • min_in_place_vel_theta - defines minimum angular velocity that will be set by trajectory planner. This should be adjusted to overcome rolling resistance and other forces that may suppress robot from moving.

  • acc_lim_theta & acc_lim_x - parameters define maximum values of accelerations used by trajectory planner.

  • holonomic_robot - defines if robot is holonomic.

  • meter_scoring - defines if cost function arguments are expressed in map cells or meters (if true, meters are considered).

  • xy_goal_tolerance & yaw_goal_tolerance - parameters define how far from destination it can be considered as reached. Linear tolerance is in meters, angular tolerance is in radians.

  • path_distance_bias, goal_distance_bias & occdist_scale - a group of parameters defines how much the aspect related to keeping to the path, following to the local minimum and avoiding objects should affect the selection of the trajectory.

  • sim_time - the amount of time to forward-simulate trajectories in seconds

move_base.yaml
# Reff: http://wiki.ros.org/move_base
recovery_behavior_enabled: true

controller_frequency: 10.0
controller_patience: 10.0
planner_frequency: 5.0
planner_patience: 5.0

conservative_reset_dist: 6.0
oscillation_timeout: 10.0
oscillation_distance: 0.15
  • recovery_behavior_enabled - enable or disable the move_base recovery behaviors to attempt to clear out space.

  • controller_frequency - defines the rate in Hz at which to run the control loop and send velocity commands to the base.

  • controller_patience - defines how long the controller will wait in seconds without receiving a valid control before space-clearing operations are performed.

  • planner_frequency - defines the rate in Hz at which to run the global planning loop.

  • planner_patience - how long the planner will wait in seconds in an attempt to find a valid plan before space-clearing operations are performed.

  • conservative_reset_dist - defines the distance away from the robot in meters beyond which obstacles will be cleared from the costmap when attempting to clear space in the map.

  • oscillation_timeout - defines how long in seconds to allow for oscillation before executing recovery behaviors.

  • oscillation_distance - defines how far in meters the robot must move to be considered not to be oscillating. Moving this far resets the timer.

Multiple Waypoint

Node
#!/usr/bin/env python
# license removed for brevity
__author__ = 'fiorellasibona'
import rospy
import math

import actionlib
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from actionlib_msgs.msg import GoalStatus
from geometry_msgs.msg import Pose, Point, Quaternion
from tf.transformations import quaternion_from_euler


class MoveBaseSeq():

    def __init__(self):

        rospy.init_node('move_base_sequence')
        points_seq = rospy.get_param('move_base_seq/p_seq')
        # Only yaw angle required (no ratotions around x and y axes) in deg:
        yaweulerangles_seq = rospy.get_param('move_base_seq/yea_seq')
        #List of goal quaternions:
        quat_seq = list()
        #List of goal poses:
        self.pose_seq = list()
        self.goal_cnt = 0
        for yawangle in yaweulerangles_seq:
            #Unpacking the quaternion list and passing it as arguments to Quaternion message constructor
            quat_seq.append(Quaternion(*(quaternion_from_euler(0, 0, yawangle*math.pi/180, axes='sxyz'))))
        n = 3
        # Returns a list of lists [[point1], [point2],...[pointn]]
        points = [points_seq[i:i+n] for i in range(0, len(points_seq), n)]
        for point in points:
            #Exploit n variable to cycle in quat_seq
            self.pose_seq.append(Pose(Point(*point),quat_seq[n-3]))
            n += 1
        #Create action client
        self.client = actionlib.SimpleActionClient('move_base',MoveBaseAction)
        rospy.loginfo("Waiting for move_base action server...")
        wait = self.client.wait_for_server(rospy.Duration(5.0))
        if not wait:
            rospy.logerr("Action server not available!")
            rospy.signal_shutdown("Action server not available!")
            return
        rospy.loginfo("Connected to move base server")
        rospy.loginfo("Starting goals achievements ...")
        self.movebase_client()

    def active_cb(self):
        rospy.loginfo("Goal pose "+str(self.goal_cnt+1)+" is now being processed by the Action Server...")

    def feedback_cb(self, feedback):
        #To print current pose at each feedback:
        #rospy.loginfo("Feedback for goal "+str(self.goal_cnt)+": "+str(feedback))
        rospy.loginfo("Feedback for goal pose "+str(self.goal_cnt+1)+" received")

    def done_cb(self, status, result):
        self.goal_cnt += 1
    # Reference for terminal status values: http://docs.ros.org/diamondback/api/actionlib_msgs/html/msg/GoalStatus.html
        if status == 2:
            rospy.loginfo("Goal pose "+str(self.goal_cnt)+" received a cancel request after it started executing, completed execution!")

        if status == 3:
            rospy.loginfo("Goal pose "+str(self.goal_cnt)+" reached") 
            if self.goal_cnt< len(self.pose_seq):
                next_goal = MoveBaseGoal()
                next_goal.target_pose.header.frame_id = "map"
                next_goal.target_pose.header.stamp = rospy.Time.now()
                next_goal.target_pose.pose = self.pose_seq[self.goal_cnt]
                rospy.loginfo("Sending goal pose "+str(self.goal_cnt+1)+" to Action Server")
                rospy.loginfo(str(self.pose_seq[self.goal_cnt]))
                self.client.send_goal(next_goal, self.done_cb, self.active_cb, self.feedback_cb) 
            else:
                rospy.loginfo("Final goal pose reached!")
                rospy.signal_shutdown("Final goal pose reached!")
                return

        if status == 4:
            rospy.loginfo("Goal pose "+str(self.goal_cnt)+" was aborted by the Action Server")
            rospy.signal_shutdown("Goal pose "+str(self.goal_cnt)+" aborted, shutting down!")
            return

        if status == 5:
            rospy.loginfo("Goal pose "+str(self.goal_cnt)+" has been rejected by the Action Server")
            rospy.signal_shutdown("Goal pose "+str(self.goal_cnt)+" rejected, shutting down!")
            return

        if status == 8:
            rospy.loginfo("Goal pose "+str(self.goal_cnt)+" received a cancel request before it started executing, successfully cancelled!")

    def movebase_client(self):
        goal = MoveBaseGoal()
        goal.target_pose.header.frame_id = "map"
        goal.target_pose.header.stamp = rospy.Time.now() 
        goal.target_pose.pose = self.pose_seq[self.goal_cnt]
        rospy.loginfo("Sending goal pose "+str(self.goal_cnt+1)+" to Action Server")
        rospy.loginfo(str(self.pose_seq[self.goal_cnt]))
        self.client.send_goal(goal, self.done_cb, self.active_cb, self.feedback_cb)
        rospy.spin()

if __name__ == '__main__':
    try:
        MoveBaseSeq()
    except rospy.ROSInterruptException:
        rospy.loginfo("Navigation finished.")

Dockerfile

Dockerfile
ARG ROS_DISTRO=noetic

FROM osrf/ros:$ROS_DISTRO-desktop-full

SHELL ["/bin/bash", "-c"]

# nvidia-container-runtime
ENV NVIDIA_VISIBLE_DEVICES \
    ${NVIDIA_VISIBLE_DEVICES:-all}
ENV NVIDIA_DRIVER_CAPABILITIES \
    ${NVIDIA_DRIVER_CAPABILITIES:+$NVIDIA_DRIVER_CAPABILITIES,}graphics


RUN sudo apt update && apt install python3-rosdep git-all -y



WORKDIR /ros_ws

COPY . src/cris_navigation

# clone robot github repositories
RUN git clone https://github.com/husarion/rosbot_ros.git --branch=noetic src/rosbot_ros && \
    git clone https://github.com/husarion/rosbot_ekf.git --branch=master src/rosbot_ekf && \
    git clone https://github.com/aws-robotics/aws-robomaker-small-house-world.git --branch=ros1 src/aws-robomaker-small-house-world && \
    rosdep update && \
    rosdep install --from-paths src --ignore-src -r -y


# build ROS workspace
RUN source /opt/ros/$ROS_DISTRO/setup.bash && \
	catkin_make -DCATKIN_ENABLE_TESTING=0 -DCMAKE_BUILD_TYPE=Release


RUN apt update && apt install -y \
		python3-pip \
		ros-$ROS_DISTRO-rosserial-python \ 
		ros-$ROS_DISTRO-rosserial-server \
		ros-$ROS_DISTRO-rosserial-client \
		ros-$ROS_DISTRO-rosserial-msgs \
		ros-$ROS_DISTRO-move-base-msgs \
		ros-$ROS_DISTRO-robot-localization \
		ros-$ROS_DISTRO-xacro \
		ros-$ROS_DISTRO-transmission-interface \
		ros-$ROS_DISTRO-controller-manager \
		ros-$ROS_DISTRO-robot-state-publisher && \
	pip3 install python-periphery && \
	pip3 install sh && \
	pip3 install pyserial && \
	python3 -m pip install --upgrade pyserial


RUN echo ". /opt/ros/$ROS_DISTRO/setup.bash" >> ~/.bashrc && \
	echo ". /ros_ws/devel/setup.bash" >> ~/.bashrc && \
	# allows us to run: docker exec -it rosbot bash --login -c "rostopic list"
	echo ". /opt/ros/$ROS_DISTRO/setup.bash" >> ~/.profile && \
	echo ". /ros_ws/devel/setup.bash" >> ~/.profile

WORKDIR /

ENTRYPOINT ["/ros_entrypoint.sh"]
CMD ["bash"]

Github

Last updated