-
Notifications
You must be signed in to change notification settings - Fork 1
Home
Welcome to the ros2Nav wiki!
openRB-150 with motor $45.90 (ROBOTIS, iNEX)
DYNAMIXEL XL330-M288-T $23.90 (ROBOTIS, iNEX)
FPX330-S101 4pcs Set $8.70 (ROBOTIS, iNEX)
TB3 Wheel Tire Set-ISW-01 (2ea) $9.40 (ROBOTIS, iNEX)
WitMotion WT61C TTL AHRS $23.31 (Aliexpress)
ld06 LiDAR $ $99.99 (Aliexpress)
Raspberry pi $4000 Bath (Cytron Thailand)
Powerbank Loop 599 Bath
Base local made 1000 Bath
add the following lines to /boot/firmware/config.txt
dtdebug=ON
dtoverlay=uart2
dtoverlay=uart3
dtoverlay=uart4
dtoverlay=uart5
enable_uart=1
add the following lines to /boot/firmware/config.txt
enable_uart=1
dtoverlay=uart1
dtoverlay=uart2
dtoverlay=uart3
dtoverlay=uart4
dtoverlay=uart5
After reboot, we can use ls -l /dev to verify the UARTS
crw-rw---- 1 root dialout 204, 64 พ.ค. 12 21:41 ttyAMA0
crw-rw---- 1 root dialout 204, 65 มี.ค. 20 21:32 ttyAMA1
crw-rw---- 1 root dialout 204, 66 มี.ค. 20 21:32 ttyAMA2
crw-rw---- 1 root dialout 204, 67 มี.ค. 20 21:32 ttyAMA3
crw-rw---- 1 root dialout 204, 68 มี.ค. 20 21:32 ttyAMA4
crw------- 1 root root 3, 192 มี.ค. 20 21:32 ttyb0
sudo apt update
sudo apt upgrade
sudo apt update && sudo apt install locales
sudo apt install software-properties-common
sudo add-apt-repository universe
sudo apt update && sudo apt install curl
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
sudo apt update
sudo apt install ros-humble-desktop
sudo apt install ros-dev-tools
sudo apt install ros-humble-gazebo-ros-pkgs
sudo apt install ros-humble-turtlebot3 ros-humble-turtlebot3-msgs ros-humble-turtlebot3-gazebo
sudo apt-key del F42ED6FBAB17C654 to remove the key you've added, then run
sudo apt update, then
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg, then
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(source /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
sudo apt install ros-humble-nav2-costmap-2d
when build with Colcon export MAKEFLAGS="-j 1"
add the following lines to .bashrc
# Replace ".bash" with your shell if you're not using bash
# Possible values are: setup.bash, setup.sh, setup.zsh
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
export ROS_DISTRO=humble
#export ROS_DOMAIN_ID=69
#export ROS_LOCALHOST_ONLY=1
source /opt/ros/humble/setup.bash
source /home/pi/amr_ws/install/local_setup.bash
Nav2 seems to work well with cyclonedds
First install
sudo apt install ros-humble-cyclonedds
sudo apt install ros-humble-rmw-cyclonedds-cpp
Then in .bashrc add this line
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
First, the arduino micro ros library can be downloaded from https://github.com/micro-ROS/micro_ros_arduino/releases and choose the one that match your ros2 version. Then install the library from the downloaded zip file.
Tested board
- openRB-150
- raspberry pi Pico (choose mbed version)
- Arduino GIGA R1
The last two can be used with Arduino scheduler (Scheduler.h) to do parallel task and can also be use with Arduino queue.
The following code is for openRB-150 with Dynamixel motor
#include <micro_ros_arduino.h>
#include <stdio.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <nav_msgs/msg/odometry.h>
#include <std_msgs/msg/int32.h>
#include <geometry_msgs/msg/twist.h>
#include <geometry_msgs/msg/vector3.h>
#include "odometry.h"
#include <Dynamixel2Arduino.h>
#include "Kinematics.h"
#if defined(__OPENCM904__)
#define DEVICE_NAME "3" //Dynamixel on Serial3(USART3) <-OpenCM 485EXP
#elif defined(__OPENCR__)
#define DEVICE_NAME ""
#endif
#define LINO_BASE DIFFERENTIAL_DRIVE // 2WD and Tracked robot w/ 2 motors
#define MAX_RPM 100 // motor's maximum RPM
#define WHEEL_DIAMETER 0.066 // wheel's diameter in meters
//#define LR_WHEELS_DISTANCE 0.16 // distance between left and right wheels 0.800
#define LR_WHEELS_DISTANCE 0.12 // distance between left and right wheels 0.800
#define FR_WHEELS_DISTANCE 0.30 // distance between front and rear wheels. Ignore this if you're on 2WD/ACKERMANN
#define BAUDRATE 57600
#define DXL_ID_LEFT 1
#define DXL_ID_RIGHT 2
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = -1;
const float DXL_PROTOCOL_VERSION = 2.0;
uint8_t dxl_id[2] = { DXL_ID_LEFT, DXL_ID_RIGHT };
#define LED_PIN 13
#define RCCHECK(fn) \
{ \
rcl_ret_t temp_rc = fn; \
if ((temp_rc != RCL_RET_OK)) { rclErrorLoop(); } \
}
#define RCSOFTCHECK(fn) \
{ \
rcl_ret_t temp_rc = fn; \
if ((temp_rc != RCL_RET_OK)) {} \
}
#define EXECUTE_EVERY_N_MS(MS, X) \
do { \
static volatile int64_t init = -1; \
if (init == -1) { init = uxr_millis(); } \
if (uxr_millis() - init > MS) { \
X; \
init = uxr_millis(); \
} \
} while (0)
rcl_publisher_t odom_publisher;
rcl_publisher_t publisher;
rcl_subscription_t twist_subscriber;
nav_msgs__msg__Odometry odom_msg;
geometry_msgs__msg__Twist twist_msg;
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t control_timer;
unsigned long long time_offset = 0;
unsigned long prev_cmd_time = 0;
unsigned long prev_odom_update = 0;
Odometry odometry;
int32_t present_velocity[2] = { 0, 0 };
bool result = false;
const uint8_t handler_index = 0;
int currentLeftWheelRPM;
int currentRightWheelRPM;
uint16_t model_number = 0;
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
//This namespace is required to use Control table item names
using namespace ControlTableItem;
Kinematics kinematics(Kinematics::LINO_BASE, MAX_RPM, WHEEL_DIAMETER, FR_WHEELS_DISTANCE, LR_WHEELS_DISTANCE);
enum states {
WAITING_AGENT,
AGENT_AVAILABLE,
AGENT_CONNECTED,
AGENT_DISCONNECTED
} state;
void setLeftRPM(int rpm) {
dxl.setGoalVelocity(DXL_ID_LEFT, rpm, UNIT_RPM);
}
void setRightRPM(int rpm) {
dxl.setGoalVelocity(DXL_ID_RIGHT, -1*rpm, UNIT_RPM);
}
int getLeftRPM(){
currentLeftWheelRPM = (int) dxl.getPresentVelocity(DXL_ID_LEFT, UNIT_RPM);
return currentLeftWheelRPM;
}
int getRightRPM() {
currentRightWheelRPM = -1* ((int) dxl.getPresentVelocity(DXL_ID_RIGHT, UNIT_RPM));
return -1*currentRightWheelRPM;
}
void setup() {
const char* log;
pinMode(LED_PIN, OUTPUT);
set_microros_transports();
dxl.begin(57600);
// Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
// Get DYNAMIXEL information
dxl.ping(DXL_ID_LEFT);
// Turn off torque when configuring items in EEPROM area
dxl.torqueOff(DXL_ID_LEFT);
dxl.setOperatingMode(DXL_ID_LEFT, OP_VELOCITY);
dxl.torqueOn(DXL_ID_LEFT);
//dxl.setGoalVelocity(DXL_ID_LEFT, 10.0, UNIT_RPM);
dxl.setGoalVelocity(DXL_ID_LEFT, 0.0, UNIT_RPM);
dxl.ping(DXL_ID_RIGHT);
// Turn off torque when configuring items in EEPROM area
dxl.torqueOff(DXL_ID_RIGHT);
dxl.setOperatingMode(DXL_ID_RIGHT, OP_VELOCITY);
dxl.torqueOn(DXL_ID_RIGHT);
//dxl.setGoalVelocity(DXL_ID_RIGHT, 10.0, UNIT_RPM);
dxl.setGoalVelocity(DXL_ID_RIGHT, 0.0, UNIT_RPM);
}
void loop() {
switch (state) {
case WAITING_AGENT:
EXECUTE_EVERY_N_MS(500, state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AGENT_AVAILABLE : WAITING_AGENT;);
break;
case AGENT_AVAILABLE:
state = (true == createEntities()) ? AGENT_CONNECTED : WAITING_AGENT;
if (state == WAITING_AGENT) {
destroyEntities();
}
break;
case AGENT_CONNECTED:
EXECUTE_EVERY_N_MS(200, state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AGENT_CONNECTED : AGENT_DISCONNECTED;);
if (state == AGENT_CONNECTED) {
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(20));
}
break;
case AGENT_DISCONNECTED:
destroyEntities();
state = WAITING_AGENT;
break;
default:
break;
}
}
void controlCallback(rcl_timer_t* timer, int64_t last_call_time) {
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
moveBase();
}
}
void twistCallback(const void* msgin) {
digitalWrite(LED_PIN, !digitalRead(LED_PIN));
Kinematics::rpm req_rpm = kinematics.getRPM(
twist_msg.linear.x,
twist_msg.linear.y,
twist_msg.angular.z);
setLeftRPM(req_rpm.motor1);
setRightRPM(req_rpm.motor2);
prev_cmd_time = millis();
}
void moveBase() {
/*if (((millis() - prev_cmd_time) >= 200)) {
twist_msg.linear.x = 0.0;
twist_msg.linear.y = 0.0;
twist_msg.angular.z = 0.0;
digitalWrite(LED_PIN, HIGH);
}*/
// get the required rpm for each motor based on required velocities, and base used
getRightRPM();
getLeftRPM();
int current_rpm1 = currentLeftWheelRPM; //rightWheel.getRPM();
int current_rpm2 = currentRightWheelRPM; //leftWheel.getRPM();
int current_rpm3 = 0;
int current_rpm4 = 0;
Kinematics::velocities current_vel = kinematics.getVelocities(current_rpm1, current_rpm2, current_rpm3, current_rpm4);
//current_vel = kinematics.getVelocities(50, 50, 0, 0);
unsigned long now = millis();
float vel_dt = (now - prev_odom_update) / 1000.0;
prev_odom_update = now;
odometry.update(
vel_dt,
current_vel.linear_x,
current_vel.linear_y,
current_vel.angular_z);
odom_msg = odometry.getData();
struct timespec time_stamp = getTime();
odom_msg.header.stamp.sec = time_stamp.tv_sec;
odom_msg.header.stamp.nanosec = time_stamp.tv_nsec;
RCSOFTCHECK(rcl_publish(&odom_publisher, &odom_msg, NULL));
}
bool createEntities() {
allocator = rcl_get_default_allocator();
//create init_options
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
// create node
RCCHECK(rclc_node_init_default(&node, "move_base_node", "", &support));
// create odometry publisher
RCCHECK(rclc_publisher_init_default(
&odom_publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(nav_msgs, msg, Odometry),
"odom/unfiltered"));
// create twist command subscriber
RCCHECK(rclc_subscription_init_default(
&twist_subscriber,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist),
"cmd_vel"));
// create timer for actuating the motors at 50 Hz (1000/20)
const unsigned int control_timeout_odom = 40;
RCCHECK(rclc_timer_init_default(
&control_timer,
&support,
RCL_MS_TO_NS(control_timeout_odom),
controlCallback));
executor = rclc_executor_get_zero_initialized_executor();
RCCHECK(rclc_executor_init(&executor, &support.context, 2, &allocator));
RCCHECK(rclc_executor_add_subscription(
&executor,
&twist_subscriber,
&twist_msg,
&twistCallback,
ON_NEW_DATA));
RCCHECK(rclc_executor_add_timer(&executor, &control_timer));
// synchronize time with the agent
syncTime();
digitalWrite(LED_PIN, HIGH);
return true;
}
bool destroyEntities() {
rmw_context_t* rmw_context = rcl_context_get_rmw_context(&support.context);
(void)rmw_uros_set_context_entity_destroy_session_timeout(rmw_context, 0);
rcl_publisher_fini(&odom_publisher, &node);
rcl_node_fini(&node);
rcl_timer_fini(&control_timer);
rclc_executor_fini(&executor);
rclc_support_fini(&support);
digitalWrite(LED_PIN, HIGH);
return true;
}
void syncTime() {
// get the current time from the agent
unsigned long now = millis();
RCCHECK(rmw_uros_sync_session(10));
unsigned long long ros_time_ms = rmw_uros_epoch_millis();
// now we can find the difference between ROS time and uC time
time_offset = ros_time_ms - now;
}
struct timespec getTime() {
struct timespec tp = { 0 };
// add time difference between uC time and ROS time to
// synchronize time with ROS
unsigned long long now = millis() + time_offset;
tp.tv_sec = now / 1000;
tp.tv_nsec = (now % 1000) * 1000000;
return tp;
}
void rclErrorLoop() {
while (1) {
digitalWrite(LED_PIN, !digitalRead(LED_PIN));
delay(100);
}
}To test micro ros, we need to install micro ros agent on the host computer by the following steps
# Source the ROS 2 installation
source /opt/ros/foxy/setup.bash
# Create a workspace and download the micro-ROS tools
mkdir microros_ws
cd microros_ws
git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup
# Update dependencies using rosdep
sudo apt update && rosdep update
rosdep install --from-paths src --ignore-src -y
# Install pip
sudo apt-get install python3-pip
# Build micro-ROS tools and source them
colcon build
source install/local_setup.bash
Once the package is build, we need to install micro-ros Agent
# Download micro-ROS agent packages
ros2 run micro_ros_setup create_agent_ws.sh
# Build step
ros2 run micro_ros_setup build_agent.sh
source install/local_setup.bash
We can test micro ros by connecting the Arduino board to the host computer and using
ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyACM0
The output will be something like
pi@pi-ros2:~$ ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyACM0
[1715914950.141446] info | TermiosAgentLinux.cpp | init | running... | fd: 3
[1715914950.142322] info | Root.cpp | set_verbose_level | logger setup | verbose_level: 4
[1715914950.596887] info | Root.cpp | create_client | create | client_key: 0x5B0F1BBE, session_id: 0x81
[1715914950.598474] info | SessionManager.hpp | establish_session | session established | client_key: 0x5B0F1BBE, address: 0
[1715914950.732630] info | ProxyClient.cpp | create_participant | participant created | client_key: 0x5B0F1BBE, participant_id: 0x000(1)
[1715914950.733778] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x5B0F1BBE, topic_id: 0x000(2), participant_id: 0x000(1)
[1715914950.734547] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x5B0F1BBE, publisher_id: 0x000(3), participant_id: 0x000(1)
[1715914950.736154] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x5B0F1BBE, datawriter_id: 0x000(5), publisher_id: 0x000(3)
[1715914950.737025] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x5B0F1BBE, topic_id: 0x001(2), participant_id: 0x000(1)
[1715914950.737773] info | ProxyClient.cpp | create_subscriber | subscriber created | client_key: 0x5B0F1BBE, subscriber_id: 0x000(4), participant_id: 0x000(1)
[1715914950.739350] info | ProxyClient.cpp | create_datareader | datareader created | client_key: 0x5B0F1BBE, datareader_id: 0x000(6), subscriber_id: 0x000(4)LiDAR
RpLIDAR
ROS 2 package https://github.com/babakhani/rplidar_ros2
LD06 LIDAR
ROS 2 package https://github.com/linorobot/ldlidar
IMU wt61c ttl
https://www.aliexpress.com/item/1005002977858846.html
ROS 2 package https://github.com/ElettraSciComp/witmotion_IMU_ros/tree/ros2
To build, this package is needed to install
sudo apt install libqt6serialbus6-dev
Microros agent to communicate with OpenCR
ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyACM0 -v6
ekf.yaml
ekf_filter_node:
ros__parameters:
frequency: 30.0
two_d_mode: true
publish_tf: true
map_frame: map
odom_frame: odom
base_link_frame: base_footprint
world_frame: odom
#x , y , z,
#roll , pitch , yaw,
#vx , vy , vz,
#vroll , vpitch, vyaw,
#ax , ay , az
odom0: odom/unfiltered
odom0_config: [true, true, false,
false, false, false,
false, false, false,
false, false, true,
false, false, false]
odom0_differential: true
odom0_relative: false
imu0: imu/data
imu0_config: [false, false, false,
false, false, true,
false, false, false,
false, false, true,
false, false, false]
imu0_differential: false
imu0_relative: true
imu0_queue_size: 2
process_noise_covariance: [0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015]
initial_estimate_covariance: [1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9]
Check topic publishing rate
pi@pi-desktop:~$ ros2 topic hz /odom/unfiltered
average rate: 48.074
min: 0.019s max: 0.025s std dev: 0.00124s window: 50
average rate: 48.147
min: 0.019s max: 0.025s std dev: 0.00117s window: 99
average rate: 48.082
min: 0.019s max: 0.025s std dev: 0.00111s window: 147
- install IMU : witmotion : witmotion package
- install movebase controller: openCR : microros agent and microros Arduino
- intall EKF robot localization: --- : sudo apt install ros-humble-robot-localization
bringup.py
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from launch_ros.actions import Node
import os
def generate_launch_description():
config_witmotion = os.path.join(get_package_share_directory('witmotion_ros'),'config', 'wt61c.yml')
ekf_config_path = '/home/pi/amr_config/ekf.yaml'
return LaunchDescription([
Node(
package='micro_ros_agent',
executable='micro_ros_agent',
name='micro_ros_agent',
arguments=["serial", "--dev", "/dev/ttyACM0", "-v6"]
),
Node(
package = 'witmotion_ros',
executable = 'witmotion_ros_node',
parameters = [config_witmotion]
),
Node(
package='robot_localization',
executable='ekf_node',
name='ekf_filter_node',
output='screen',
parameters=[
ekf_config_path
],
remappings=[("odometry/filtered", "odom")]
),
])
eru.urdf
<?xml version="1.0" ?>
<robot name="turtlebot3_burger" xmlns:xacro="http://ros.org/wiki/xacro">
<link name="base_footprint"/>
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.020" rpy="0 0 0"/>
</joint>
<link name="base_link">
</link>
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
<origin xyz="-0.007 0 0.05" rpy="0 0 0"/>
</joint>
<link name="imu_link"/>
<joint name="scan_joint" type="fixed">
<parent link="base_link"/>
<child link="base_scan"/>
<origin xyz="-0.04 0 0.095" rpy="0 0 0"/>
</joint>
<link name="base_scan">
</link>
<joint name="wheel_left_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_left_link"/>
<origin xyz="0.0 0.08 0.023" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="wheel_left_link">
</link>
<joint name="wheel_right_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_right_link"/>
<origin xyz="0.0 -0.080 0.023" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="wheel_right_link">
</link>
<joint name="caster_back_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_back_link"/>
<origin xyz="-0.081 0 -0.004" rpy="-1.57 0 0"/>
</joint>
<link name="caster_back_link">
</link>
</robot>Static TF publisher launch file
#!/usr/bin/env python3
#
# Copyright 2019 ROBOTIS CO., LTD.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# Authors: Darby Lim
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time', default='false')
urdf = '/home/pi/amr_config/eru.urdf'
# Major refactor of the robot_state_publisher
# Reference page: https://github.com/ros2/demos/pull/426
with open(urdf, 'r') as infp:
robot_desc = infp.read()
rsp_params = {'robot_description': robot_desc}
# print (robot_desc) # Printing urdf information.
return LaunchDescription([
DeclareLaunchArgument(
'use_sim_time',
default_value='false',
description='Use simulation (Gazebo) clock if true'),
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[rsp_params, {'use_sim_time': use_sim_time}])
])Start publish static TF
pi@pi-desktop:~$ ros2 launch state_publisher.py
package: slam_toolbox
launch file: online_async_launch.py
parameters:
'use_sim_time': LaunchConfiguration("sim"),
slam_param_name: slam_config_path
Installation
sudo apt install ros-humble-slam-toolbox
Save a map file
cd linorobot2/linorobot2_navigation/maps
ros2 run nav2_map_server map_saver_cli -f <map_name> --ros-args -p save_map_timeout:=10000.
# Copyright (c) 2021 Juan Miguel Jimeno
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http:#www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import os
from launch import LaunchDescription
from launch import LaunchContext
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.conditions import IfCondition
from launch.substitutions import EnvironmentVariable
from launch_ros.substitutions import FindPackageShare
from launch_ros.actions import Node
def generate_launch_description():
slam_launch_path = PathJoinSubstitution(
[FindPackageShare('slam_toolbox'), 'launch', 'online_async_launch.py']
)
slam_config_path = PathJoinSubstitution(
[FindPackageShare('linorobot2_navigation'), 'config', 'slam.yaml']
)
rviz_config_path = PathJoinSubstitution(
[FindPackageShare('linorobot2_navigation'), 'rviz', 'linorobot2_slam.rviz']
)
lc = LaunchContext()
ros_distro = EnvironmentVariable('ROS_DISTRO')
slam_param_name = 'slam_params_file'
if ros_distro.perform(lc) == 'foxy':
slam_param_name = 'params_file'
return LaunchDescription([
DeclareLaunchArgument(
name='sim',
default_value='false',
description='Enable use_sime_time to true'
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(slam_launch_path),
launch_arguments={
'use_sim_time': LaunchConfiguration("sim"),
slam_param_name: slam_config_path
}.items()
),
])ros2 launch slam_async.py
ros2 launch navigation.py
package: nav2_bringup
launch file: bringup_launch.py
parameters:
map: LaunchConfiguration("map"),
use_sim_time': LaunchConfiguration("sim"),
params_file': nav2_config_path
launch file snippet:
# Copyright (c) 2021 Juan Miguel Jimeno
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http:#www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.conditions import IfCondition
from launch_ros.substitutions import FindPackageShare
from launch_ros.actions import Node
def generate_launch_description():
nav2_launch_path = PathJoinSubstitution(
[FindPackageShare('nav2_bringup'), 'launch', 'bringup_launch.py']
)
#default_map_path = '/home/pi/amr_config/maps/myOfficeDesk.yaml'
default_map_path = '/home/pi/amr_config/maps/house1.yaml'
nav2_config_path = '/home/pi/amr_config/navigation.yaml'
return LaunchDescription([
DeclareLaunchArgument(
name='sim',
default_value='false',
description='Enable use_sime_time to true'
),
DeclareLaunchArgument(
name='map',
default_value=default_map_path,
description='Navigation map path'
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(nav2_launch_path),
launch_arguments={
'map': LaunchConfiguration("map"),
'use_sim_time': LaunchConfiguration("sim"),
'params_file': nav2_config_path
}.items()
)
])Action Stops at Each Point Smoothness Primary Use Case Action Type FollowWaypoints Yes Sequential Patrols, predefined stops nav2_msgs/action/FollowWaypoints FollowPath No Smooth continuous Follow a trajectory or path nav2_msgs/action/FollowPath NavigateThroughPoses Optional Flexible (adaptive) Navigate through multiple poses nav2_msgs/action/NavigateThroughPoses