note: Package for ROS 2 - C++/Python (CMake) based package
The move_base_package is a comprehensive package designed to control various aspects of the robot's behavior. Here's an overview of its key functionalities:
-
LED Strip Control: The package efficiently manages the LED strip on the robot, dynamically adjusting its state based on the current state of the robot.
-
Odometry Calculation: Utilizing encoder and IMU (Inertial Measurement Unit) data, the package accurately calculates odometry, providing essential information about the robot's position and orientation.
-
Joystick Commands: The package seamlessly integrates with joystick commands, offering both manual and autonomous control modes. Users can command the robot through the joystick, including emergency stop functionality and velocity control.
-
Safety Determination: A critical feature of the move_base_package is its capability to assess the safety of robot movements. It considers both joystick commands, such as emergency stop signals, and ultrasonic readings to determine whether it is secure to initiate robot movements.
1. Clone the repository into your ROS2 workspace:
cd ros2_ws/src
git clone https://github.com/AMR-Frederico/fred2_move_base.git
2. Build the package:
cd ros2_ws
colcon build
3. Install the transforms3d
library:
pip install transforms3d
ros2 launch fred2_move_base move_base.launch.py
-
Use the
left analog
stick for linear velocity control. -
Use the
right analog
stick for angular velocity control. -
Press the
circle button
to reset odometry. -
Press the
triangle button
to switch between different modes. -
Press the
X button
to stop and block/release the robot
Determinate the LED strip's color basead on the robot state. Responsable for the waypoint sinalization.
Type: python
Name: led_manager
Namespace: move_base
Publishers:
-
/cmd/led_strip/color
(std_msgs/Int16): Colors that indicates the main state of the robot -
/cmd/led_strip/debug/color
(std_msgs/Int16): Color for debug the robot status, like joy connectivity or alert of colision detection.
Subscribers:
-
safety/abort/colision_detection
(std_msgs/Bool): ReturnsTrue
if a obstacle is detected, otherwise isFalse
-
safety/abort/user_command
(std_msgs/Bool): ReturnsTrue
if the user pressedX
, stopping the robot, andFalse
if the user pressX
again to release the robot -
safety/ultrasonic/disabled
(std_msgs/Bool): PublishTrue
if the ultrasonics were desabled, otherwise isFalse
-
joy/controller/connected
(std_msgs/Bool): Joy status connectivity. -
machine_states/robot_state
(std_msgs/Int16): Robot state from the main machine states -
goal_manager/goal/current
(geometry_msgs/PoseStamped): Robot current goal -
/odom/reset
(std_msgs/Bool): Reset odometry and tobot state
-
WHITE
: Index to indicate white color on the LED strip -
BLUE
: Index to indicate blue color on the LED strip -
YELLOW
: Index to indicate yellow color on the LED strip -
PINK
: Index to indicate pink color on the LED strip -
GREEN
: Index to indicate green color on the LED strip -
ORANGE
: Index to indicate orange color on the LED strip -
RED
: Index to indicate red color on the LED strip -
CYAN
: Index to indicate cyan color on the LED strip -
PURPLE
: Index to indicate purple color on the LED strip -
LIGHT GREEN
: Index to indicate light green color on the LED strip -
BLACK
: Index to turn off the LED strip -
WAYPOINT_GOAL
: Index to indicate goals points that the robot must signal -
GHOST_GOAL
: Index to indicate ghost goals -
DEBUG
: Enables the debug prints. -
UNIT_TEST
: Allows the node to run isolated .
ros2 param list
ros2 param describe /move_base/led_manager <parameter name>
ros2 param get /move_base/led_manager <parameter name>
ros2 param load /move_base/led_manager <path-to-parameter-config-file>
Default:
ros2 run fred2_move_base led_manager.py --ros-args --params-file <path-to-parameter-config-file>
Enable debug:
ros2 run fred2_move_base led_manager.py --ros-args --params-file <path-to-parameter-config-file> --debug
The node is responsible for managing the velocity commands of a robot based on safety constraints, including ultrasonic sensor readings and user commands.
Type: python
Name: safe_twist
Namespace: move_base
Publishers:
-
/cmd_vel/safe
(geometry_msgs/Twist): Safe velocity command for the robot -
safety/abort/user_command
(std_msgs/Bool): Topic for debug, to inform a user request command to stop the robot -
safety/abort/colision_alert
(std_msgs/Bool): Topic for debug, to inform when there is a collision alert -
safety/ultrasonic/disabled
(std_msgs/Bool): Topic for debug, to inform when the ultrsonics are disable -
robot_safety
(std_msgs/Bool): Robot safety status, returnsTrue
when the robot is safe, andFalse
when the robot is blocked bysafe twist node
Subscribers:
-
/sensor/range/ultrasonic/right
(std_msgs/Float32): Ultrasonic right data -
/sensor/range/ultrasonic/left
(std_msgs/Float32`): Ultrasonic left data -
/sensor/range/ultrasonic/back
(std_msgs/Float32): Ultrsonic back data -
/odometry/filtered
(nav_msgs/Odometry): Odometry fromRobot Localization
-
/odom
(nav_msgs/Odometry): Odometry fromMove Base
-
/cmd_vel
(geometry_msgs/Twist): Velocity commands from other nodes -
/joy/controler/ps4/break
(std_msgs/Bool): User stop command by the joystick
-
SAFE_DISTANCE
: Minimum safe distance (in cm) that the robot can be from an object -
MOTOR_BRAKE_FACTOR
: Brake factor for stop the robot as quickly as possible -
MAX_LINEAR_SPEED
: Maximum linear speed of the robot -
MAX_ANGULAR_SPEED
: Maximum angular of the robot -
DISABLE_ULTRASONICS
: Parameter for disable the ultrasonics reading, therefore, disable detection alert -
DEBUG
: Enables the debug prints.
ros2 param list
ros2 param describe /move_base/safe_twist <parameter name>
ros2 param get /move_base/safe_twist <parameter name>
ros2 param load /move_base/safe_twist <path-to-parameter-config-file>
Default:
ros2 run fred2_move_base safe_twist.py --ros-args --params-file <path-to-parameter-config-file>
Enable debug:
ros2 run fred2_move_base safe_twist.py --ros-args --params-file <path-to-parameter-config-file> --debug
The Joy Interface is a node that interfaces with a joystick (e.g., PS4 controller) to control a mobile robot. It receives the joystick commands, sent by a microcontroller and translates it into velocity commands for the robot, allowing for manual control and additional functionalities.
Type: python
Name: joy_esp_interface
Namespace: move_base
Publishers:
-
/cmd_vel
(geometry_msgs/Twist): Velocity command -
/odom/reset
(std_msgs/Bool): Command for reset the odometry and reset the robot state -
/joy/machine_states/switch_mode
(std_msgs/Bool): Switch betweenMANUAL
andAUTONOMOUS
mode. -
/goal_manager/goal/mission_completed
(std_msgs/Bool): Publish false when received a command for reset the odometry
Subscribers:
-
/joy/controler/ps4/cmd_vel/linear
(std_msgs/Int16): Linear velocity from the analog joy control -
/joy/controler/ps4/cmd_vel/angular
(std_msgs/Int16): Angular velocity from the analog joy control -
/joy/controler/ps4/circle
(std_msgs/Int16): Get the circle button command -
/joy/controler/ps4/triangle
(std_msgs/Int16): Get the triangle button command -
/machine_state/robot_state
(std_msgs/Bool): Get the robot state
-
MAX_SPEED_JOY_LINEAR
: Maximum linear speed of the robot. -
MAX_SPEED_JOY_ANGULAR
: Maximum angular speed of the robot. -
MAX_VALUE_CONTROLLERr
: Maximum value of analog joystick input. -
DRIFT_ANALOG_TOLERANCE
: Minimum threshold for joystick input to be considered. -
DEBUG
: Enables the debug prints. -
UNIT_TEST
: Allows the node to run isolated .
ros2 param list
ros2 param describe /move_base/joy_esp_interface <parameter name>
ros2 param get /move_base/joy_esp_interface <parameter name>
ros2 param load /move_base/joy_esp_interface <path-to-parameter-config-file>
Default:
ros2 run fred2_move_base joy_esp_interface.py --ros-args --params-file <path-to-parameter-config-file>
Enable debug:
ros2 run fred2_move_base joy_esp_interface.py --ros-args --params-file <path-to-parameter-config-file> --debug
The Odometry Node is responsible for calculating and publishing odometry information for a mobile robot using wheel encoder ticks and IMU data, with automatic reset of odometry when requested.
Type: python
Name: odometry
Namespace: move_base
Publishers:
/power/status/distance/ticks/right
(std_msgs/Int32): Ticks data from the right encoders/power/status/distance/ticks/left
(std_msgs/Int32): Ticks data from left encoders/sensor/orientation/imu
(sensor_msgs/Imu): Imu raw data/odom/reset
(std_msgs/Bool): Command for reset the odometry
Subscribers:
/odom
(nav_msgs/Odometry): Odometry (without kalman filter)
WHEELS_TRACK
: Distance (in m) between wheelsWHEELS_RADIUS
: Radius of the wheel in meters.TICKS_PER_REVOLUTION
: Ticks per turn for the wheel encoder.BASE_LINK_OFFSET
: Distance (in meters) between thebase_footprint
andbase_link
DEBUG
: Enables the debug prints.
ros2 param list
ros2 param describe /move_base/odometry <parameter name>
ros2 param get /move_base/odometry <parameter name>
ros2 param load /move_base/odometry <path-to-parameter-config-file>
Default:
ros2 run fred2_move_base ticks2odom.py --ros-args --params-file <path-to-parameter-config-file>
Enable debug:
ros2 run fred2_move_base ticks2odom.py --ros-args --params-file <path-to-parameter-config-file> --debug