Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Loading...
Installing Seirios RNS onto your robot PC is easy! Follow these step-by-step guides to ensure seamless integration and deployment of Seirios RNS.
If you need help or have any inquiries along the way, reach out to us at sales@movel.ai or live chat at movel.ai/contact
If you're an existing client, please refer to this form to submit URLs to your required pre-installation videos and images
Seirios is designed to work with robots of all shapes and sizes.
However, checking that the robot is working correctly before software installation is crucial to preventing compounding errors.
Robot Checks:
Ensure odometry is working well
Align the bot appropriately to test 3-4 meters of linear, straight distance without an angular component. Test using the following command in Terminal: rostopic pub /cmd_vel geometry_msgs/Twist "linear: x: 0.0 y: 0.0 z: 0.0 angular: x: 0.0 y: 0.0 z: 0.0"
Restart motor
Check odom pose is zero.
Publish only linear vel x: 0.1 and stop the bot at the 3-4 m mark.
Echo the odom topic: rostopic echo /odom
.
Compare the pose of the updated odom with linear and angular bot travelled (offset 1-2%).
Align the bot properly. Mark the spot where the bot will begin rotating.
Restart the motors.
Rotate the bot clockwise. Quaternion should be updated to negative.
Restart the motor and rotate the bot anticlockwise. Quaternion should be updated to positive.
Restart the motor. Rotate and stop the bot at the original marked spot.
Make sure that the angular pose is a 0 rad change.
Validating Odometry Data
We provide you with a script that enables you to verify the odometry data by inputting the velocity and duration. The robot will then move at the specified velocity for the given duration. Subsequently, the script will calculate and provide the distance traveled by the robot based on these inputs.
This will facilitate the verification of your odometry data, making it easier and more efficient for you.
You can download the script here.
For seamless integration with Seirios RNS, it is important to set up some key robotics software and drivers in your robot system. The following is a checklist of things that Seirios RNS requires your robot system to have before Seirios is installed:
TF for base_link to scan:
Ensure that there is a direct tf link between the base_link
frame and the laser
frame as it is required by Seirios RNS
Ensure robot is moving linearly at the right speed
A minimum speed of 0.1 - 0.5 m/s needs to be tested. Also, manually check if the robot covers the distance correctly. A video recording is encouraged to troubleshoot any issues that may arise.
Open a new terminal window. Execute this command: rostopic pub /cmd_vel geometry_msgs/Twist "linear: x: 0.0 y: 0.0 z: 0.0 angular: x: 0.0 y: 0.0 z: 0.0"
Change the linear: x:
to 0.1-0.5 as we only want to move the robot straightly forward. Leave all the other values to 0.0.
Measure the distance the robot moved. And record the time between when the robot started to move and when the robot stopped. Calculate speed by dividing the distance over time.
Check whether your calculated speed matches up to the value that you have given for linear x.
If not, please recalibrate your wheels.
Alternatively, you may use rosrun telelop_twist_keyboard teleop_twist_keyboard.py
. Similarly, give it a linear speed between 0.1-0.5. Then repeat Steps 3 - 5 above.
Note:
If your robot is non-holonomic, it shouldn't be able to slide sideways. y should be 0.0.
If your robot is not flight-capable, z should be 0.0.
Validating Odometry Data
We provide you with a script that enables you to verify the odometry data by inputting the velocity and duration. The robot will then move at the specified velocity for the given duration. Subsequently, the script will calculate and provide the distance traveled by the robot based on these inputs.
This will facilitate the verification of your odometry data, making it easier and more efficient for you.
You can download the script here.
Ensure no wheel slippage occurs and that robot is able to teleoperate in a straight line
Move the robot straight, and echo the /odom
topic.
Align the wheels accordingly to test straight linear movement. It’s recommended to draw lines on the floor for accuracy.
Give only linear speed. Check the robot is travelling straight. A slight deviation is acceptable (1 - 2 degrees), but no more than 5 degrees.
Technical Resources relating to the Seirios Software:
We also have made our Seirios Manual Book available for download by clicking here.
Clone Your Robot
Installation Guide
REST APIs
Hardware Related
Custom Task / External Process Handler
TEB Tuning Guide
Pebble Tuning Guide
Kudan Integration
Import Multiple Stations to Seirios RNS from Excel File
After restarting the PC/machine, Seirios will automatically start every time the machine powers up.
To start Seirios manually, open a Terminal and enter your workspace by running the command cd ~/catkin_ws/movel_ai
Run docker-compose up
to start the docker containers for Seirios (output will be shown in the terminal)
Run docker-compose up -d
to start Seirios in the background (no output will be shown in the terminal)
To stop Seirios, go into the terminal where Seirios is currently running, and use Ctrl+C (if you run by using docker-compose up) OR run docker-compose down
in another terminal with the same directory. This will lead to the Docker containers being stopped.
To check for docker containers running at any point of time, run docker ps
.
If Seirios is up and running, you should expect to see the different containers of Seirios components being displayed. Otherwise, it should yield an empty table.
You can also check the version of Seirios by using docker ps
.
The goal of Part 1 of the installation is to install Docker and it’s dependencies
In the same directory in the Terminal, run the command bash install-1-docker.sh
Wait for the installation to complete
Then we move to the last part to install Seirios-RNS.
Taking the node “/motors_ctrl”
as an example. It is publishing to “/odom”
topic with “nav_msgs/Odometry”
message type, along with the other topics in the list. It also subscribes to “/cmd_vel”
topic with message type “geometry_msgs/Twist”
Go into the folder ‘/home/<user>/catkin_ws/movel_ai/config/movel/config/’
In the parameter file costmap_common_params.yaml, ensure that the robot footprint is defined correctly.
If the robot footprint is a polygon, configure the footprint parameter and comment out robot_radius. For example:
Here, the robot has a square footprint with the xy coordinates of the four corners as shown, while robot_radius is commented out.
If the robot footprint is circular, configure the robot_radius parameter and comment out footprint. For example:
In base_local_planner_params.yaml:
Go to “#Robot
” section. To tune the speed of the robot, configure max_vel_x
for linear speed, and max_vel_theta
for angular speed.
If the robot is not reaching the max speed, increase acc_lim_x
and acc_lim_theta
.
In footprint_model, select a suitable model type and configure the corresponding parameters.
In “#Obstacles
” section, tune the value of min_obstacle_dist
to set how far away the robot should keep away from obstacles. Reduce this parameter value if the robot is required to go through narrow spaces.
If the autonomous navigation motion is jerky, go to “catkin_ws/movel_ai/config/cmd_vel_mux/config”, find cmd_vel_mux.yaml, and increase the value set for timeout_autonomous
.
For in depth tuning of base_local_planner_params.yaml, refer to http://wiki.ros.org/teb_local_planner.
Ensure robot is moving linearly at the right speed
Before starting Robot checks:
Kill all Movel nodes (if you already have it previously installed)
Launch only the motor controller and the teleoperation keyboard twist for testing
[OR]
Run the following command:
rostopic pub -r 10 /cmd_vel - for linear linear: x-0.1 for rotation only : angular: z-0.1
Before downloading or installing Seirios RNS, it's important to check the following (hardware and software) to ensure errors do not compound during or after installation
If you're an existing client, please refer to this form to submit URLs to your required pre-installation videos and images
Click the following tab to view checklists
Installation is easy with simple commands on the command line interface. Before you start, please ensure your system has both Ubuntu and ROS installed. Recommended;
(x86_64) Ubuntu 20.04 & ROS Noetic OR (arm64) Ubuntu 18.04 & ROS Melodic
The easy-deploy package can be obtained from our Movel AI representative or can be downloaded from the following mirrors. Please ensure the right mirror for the right architecture (arm64 or x86 is selected)
Follow the instructions on the following pages to completely install Seirios RNS:
Google Drive Link | Mirror (Terabox) |
---|---|
A trial license of 15 days is included in this easy-deploy package. Tuning of your robot parameters and configuration is required after installation. Please contact your Movel AI representative or email sales@movel.ai for support and assistance.
Custom features such as docking to charging stations are not included as it is a custom feature that requires development and integration. If you have a docking /custom feature code, please refer to this link for integration
Move the easy-deploy zip file to your home directory /home/<USER>
and extract the zip using the Archive Manager (<USER> refers to the account username).
Now, we need to run the installation in a Terminal
Right-click in the file explorer and open a Terminal in the extracted easy-deploy folder/directory
Then we move to the next part to install docker.
Launch the robot's motor and sensor drivers.
Run rosnode list
to find the names of the ROS nodes of the drivers.
Run rosnode info <node>
, where <node> is the name of the nodes determined from step 2.
Sample output:
From the information displayed from running step 3, make sure that:
The robot motor driver node subscribes to the topic /cmd_vel
for velocity commands.
The Lidar driver node publishes laser data to the topic /scan
If the topic names are not set as in step 4, remap them in the launch files of the drivers by adding a line in the launch files in the following format:
While the robot base and lidar are launched, run rosrun rqt_tf_tree rqt_tf_tree
and check that the frames are linked in this order: odom → base_link → laser.
If the frames of base_link and laser are not linked correctly, there are two options you can link them. You can select one of them. (Prefer use Broadcast a transformation)
Broadcast a transformation refer to this link.
Create static transformation. Add the following line in the launch file of the lidar drivers:
In “args”, x = 0.22, y = 0, z = 0.1397, yaw = 0, pitch = 0, roll = 0 for this example. This should provide a transformation between the base_link and laser frame If you use static transformation, there will be several issues, one of the most is localizer mode, the UI won't visualize a laser scan in localizer mode.
With the driver nodes running, run RVIZ using: rosrun rviz rviz
, do the following checks:
Laser data ("/scan")
can be seen and is orientated in the correct direction.
Movement direction during teleoperation is correct.
Robot odometry ("/odom")
is updating correctly during teleoperation.
Skip this step if you are only evaluating Seirios RNS on a trial license
To view the remainder of the days left of your trial license, enter in your browser of choice
The Seirios RNS license is specific to the individual PC/robot that you are installing it on. The license that has been activated cannot be transferred and used on another machine.
Retrieve the c2v file
Generate your fingerprint of the PC by executing this command:
cd ~/catkin_ws/movel_ai/license/
./hasp_update_34404 f hasp_34404.c2v
(x86)
./hasp_update_34404_arm64 f hasp_34404.c2v
(arm64)
You will see the new c2v file on the /home/<USER>/catkin_ws/movel_ai/license/hasp_34404.c2v
c2v
(customer-to-vendor) is a fingerprint of your PC/robot that Movel AI requires to generate a licensed product
Send a c2v file to or your Movel AI representative to request the license activation
Movel AI will send a v2c file with installation instructions
Send Movel AI the updated c2v file with the license activated
Keep the v2c and c2v files safe for future reference with Movel AI
Timed Elastic Band (TEB) locally optimizes the robot's trajectory with respect to execution time, distance from obstacles and kinodynamic constraints at runtime.
teb_local_planner
for navigationThis guide is for you if you choose to use teb_local_planner
to navigate your robots. For more information, .
Filepath: catkin_ws/movel_ai/config/movel/config/
File to modify: base_local_planner_params.yaml
Note that config files for local planner is located in the movel
package. In the yaml file itself, you see there are actually 3 local planners included. But we will only use one of them. Uncomment the entire long section under TebLocalPlannerROS
.
One good practice will be to include only things you need (uncomment if previously commented) and comment out the rest.
These are the parameters that can be configured. Will explain how to tune these parameters later.
Warn: yaml forbids tabs. Do not use tabs to indent when editing yaml files. Also, check your indentations align properly.
After configuring Seirios to use teb planner, you need to sync the velocity with maximum velocity specified by teb planner.
Filepath: catkin_ws/movel_ai/config/velocity_setter/config/
File to modify: velocity_setter.yaml
Check local_planner
match the name of the planner in the base local planner configuration. You are configuring the maximum velocities to be the maximum velocities you specified in teb planner.
rviz: Use the 2D Pose Estimator tool to pinpoint the location of your robot on the map. You can use LaserScan to help you – increase the Size (m) to at least 0.05 and try to match the lines from the LaserScan as closely as possible with the map.
Seirios: Go to Localize. Use either your keyboard or the joystick button to align the laser with the map as closely as possible.
Filepath: catkin_ws/movel_ai/config/movel/config/amcl.yaml
File to modify: amcl.yaml
Amcl configuration file is in the same directory as base_local_planner_params.yaml.
Similarly, there are a lot of paramters in the amcl file although we are only interested in these 2 parameters:
Configure min_particles
and max_particles
to adjust the precision.
You can increase the values if you want a more precise localization.
However, tune the values with respects to the size of your map. Too many particles on a small map means there are redundant particles which only wastes computing power.
teb_local_planner
parametersThis section provides some suggestions on what values to give to the long list of parameters for TebLocalPlannerROS. Go back to the same base_local_planner_params.yaml file.
TEB requires a lot of tuning to get it to behave the way you want. Probably a lot of it is through trial and error.
For all kinds of robot tuning, always refer to the robot manufacturer’s configs. Whatever params you set must be within what that is handleable by your robot.
General tip: Make changes to only one/a few parameters at a time to observe how the robot behaves.
Tuneable parameters can be grouped into the following categories
Robot
Goal Tolerance
Trajectory
Obstacles
Optimisation
Tune robot related params with respects to the configurations specified by the manufacturer. i.e. The values set for velocity and acceleration should not exceed the robot's hardware limitations.
Kinematics
vel
parameters limits how fast the robot can move. acc
parameters limits how fast robot can accelerate. _x
specifies linear kinematics whereas _theta
specifies angular kinematics.
Footprint Model
radius
is required for type: "circular"
vertices
is required for type: "polygon"
Specifies how much deviation from the goal point that you are willing to tolerate.
xy_goal_tolerance
is the acceptable linear distance away from the goal, in meters.
Should not set xy
value too high, else the robot will stop at a very different location. However, some leeway is required to account for robot drift etc.
yaw_goal_tolerance
is the deviation in the robot's orientation. i.e. Goal specifies that the robot should face directly in front of the wall but in actual, the robot faces slightly to the left.
Should not give a too tight yaw
tolerance, else the robot could be jerking around just to get the orientation right. Which might not be ideal in terms of efficiency.
Decides how the robot should behave in front of obstacles.
Experimentation is required to tune the planner to approach obstacles optimally. A riskier configuration will allow the robot to move in obstacle ridden paths i.e. narrow corridors but it might get itself stuck around obstacles or bump into obstacles. A more conservative configuration might cause the robot to rule out its only available path because it thinks its too close to obstacles.
The tricky part is really to achieve a balance between those two scenarios.
min_obstacle_dist
is the minimum distance you want to maintain away from obstacles.
inflation_dist
is the buffer zone to add around obstacles.
Besides configuring obstacle handling behaviours in local planner, we can also configure the costmaps.
A costmap tells a robot how much does it cost to move the robot to a particular point. The higher the cost, the more the robot shouldn’t go there. Lethal obstacles that could damage the robot will have super high cost.
Filepath: catkin_ws/movel_ai/config/movel/config/
File to modify: costmap_common_params.yaml
File is in the same directory as base_local_planner_params
.
footprint
must match the measurements specified in base_local_planner_params.yaml.
You can choose to add some or all of the layers in the common_costmap_params
into global_costmap_params
and local_costmap_params
.
The most important thing in this section is to get the robot's footprint right.
Tip: Tune the teb_local_planner
params first. Modify the costmap only if you need more fine tuning after that.
This layer inflates the margin around lethal obstacles and specifies how much bigger you want to inflate the obstacles by.
inflation_radius
is the radius, in meters, to which the map inflates obstacle cost value. Usually it is the width of the bot, plus some extra space.
cost_scaling_factors
is the scaling factor to apply to cost values during inflation.
The
inflation_radius
is actually the radius to which the cost scaling function is applied, not a parameter of the cost scaling function. Inside the inflation radius, the cost scaling function is applied, but outside the inflation radius, the cost of a cell is not inflated using the cost function.You'll have to make sure to set the inflation radius large enough that it includes the distance you need the cost function to be applied out to, as anything outside the inflation_radius will not have the cost function applied.
For the correct
cost_scaling_factor
, solve the equation there ( exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1)), using your distance from obstacle and the cost value you want that cell to have.
Ideally, we want to set these two parameters such that the inflation layer almost covers the corridors. And the robot is moving in the center between the obstacles. (See figure below)
The obstacle layer marks out obstacles on the costmap. It tracks the obstacles as registered by sensor data.
For 2D mapping, laser_scan_sensor
must be selected.
obstacle_range
is the maximum distance from the robot that an obstacle will be inserted into the costmap. A value of 10 means the costmap will mark out obstacles that are within 10 meters from the robot.
raytrace_range
is the range in meters at which to raytrace out obstacles. The value must be set with respects to your sensors.
max_obstacle_height
is the maximum height of obstacles to be added to the costmap. Increase this number if you have very tall obstacles. The value must be set with respects to your sensors.
Voxel layer parameters
origin_z
is the z-origin of the map (meters)
z_resolution
is the height of the cube
z_resolution
controls how dense the voxels is on the z-axis. If it is higher, the voxel layers are denser. If the value is too low (e.g. 0.01), you won’t get useful costmap information. If you set z resolution to a higher value, your intention should be to obtain obstacles better, therefore you need to increasez_voxels
parameter which controls how many voxels in each vertical column. It is also useless if you have too many voxels in a column but not enough resolution, because each vertical column has a limit in height.
z_voxels
is the number of voxels
Low obstacle layer is obstacle layer, but with additional parameters. Change your observation_sources
to the topic that you want to take in data from.
Use obs_cloud
if you want a PointCloud (3D) or mock_scan
if you want a LaserScan (2D). Or you can specify your own method.
There are only two important parameters to note.
min_obstacle_height
is the height of the obstacle below the base of the robot. Examples includes stairs. Specify this param so that the robot can detect obstacles below its base link and prevent it from falling into the pit...
max_obstacle_height
is the maximum height of obstacle. It is usually specified as the height of the robot.
You WILL definitely be encountering some of the issues. Because param tuning requires experimentation, it is suggested you test out your values in the console first before modifying the yaml files.
rosrun rqt_reconfigure rqt_reconfigure
List of known issues and possible fixes is not exhaustive. There will be many more issues yet to be encountered when extensively using the robot. Thus it is good practice to keep a list of problems and solutions so you know how to deal with the problem should it come up again.
Issue #1: Problems getting the robot to go to the other side of the narrow path.
It is noted from observations that the robot will be returning goal failure, or that robot will get itself uncomfortably close to walls and get stuck there.
Issue #2: Problems getting the robot to turn 90 degrees.
The planner somehow disregards the wall and direct the robot to go through it instead of making a 90 degree turn around the wall. Though it seems most robots are smart enough to recognize they cannot go through walls and will either abort the goal or get stuck trying.
Solution #1: Reducing the velocity and acceleration. The intuition is that by slowing down the movement and rotation of the robot, the planner might have more time to react to the obstacle and plan accordingly.
Solution #2: (For robots that refuse to go to the other side of the corridor.)
Shrink the inflation_radius
in both costmaps so that it does not cover the corridor. (Right figure) Noted with observation that if the radius covers the entire corridor, robot may refuse to move.
Check that the robot's footprint size is correct and check that the costmaps aren't blocking the paths.
External resources if you need more information about planners and tuning planners.
Angular speed calibration check - Test using pub /cmd_vel for accurate result
Check the angular speed for at least 0.1-0.6 rad/s, and check whether the robot rotates correctly. A video recording is encouraged to troubleshoot any issues that may arise.
Likewise, repeat the same method to check angular speed calibration.
Run rostopic pub /cmd_vel geometry_msgs/Twist "linear: x: 0.0 y: 0.0 z: 0.0 angular: x: 0.0 y: 0.0 z: 0.0"
Set angular x value between 0.1-0.6. Leave the other values as 0.0.
Measure how much the robot turns. And similarly, record the time it took to turn.
Check that your calculations match the value you set for angular z.
Alternatively, you may use rosrun telelop_twist_keyboard teleop_twist_keyboard.py
. Set angular speed between 0.1-0.5. Then repeat Steps 3 - 5 above.
Validating Odometry Data
We provide you with a script that enables you to verify the odometry data by inputting the velocity and duration. The robot will then move at the specified velocity for the given duration. Subsequently, the script will calculate and provide the distance traveled by the robot based on these inputs.
This will facilitate the verification of your odometry data, making it easier and more efficient for you.
You can download the script .
This guide shows you how to migrate or clone your current robot images, database, and configurations of Seirios RNS to another robot.
You can migrate or close your current robot images, database, and configuration of Seirios RNS to another robot, depending on your needs.
You couldn't copy the license of your current robot and apply it to another robot, because the license is tied to one robot only. If you want to purchase the license for another robot you can reach us at or see this .
Backing up the custom images (not the default ones) is the most important because in our cloud, we don't have any custom images of the clients, we only have the default images. Since custom images may be different for each client/robot.
Usually, the default images are named “registry.gitlab.com/<path>:<tag>”, but the custom images are usually named by adding some word behind the tag like “registry.gitlab.com/<path>:<tag>-<client>” or another name.
Check the name of your custom image on your docker-compose.yaml file,
or you can check on the docker ps
(if you are already running the container):
See the image using docker image ls
:
Save the docker images to a tar archive file:
docker save seirios-ros-development > ~/catkin_ws/movel_ai/seirios-ros-development.tar
Change the seirios-ros-development to your custom image name, and you can change the tar filename as well
see if the new tar file is generated
ls -sh ~/catkin_ws/movel_ai/seirios-ros-development.tar
Otherwise, if you want to backup the default images as well, you can also backup the images using the same steps above.
You probably want to copy all the logs, maps, and some tasks that are already saved on your robot to another robot. So you don't have to do mapping and creating the tasks again.
Please follow the instructions below to back up the database:
Go inside the seirios-mongo container, and copy the db to the folder you want to save it inside the container, by executing the following command:
docker exec -i seirios-mongo /usr/bin/mongodump --db=movelweb --out=/backup_db
Create a folder on the pc, this will be a location for the database file, by executing this command:
mkdir -p ~/catkin_ws/movel_ai/backup_db
Copy the folder inside the docker container to outside, by following this command:
docker cp <container_name>:/backup_db ~/catkin_ws/movel_ai/backup_db
Since we already copied the database and images to ~/catkin_ws/movel_ai
folder, and the docker-compose.yaml
and all the configuration files are already on ~/catkin_ws/movel_ai
as well. Then the next step is you can copy all the files and folders on ~/catkin_ws/movel_ai
folder.
---------------------
If you want to clone the seirios-RNS software with all the configs from one robot to another robot, please make sure those robot has the same configuration below:
Camera ROS topics
Dimension or Footprint of the robot
LiDAR ROS topics
Odometry ROS topics and frame id
Transformation of the frame
Please copy ~/catkin_ws/movel_ai
folder from your old robot to the new robot, to restore the docker-compose.yaml and all the configurations.
Since we already copied the image as a tar archive file, you can load it into docker as a docker image file by executing this command:
docker load < ~/catkin_ws/movel_ai/seirios-ros-development.tar
Change the seirios-ros-development.tar to your docker image name.
Then check if all the images are loaded properly or not by executing the following command: docker image ls
.
First, make sure you run the seirios-mongo container on the docker.
To restore the database that you already saved before, you can execute the following command on the new PC:
docker exec -i seirios-mongo /usr/bin/mongorestore --db=movelweb ~/catkin_ws/movel_ai/backup_db
.
Seirios supports a wide range, variety, and combination of sensors on robots for various applications.
The following are sensors tried and tested with Seirios RNS on various robots types
If you do not see a familiar or preferred sensor below, benchmark against the available sensor's technical specifications. Contact us at for further inquiries or clarifications
Computers, mini PCs, and other developer boards come with either x86 or ARM64 chips. Click next to see hardware that has been tried and tested with Seirios.
Processing power is crucial to running Seirios RNS with your robot. With more sensors installed, more computing power will be required to be allocated - and less will be available for Seirios
The following are recommended PC/board specifications to take advantage of every feature available on Seirios RNS
PC with x86 processor (4 cores with 8 threads @ >3.1GhZ) OR ARM64 (8 cores) [We recommend you to use min i7 gen 8th]
8GB DDR4 RAM
256GB SSD
Ubuntu 20.04 & ROS Noetic (x86) OR Ubuntu 18.04 & ROS Melodic (ARM64)
WiFi connectivity 802.11a/b/g/n/ac
The following pages are specific PCs and developer boards that we have tested with Seirios RNS
x86-64 systems are widely used in most robotics systems and robots with compact-form PCs. It has high computing power and supports multiple hardware sensors connected to it.
Be sure that your robotic system has a large enough battery to accommodate its operations
Coming soon!
Seirios RNS is compatible with the following ARM-based systems and kits. ARM-based boards are power efficient but lack computing power (compared to x86-64 / AMD6 systems.
Some computing-intensive features such as 3D LiDAR mapping and navigation or multisensor support (eg 3 different sensors) will not be available on these boards.
Cameras are crucial for navigation and localization. Some brands/models have IMU integrated for an additional dimension for precision navigation.
360° cameras are useful for many applications such as cleaning and security
Light Detection and Ranging (LiDAR) sensors are useful in many settings, situations, and applications. It does not rely on visual light for path planning, navigation, and localization.
Useful at short ranges, low-lying obstacles can be detected using ult
A low-powered sensor; usually used for non-opaque obstacle detection such as glass or plastic panels
external_process_handler is a package for clients to run their own tasks into Seirios.
This guide shows you how to integrate your own programs as a plugin into Seirios using external_process_handler
package.
Check your Ubuntu + ROS version.
For Ubuntu 20.04, ROS Noetic users:
Go here to download the .deb package:
Move the .deb into your home folder. Open a terminal window, run the command sudo apt install ./ros-noetic-movel-seirios-msgs_0.0.0-0focalXXX64.deb
to install.
Else:
Git clone this repo here: into catkin_ws/src. Then go back to /catkin_ws to run catkin_make.
You need to mount your own packages/nodes as a plugin to task_supervisor for Seirios to run it.
File to modify: ../config/task_supervisor/config/
task_supervisor.yaml
Look for the plugins section in the config to add your own plugin. You can give any name and type. For type, give a number not used by previous plugins.
Then at the end of the file, create a new section with the same name you give for your plugin e.g. detecting. Then paste in the parameters.
There are different ways to launch your own codes. Choose one in the below subsection that best suits you.
Start & stop
You need to write a ROS service service_start with start_handler as the callback function to start your code.
And you need another ROS service service_stop with stop_handler to stop your code. Names must be service_start and service_stop.
You must use the movel_seirios_msgs package for msg and srv.
(For ROS C++ only) Add movel_seirios_msgs to package.xml and CMakeLists.txt.
Then in task_supervisor.yaml file. Change service_req: true
and service_start
and service_stop
params to your own topics.
Stop with topic (optional)
IF you have your own script to stop the launch.
Write a subscriber topic_process_cancel to subscribe to the UI topic. Inside the handle_publish_cancel callback, include your own codes to stop.
Then change the params topic_cancel_req: true
and topic_process_cancel
to your own topic.
Getting status (optional)
IF you are launching your program from a launch file. Write a publisher client_status that publishes 2 if the program runs successfully or 3 if it fails.
Then change client_status: true
.
Go to Custom Task UI, and choose Seirios Engine as your Execute Engine. Similarly, you need to give a task type number that is not used by other task supervisor plugins.
Then, you will need a custom service_start_msg
and/or service_stop_msg
to run or stop your external process.
Input a Payload in the JSON format e.g. {“service_start_msg”: “/eg/payload/start”, “service_stop_msg”:”/eg/payload/stop”}
to customize the parameters.
Payload has to be parsable in JSON format so remember the “ ”s.
For reference only.
The goal of Part 2 of the installation is to install Seirios, prepare the catkin_ws
, and create the appropriate docker-compose.yaml
file.
In the same directory in Terminal, run the command bash install-2-seirios.sh
Wait for the installation to complete
Restart the PC/machine after the installation
The script install_2.sh will not overwrite existing files in /home/catkin_ws , and will maintain backups of configuration files for safekeeping
The Pebble Planner is a simple local planner that is designed to follow the global plan closely. Advantages of Pebble Planner include fewer configurable parameters and less oscillating motions.
Pebble Planner takes the global plan, decimates it to space out the poses as “pebbles”, then tries to reach them one by one.
It does this by rotating towards the next pebble, then accelerating until the maximum velocity is reached.
Filepath: ~/catkin_ws/movel_ai/config/movel/config/
File to modify: base_local_planner_params.yaml
Same steps as setting up for TEB Local Planner. In the file, uncomment the section PebbleLocalPlanner
to set your local planner to use Pebble.
Filepath: ~/catkin_ws/movel_ai/config/velocity_setter/config/
File to modify: velocity_setter.yaml
Change the parameterlocal_planner: "PebbleLocalPlanner"
.
Make sure you changed the parameters in both files or else an error may be thrown.
Compared to TEB, the pebble planner has fewer configurable parameters.
Find these parameters in ~/movel/config/base_local_planner_params.yaml under the section PebbleLocalPlanner.
Can be generally classified as Probably Important, Optional, and can be Ignored.
robot_frame
map_frame
d_min
Defines the minimal distance between waypoints (pebbles) when decimating the global plan. This ensures that the robot’s path is simplified by reducing the number of closely spaced waypoints.
Impact:
A smaller value allows for more closely spaced waypoints, making the path smoother but potentially more complex.
A larger value reduces the number of waypoints, simplifying the path.
Unit: Meters.
allow_reverse
Determines whether the robot is allowed to move in reverse.
Impact:
True: Enables backward movement, improving flexibility and maneuverability, especially in tight spaces.
False: Disables backward motion, limiting the robot to forward-only movement, which may restrict its ability to navigate in certain situations. Recommended if your robot doesn't have sensors at the back.
acc_lim_x
The maximum linear acceleration of the robot in the x direction (forward motion).
Impact:
A higher value allows quicker acceleration.
A lower value results in smoother, more gradual acceleration.
Unit: Meters per second²
acc_lim_theta
The maximum angular acceleration of the robot (rotation speed change). The pebble planner will rotate the robot towards the next pebble, then accelerates towards it (till max speed). The planned path may be straighter if angular acceleration is lowered.
Impact:
A higher value allows for faster changes in rotational speed.
A lower value makes the robot’s rotation smoother and slower.
Unit: Radians per second² (0.785 rad/s ≈ 45 degrees per second).
xy_goal_tolerance
Specifies how close the robot needs to be to the goal’s x and y coordinates before considering the goal reached.
Impact:
A smaller value requires more precision in reaching the goal.
A larger value allows the robot to stop farther away from the exact goal position.
Unit: Meters.
yaw_goal_tolerance
Specifies the angular tolerance (yaw, or rotation around the z-axis) at the goal.
Impact:
A smaller value requires the robot to align more precisely with the goal orientation.
A larger value allows more flexibility in the robot’s final orientation.
Unit: Radians (0.3925 radians ≈ 22.5 degrees).
local_obstacle_avoidance
Whether to use Pebble Planner’s local obstacle avoidance. If set to false, and move_base’s planner_frequency is set to > 0 Hz, the global planner takes care of obstacle avoidance.
Impact:
True: The Pebble Planner will handle local obstacle avoidance, making the robot actively avoid obstacles along its path.
False: Disables local obstacle avoidance, relying on the global planner to manage obstacle avoidance based on the frequency set in move_base.
n_lookahead
How many pebbles are ahead of the active one to look ahead for obstacles. This parameter is only relevant if local_obstacle_avoidance is set to true.
Impact:
A higher value means the robot will anticipate obstacles further ahead.
A lower value limits how far the robot looks ahead for obstacles, focusing on the immediate area around the active pebble.
th_turn
The threshold angle beyond which the robot will stop and turn in place to face the next waypoint (pebble), instead of trying to turn and move at the same time.
Impact:
A lower value makes the robot attempt to turn while moving more often.
A higher value means the robot will stop and rotate in place for larger angle changes.
Unit: Radians (1.0472 rad ≈ 60 degrees).
th_reverse
The threshold angle for reversing. If the angle between the robot and the target exceeds this value, the robot will reverse instead of turning around.
Impact:
A smaller value makes the robot reverse less often.
A larger value encourages more frequent reverse movements.
Unit: Radians (2.3562 rad ≈ 135 degrees).
decelerate_goal
Controls whether the robot should decelerate as it approaches the goal.
Impact:
True: The robot slows down as it nears the goal for improved precision.
False: The robot maintains speed until it reaches the goal.
decelerate_each_waypoint
Determines whether the robot should decelerate when reaching each waypoint (pebble) along its path.
Impact:
True: The robot decelerates at each waypoint, making navigation smoother but slower.
False: The robot maintains speed between waypoints for quicker movement.
decelerate_distance
The distance from the waypoint at which the robot starts to decelerate.
Impact: Affects how early the robot starts slowing down before reaching waypoints or the goal.
Unit: Meters.
decelerate_factor
The rate at which the robot decelerates as it approaches a waypoint or goal.
Impact: A higher factor increases the rate of deceleration, while a lower factor results in more gradual deceleration.
curve_angle_tolerance
The angular tolerance allowed when following a curved path.
Impact:
A higher value allows for looser curve-following, reducing the need for sharp corrections.
A smaller value requires more precise curve-following.
Unit: Degrees.
curve_d_min
The minimum distance between waypoints (pebbles) on a curved path.
Impact:
A smaller value results in more frequent waypoints along the curve, offering finer control.
A larger value simplifies the path by reducing the number of waypoints.
Unit: Meters.
curve_vel
The speed at which the robot should travel while navigating curved paths.
Impact:
A higher value allows faster movement along curves.
A lower value ensures more controlled and precise movements.
Unit: Meters per second.
consider_circumscribed_lethal
Determines whether the circumscribed area around the robot (the area just beyond the robot’s footprint) is considered lethal (i.e., an obstacle).
Impact:
True: The circumscribed area is considered an obstacle, making the robot more conservative in its movements.
False: The circumscribed area is ignored, allowing the robot to navigate closer to obstacles.
inflation_cost_scaling_factor
The scaling factor for the cost of inflated obstacles in the costmap.
Impact:
A higher value increases the cost of cells near obstacles, forcing the robot to take wider detours.
A lower value makes the robot more willing to move closer to obstacles.
Unit: Unitless (scaling factor).
max_vel_x, max_vel_theta - These values will be set by the UI depending on what values you give there. Can ignore it if you are using the UI.
(kp, ki, kd values) - Configurations for a differential drive.
max_vel_x
The maximum forward velocity of the robot.
Impact:
A higher value allows the robot to move faster.
A lower value limits the robot’s speed, improving safety and control.
Unit: Meters per second.
max_vel_theta
The maximum rotational velocity of the robot.
Impact:
A higher value enables faster turns.
A lower value makes the robot turn more slowly, offering smoother rotations and planned path straighter
Unit: Radians per second (0.785 rad/s ≈ 45 degrees per second).
Seirios RNS comes with REST APIs for you to utilize - for integration and advanced deployments. To view the list of APIs available:
Please enter <IPaddress>:8000/api-docs/swagger
on your robot/PC.
Alternatively, please download this pdf to explore available APIs ⬇️
for more information.
Literally a footprint. Ideally, configure the footprint to be slightly bigger than the actual measurement of the robot. footprint_model
should be configured with respects to the robot's measurements.
You must indicate the type
of the robot footprint. Different types include polygon
, circular
, two_circles
, line
, point
etc. For simplicity sake, footprints are usually circular or polygon. for more footprint information.
for more information about obstacle avoidance and penalty. And for known problems with regards to obstacle avoidance tuning.
There are several layers added into the costmap. Usually we follow the specifications .
For the costmap layers that you have decided to use, you must mount the layers into global_costmap_params.yaml
and local_costmap_params.yaml
as plugins. for more information on the difference between global and local costmaps.
Additional information to configure it correctly (directly lifted from )
Voxels are 3D cubes that has a relative position in space. Can be used for 3D reconstruction with depth cameras. Ignore the parameters below if you are not using 3D. More information .
It’s also important to back up the default images as well because if it’s not, the new PC has to download the images (it took > 6 GB) and also needs a credential key from movel.ai, you can ask the credential key to .
Please make sure you already install the seirios RNS, you can use for installing the seirios-RNS.
If you have any questions and need help for migrate the software to another PC, please feel free to ask by reaching us at .
If you are unsure if your sensor(s) is/are supported, please contact us at
To view the remainder of days left of your trial licence, enter in your browser of choice
Seirios RNS Feature Documentation: Bulk Station Management
Seirios RNS (Robot Navigation Software) introduces a powerful feature that significantly enhances the efficiency of defining navigation stations for robots. This document covers the steps to utilize the new bulk station management feature, which allows users to import station details from an Excel file. This feature can create or update over 500+ stations in a matter of seconds, a significant improvement over the manual method. The feature is available from version 4.30.1 for both Frontend and Backend.
Feature Summary
The bulk station management feature enables users to define multiple stations simultaneously by importing data from an Excel file. This reduces the manual effort required to set stations one by one, which can be time-consuming and prone to error.
Benefits
- Efficiency: Import over 500+ stations in a few seconds.
- Accuracy: Reduces human errors associated with manual data entry.
- Convenience: Manage station updates and deletions through a simple Excel interface.
Setup Instructions
1. Preparation of Files
- Download Scripts and Template File: Begin by downloading the scripts `create_multiple_station_script.py` and `delete_multiple_station_script.py` here. Prepare an Excel file named `updated_station_list.xlsx` containing 5 columns:
- station_name
- station_id: Leave this column blank; it will be automatically populated or updated when the scripts are run.
- position_x: X-coordinate of the station in meters.
- position_y: Y-coordinate of the station in meters.
- orientation_theta: Orientation in degrees.
Alternatively, a template of this Excel file can be downloaded from https://drive.google.com/drive/folders/10sSi3olbjGWZ1V8kT1dA-w9l8DSgLDCo?usp=drive_link .
- File Location: Copy all three files (`create_multiple_station_script.py`, `delete_multiple_station_script.py`, `updated_station_list.xlsx`) to `~/catkin_ws/movel_ai/config`.
2. Editing the Station List
- Add new rows to define new stations in the `updated_station_list.xlsx` file. Fill in details except for the `station_id` as it is handled by the script.
- To update existing stations, modify the `station_name`, `position_x`, and `orientation_theta` fields as needed. Do not alter the `station_id`.
- Important: Save and close the Excel file to ensure the `station_id` gets updated correctly.
Execution Instructions
Running the Scripts
1. Access Terminal: Open your terminal and run the following command to access the Docker container running Seirios RNS:
docker exec -it seirios-ros bash
2. Navigate to the Configuration Directory:
cd /home/movel/.config/movel/config/
3. Create or Update Stations:
python3 create_multiple_station_script.py
4. Delete Stations (if necessary):
python3 delete_multiple_station_script.py
5. Refresh the UI: Refresh the user interface to view and verify the changes made to the stations.
Support
For further assistance or queries regarding the bulk station management feature, please contact our support team at help@movel.ai or visit our support page .
This feature is designed to streamline your robotic navigation setup and updates, making process management more efficient and less labor-intensive. For optimal use, ensure that all instructions are correctly followed and that the file and column names are kept consistent as specified.
arm64 (currently unavailable)
This guide shows you how to integrate the Kudan packages into Seirios RNS.
Kudan Inc is a Japan-headquartered company focusing on artificial perception computer software by providing artificial perception solutions, such as localization and mapping software.
Kudan offers commercial-grade localization and mapping software based on SLAM technology (Simultaneous localization and mapping). This technology enables machines and devices to understand where they are, how they are moving, and the structure of their environment.
For more information, please refer to Kudan’s website, or if you want to use a Kudan as your SLAM solution for your 3D lidar, you can contact sales@movel.ai.
First, you have to download the Kudan ROS Packages,
If you haven't installed the Seirios RNS yet, you can download the kudan-movel easy deploy package using this link (only for x86_64 architecture).
But if you already installed the Seirios RNS yet, you can contact sales@movel.ai for the link to download the Kudan Packages.
Then please make sure your seirios-ros image version is at least 2.48.9
or newer.
You can check it by executing this command:
docker ps | grep seirios-ros
And see the version on this line:
If your version is older than 2.48.9
, please contact sales@movel.ai for updating the version.
Copy the kdlidar_ros package into the ~/catkin_ws/movel_ai/
folder
Change the permission of kdlidar_ros, so it can be executed inside the docker
chmod -R +x ~/catkin_ws/movel_ai/kdlidar_ros/
Configure tf/transform parameters in these launch files:
~/movel_ws/kdlidar_ros/install/share/kdlidar_ros/launch/kdlidar_ros_pcl_localise.launch
,
Change the platform_to_lidar0_rot
and platform_to_lidar0_trans
based on your tf from lidar link to base_link.
~/movel_ws/kdlidar_ros/install/share/kdlidar_ros/launch/kdlidar_ros_pcl_mapping.launch
,
Change the platform_to_lidar0_rot
and platform_to_lidar0_trans
based on your tf from lidar link to base_link.
Create the ros_entrypoint.sh
in the ~/catkin_ws/movel_ai/
folder.
Also, change the permission of the ros_entry_point.sh by executing this command:
sudo chmod +x ~/catkin_ws/movel_ai/ros_entrypoint.sh
Edit your docker-compose.yaml
file in the ~/catkin_ws/movel_ai/
folder.
Under the seirios-ros volumes, add the following line:
Add the following variables under the seirios-backend and seirios-frontend environment:
Edit the task_supervisor.yaml
(at ~/catkin_ws/movel_ai/config/task_supervisor/config/task_supervisor.yaml
)
Add kudan_localization_handler
to the plugins section with the following lines and comment if there's any plugin with the same type number. Example:
Add a kudan_localization_handler
section with the following parameters at the end of the file:
Add kudan_slam_handler
to the plugins section with the following lines and comment if there's any plugin with the same type number. Example:
Add a kudan_slam_handler
section with the following parameters at the end of the file:
After you edit the task_supervisor.yaml
, please restart all the docker containers by executing the following commands:
Now you can do the 3D Mapping using Kudan Package by clicking the "Mapping" feature on Seirios RNS UI. If you are facing any issues and have questions, please feel free to ask by reaching us at sales@movel.ai