https://cyberbotics.com/
sudo apt-get install ros-iron-webots-ros2
$ export WEBOTS_HOME=/mnt/c/Program\ Files/Webots
$ ros2 launch webots_ros2_universal_robot multirobot_launch.py
Webot 예제 실행
$ ros2 topic list
$ ros2 service list
$ ros2 action list
이때, waiting for connection, retrying for another ? seconds 등의 메세지가 출력되며 로봇이 움직이지 않는 경우가 있으며, 이는 본 포스팅 작성일 기준 windows 11의 최신 빌드에서 발생하는 것으로 보임
이러한 문제는 wsl 버전을 2.1.5로 낮춰주면 해결됨. 링크에서 2.1.5 버전의 .msi 파일을 받아 실행
새로운 프로젝트 생성
좌측 상단 "File-New-New Project Directory"
계속 Next 선택 및, "world settings" 단계에서 프로젝트 이름과 체크박스 확인
기본 뷰포트 조작법:
시뮬레이터 창의 왼쪽, 객체들이 나열된 창을 scene tree라고 함
Webots 첫 실행 시, 시뮬레이션이 이미 시작되어 시간이 흐르고 있는 상태임
해당 시뮬레이션 환경에 어떠한 객체를 추가하기 위하여 우선 시뮬레이션을 정지하고, 초기 시간으로 되돌려야함(아래 그림과 같이 수행)
시뮬레이션 정지 및 초기화
뷰포트 설정
새로운 객체(노드) 생성
Webots에서는 각 객체를 노드(node)라고 부름: 객체 뿐만 아니라, 회전 시스템, 조명 등도 노드로 이루어져 있음
좌측 상단 + 버튼을 통해 새로운 노드 생성 가능
Base nodes: 새로운 노드를 만들고 싶을 때(본인이 원하는 로봇 모델을 직접 구현하고 싶을 때 사용)
PROTO nodes: webot에서 미리 만들어놓은 노드들
새로운 구체 객체 생성
생성과정 요약
새로운 구체 객체 생성:
구체 객체의 물리적 특성 추가:
PROTO 노드 추가(webot이 제공하는 로봇 모델)
이륜 이동 로봇 구조
실린더 모양의 로봇 바디가 생성되었고, 물리적 특성 추가를 위한 bounding(하얀색 선)이 청색 실린더와 일치하는 것을 확인
완성된 이륜 이동 로봇
$ ros2 pkg create --build-type ament_python --license Apache-2.0 --node-name my_robot_driver my_package --dependencies rclpy geometry_msgs webots_ros2_driver
$ cd my_package
$ mkdir launch
$ mkdir worlds
~/my_ws/src/my_package/worlds/ 디렉토리 내에 저장$ code ~/my_ws/src/my_package/my_package/my_robot_driver.py
import rclpy
from geometry_msgs.msg import Twist
HALF_DISTANCE_BETWEEN_WHEELS = 0.045
WHEEL_RADIUS = 0.025
class MyRobotDriver:
# 생성자에서 항상 2개의 인자를 받음
# webots_node: webots 시뮬레이터의 instance에 대한 reference
# properties: URDF파일에서 주어진 XML 태그로부터 생성된 dictionary. 이를 이용하여 여러 파라미터를 controller에 전달 할 수 있음
def init(self, webots_node, properties):
self.__robot = webots_node.robot
self.__left_motor = self.__robot.getDevice('left wheel motor')
self.__right_motor = self.__robot.getDevice('right wheel motor')
self.__left_motor.setPosition(float('inf'))
self.__left_motor.setVelocity(0)
self.__right_motor.setPosition(float('inf'))
self.__right_motor.setVelocity(0)
self.__target_twist = Twist()
rclpy.init(args=None)
self.__node = rclpy.create_node('my_robot_driver')
self.__node.create_subscription(Twist, 'cmd_vel', self.__cmd_vel_callback, 1)
def __cmd_vel_callback(self, twist):
self.__target_twist = twist
def step(self):
rclpy.spin_once(self.__node, timeout_sec=0)
forward_speed = self.__target_twist.linear.x
angular_speed = self.__target_twist.angular.z
command_motor_left = (forward_speed - angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS
command_motor_right = (forward_speed + angular_speed * HALF_DISTANCE_BETWEEN_WHEELS) / WHEEL_RADIUS
self.__left_motor.setVelocity(command_motor_left)
self.__right_motor.setVelocity(command_motor_right)
$ code ~/my_ws/src/my_package/resource/my_robot.urdf
<?xml version="1.0" ?>
<robot name="My robot">
<webots>
<plugin type="my_package.my_robot_driver.MyRobotDriver" />
</webots>
</robot>
$ code ~/my_ws/src/my_package/launch/robot_launch.py
import os
import launch
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.webots_launcher import WebotsLauncher
from webots_ros2_driver.webots_controller import WebotsController
def generate_launch_description():
package_dir = get_package_share_directory('my_package')
robot_description_path = os.path.join(package_dir, 'resource', 'my_robot.urdf')
webots = WebotsLauncher(
world=os.path.join(package_dir, 'worlds', 'my_world.wbt')
)
my_robot_driver = WebotsController(
robot_name='my_robot',
parameters=[
{'robot_description': robot_description_path},
]
)
return LaunchDescription([
webots,
my_robot_driver,
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
)
)
])
$ code ~/my_ws/src/my_package/setup.py
from setuptools import find_packages, setup
package_name = 'my_package'
data_files = []
data_files.append(('share/ament_index/resource_index/packages', ['resource/' + package_name]))
data_files.append(('share/' + package_name + '/launch', ['launch/robot_launch.py']))
data_files.append(('share/' + package_name + '/worlds', ['worlds/my_world.wbt']))
data_files.append(('share/' + package_name + '/resource', ['resource/my_robot.urdf']))
data_files.append(('share/' + package_name, ['package.xml']))
setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=data_files,
install_requires=['setuptools'],
zip_safe=True,
maintainer='user',
maintainer_email='user.name@mail.com',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'my_robot_driver = my_package.my_robot_driver:main',
],
},
)
$ cd ~/my_ws --symlink-install
$ colcon build
$ source install/local_setup.bash
$ ros2 launch my_package robot_launch.py
$ ros2 topic pub /cmd_vel geometry_msgs/Twist "linear: { x: 0.1 }"
로봇에 추가된 거리 센서
센서 생성 예시
$ code ~/my_ws/src/my_package/my_package/obstacle_avoider.py
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Range
from geometry_msgs.msg import Twist
MAX_RANGE = 0.15
class ObstacleAvoider(Node):
def __init__(self):
super().__init__('obstacle_avoider')
self.__publisher = self.create_publisher(Twist, 'cmd_vel', 1)
self.create_subscription(Range, 'left_sensor', self.__left_sensor_callback, 1)
self.create_subscription(Range, 'right_sensor', self.__right_sensor_callback, 1)
def __left_sensor_callback(self, message):
self.__left_sensor_value = message.range
def __right_sensor_callback(self, message):
self.__right_sensor_value = message.range
command_message = Twist()
command_message.linear.x = 0.1
if self.__left_sensor_value < 0.9 * MAX_RANGE or self.__right_sensor_value < 0.9 * MAX_RANGE:
command_message.angular.z = -2.0
self.__publisher.publish(command_message)
def main(args=None):
rclpy.init(args=args)
avoider = ObstacleAvoider()
rclpy.spin(avoider)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
avoider.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
$ code ~/my_ws/src/my_package/resource/my_robot.urdf
<?xml version="1.0" ?>
<robot name="My robot">
<webots>
<device reference="ds0" type="DistanceSensor">
<ros>
<topicName>/left_sensor</topicName>
<alwaysOn>true</alwaysOn>
</ros>
</device>
<device reference="ds1" type="DistanceSensor">
<ros>
<topicName>/right_sensor</topicName>
<alwaysOn>true</alwaysOn>
</ros>
</device>
<plugin type="my_package.my_robot_driver.MyRobotDriver" />
</webots>
</robot>
$ code ~/my_ws/src/my_package/launch/robot_launch.py
import os
import launch
from launch_ros.actions import Node
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.webots_launcher import WebotsLauncher
from webots_ros2_driver.webots_controller import WebotsController
def generate_launch_description():
package_dir = get_package_share_directory('my_package')
robot_description_path = os.path.join(package_dir, 'resource', 'my_robot.urdf')
webots = WebotsLauncher(
world=os.path.join(package_dir, 'worlds', 'my_world.wbt')
)
my_robot_driver = WebotsController(
robot_name='my_robot',
parameters=[
{'robot_description': robot_description_path},
]
)
obstacle_avoider = Node(
package='my_package',
executable='obstacle_avoider',
)
return LaunchDescription([
webots,
my_robot_driver,
obstacle_avoider,
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
)
)
])
$ code ~/my_ws/src/my_package/setup.py
'console_scripts': [
'my_robot_driver = my_package.my_robot_driver:main',
'obstacle_avoider = my_package.obstacle_avoider:main'
],
$ colcon build --simlink-install
$ source install/local_setup.bash
$ ros2 launch my_package robot_launch.py
$ rviz2
./bashrc 아래에 추가export LIBGL_ALWAYS_INDIRECT=0
export LIBGL_ALWAYS_SOFTWARE=1