입문 로봇 프로그래밍 튜토리얼
게시 됨: 2022-03-11그것을 직시하자, 로봇은 멋지다. 그들은 또한 언젠가는 세계를 운영할 것이며, 그 때 그들은 불쌍한 연약한 살덩이 제작자(로봇 개발자라고도 함)를 불쌍히 여겨 우리가 풍요로운 우주 유토피아를 건설하는 데 도움을 주기를 바랍니다. 물론 농담이지만 일종의 농담입니다.
이 문제에 작은 영향을 미치고 싶은 야망에서 저는 작년에 자율 로봇 제어 이론 과정을 수강했습니다. 이 과정에서 저는 Python 기반 로봇 시뮬레이터를 구축하여 단순하고 모바일이며 프로그래밍 가능한 로봇에서 제어 이론을 연습할 수 있었습니다. .
이 기사에서는 Python 로봇 프레임워크를 사용하여 제어 소프트웨어를 개발하고, 내가 시뮬레이션한 로봇을 위해 개발한 제어 체계를 설명하고, 환경과 상호 작용하고 목표를 달성하는 방법을 설명하고, 몇 가지를 논의할 것입니다. 그 과정에서 만난 로봇 공학 프로그래밍의 근본적인 문제.
초보자를 위한 로봇 프로그래밍에 대한 이 튜토리얼을 따르려면 다음 두 가지에 대한 기본 지식이 있어야 합니다.
- 수학 - 몇 가지 삼각 함수와 벡터를 사용할 것입니다.
- Python—Python은 가장 인기 있는 기본 로봇 프로그래밍 언어 중 하나이기 때문에 기본 Python 라이브러리와 함수를 사용할 것입니다.
여기에 표시된 코드 조각은 클래스와 인터페이스에 의존하는 전체 시뮬레이터의 일부일 뿐입니다. 따라서 코드를 직접 읽으려면 Python 및 객체 지향 프로그래밍에 대한 약간의 경험이 필요할 수 있습니다.
마지막으로, 이 튜토리얼을 더 잘 이해하는 데 도움이 되는 선택적 주제는 상태 머신이 무엇인지, 범위 센서와 인코더가 작동하는 방식을 아는 것입니다.
프로그래밍 가능한 로봇의 과제: 인식 대 현실, 그리고 제어의 취약성
모든 로봇의 근본적인 도전은 이것이다. 환경의 진정한 상태를 아는 것은 불가능하다. 로봇 제어 소프트웨어는 센서에서 반환된 측정값을 기반으로 현실 세계의 상태만 추측할 수 있습니다. 제어 신호 생성을 통해서만 현실 세계의 상태를 변경하려고 시도할 수 있습니다.
따라서 제어 설계의 첫 번째 단계 중 하나는 센서 판독값을 해석하고 결정을 내리는 데 사용할 모델 이라는 실제 세계의 추상화를 제시하는 것입니다. 현실 세계가 모델의 가정에 따라 행동하는 한 우리는 좋은 추측을 하고 통제력을 행사할 수 있습니다. 그러나 현실 세계가 이러한 가정에서 벗어나는 즉시 우리는 더 이상 정확한 추측을 할 수 없으며 통제력을 잃게 됩니다. 종종 통제력은 한 번 상실되면 결코 회복할 수 없습니다. (어떤 자비로운 외부 세력이 그것을 복구하지 않는 한.)
이것이 로봇 프로그래밍이 어려운 주요 이유 중 하나입니다. 우리는 종종 실험실에서 손재주, 탐색 또는 팀워크의 환상적인 위업을 수행하는 최신 연구 로봇의 비디오를 보고 "이것이 실제 세계에서 사용되지 않는 이유는 무엇입니까?"라고 묻고 싶은 유혹을 받습니다. 음, 다음에 그런 비디오를 보게 되면 실험실 환경이 얼마나 통제가 잘 되는지 한 번 보세요. 대부분의 경우 이러한 로봇은 환경 조건이 내부 모델의 좁은 범위 내에서 유지되는 한 이러한 인상적인 작업을 수행할 수 있습니다. 따라서 로봇 기술 발전의 한 가지 핵심은 보다 복잡하고 유연하며 강력한 모델의 개발이며, 이러한 발전은 사용 가능한 계산 리소스의 한계에 따라 달라질 수 있습니다.
[참고: 철학자와 심리학자 모두 생명체도 감각이 말하는 내용에 대한 자신의 내부 인식에 의존하는 것으로 고통받고 있다는 점에 주목합니다. 로봇 공학의 많은 발전은 생물을 관찰하고 예상치 못한 자극에 생물이 어떻게 반응하는지 보는 데서 비롯됩니다. 그것에 대해 생각해보십시오. 세계의 내부 모델은 무엇입니까? 개미랑 물고기랑 달라? (바라건대.) 그러나 개미와 물고기처럼 세상의 일부 현실을 지나치게 단순화할 가능성이 있습니다. 세상에 대한 당신의 가정이 정확하지 않을 때, 당신은 사물에 대한 통제력을 잃을 위험이 있습니다. 때때로 우리는 이것을 "위험"이라고 부릅니다. 우리의 작은 로봇이 미지의 세계에 맞서 살아남기 위해 고군분투하는 것과 마찬가지로 우리 모두도 마찬가지입니다. 이것은 로봇 공학자들에게 강력한 통찰력입니다.]
프로그래밍 가능한 로봇 시뮬레이터
내가 만든 시뮬레이터는 Python으로 작성되었으며 매우 영리하게 Sobot Rimulator 라고 불립니다. GitHub에서 v1.0.0을 찾을 수 있습니다. 그것은 많은 종소리와 휘파람을 가지고 있지 않지만 한 가지를 매우 잘 수행하도록 제작되었습니다. 모바일 로봇의 정확한 시뮬레이션을 제공하고 야심 찬 로봇 학자에게 로봇 소프트웨어 프로그래밍을 연습하기위한 간단한 프레임 워크를 제공합니다. 실제 로봇을 가지고 노는 것이 항상 더 좋지만 좋은 Python 로봇 시뮬레이터는 훨씬 더 접근하기 쉽고 시작하기에 좋은 곳입니다.
실제 로봇에서 제어 신호를 생성하는 소프트웨어("컨트롤러")는 매우 빠른 속도로 실행되고 복잡한 계산을 수행하는 데 필요합니다. 이것은 어떤 로봇 프로그래밍 언어를 사용하는 것이 가장 좋은지 선택에 영향을 줍니다. 일반적으로 C++는 이러한 종류의 시나리오에 사용되지만 더 간단한 로봇 공학 응용 프로그램에서 Python은 실행 속도와 개발 및 테스트의 용이함 사이에서 매우 좋은 절충안입니다.
내가 작성한 소프트웨어는 Khepera라는 실제 연구 로봇을 시뮬레이션하지만 다른 치수와 센서를 가진 다양한 모바일 로봇에 적용할 수 있습니다. 시뮬레이터를 실제 로봇의 기능과 최대한 비슷하게 프로그래밍하려고 했기 때문에 최소한의 리팩토링으로 제어 로직을 실제 Khepera 로봇에 로드할 수 있으며 시뮬레이션된 로봇과 동일한 성능을 보일 것입니다. 구현된 특정 기능은 Khepera III를 참조하지만 새로운 Khepera IV에 쉽게 적용할 수 있습니다.
즉, 시뮬레이션 로봇을 프로그래밍하는 것은 실제 로봇을 프로그래밍하는 것과 유사합니다. 시뮬레이터가 다른 제어 소프트웨어 접근 방식을 개발하고 평가하는 데 사용되는 경우 이는 중요합니다.
이 튜토리얼에서는 Sobot Rimulator v1.0.0과 함께 제공되는 로봇 제어 소프트웨어 아키텍처를 설명하고 Python 소스의 스니펫을 제공합니다(명확성을 위해 약간 수정함). 그러나 소스에 들어가서 엉망으로 만드는 것이 좋습니다. 시뮬레이터는 포크되어 iRobot의 Roomba2를 비롯한 다양한 모바일 로봇을 제어하는 데 사용되었습니다. 마찬가지로 프로젝트를 포크하고 개선하십시오.
로봇의 제어 논리는 다음 Python 클래스/파일로 제한됩니다.
-
models/supervisor.py
—이 클래스는 로봇 주변의 시뮬레이션된 세계와 로봇 자체 간의 상호 작용을 담당합니다. 이는 로봇 상태 머신을 발전시키고 원하는 동작을 계산하기 위해 컨트롤러를 트리거합니다. -
models/supervisor_state_machine.py
— 이 클래스는 센서의 해석에 따라 로봇이 있을 수 있는 다양한 상태 를 나타냅니다. -
models/controllers
디렉토리의 파일 - 이 클래스는 알려진 환경 상태에서 로봇의 다양한 동작을 구현합니다. 특히 상태 머신에 따라 특정 컨트롤러가 선택됩니다.
목표
로봇도 사람과 마찬가지로 삶의 목적이 필요합니다. 이 로봇을 제어하는 소프트웨어의 목표는 매우 간단합니다. 미리 결정된 목표 지점에 도달하려고 시도하는 것입니다. 이것은 일반적으로 자율주행차에서 로봇 청소기에 이르기까지 모든 이동 로봇이 갖추어야 할 기본 기능입니다. 목표 좌표는 로봇이 활성화되기 전에 제어 소프트웨어에 프로그래밍되지만 로봇 움직임을 감독하는 추가 Python 응용 프로그램에서 생성될 수 있습니다. 예를 들어 여러 웨이포인트를 통과하는 운전을 생각해 보십시오.
그러나 문제를 복잡하게 만드는 것은 로봇의 환경이 장애물로 뒤덮일 수 있다는 것입니다. 로봇은 목표를 향해 가는 도중에 장애물과 충돌하면 안 됩니다. 따라서 로봇이 장애물을 만나면 목표를 향해 계속 나아갈 수 있도록 길을 찾아야 합니다.
프로그래밍 가능한 로봇
모든 로봇에는 다양한 기능과 제어 문제가 있습니다. 시뮬레이션된 프로그래밍 가능 로봇에 대해 알아봅시다.
가장 먼저 주목해야 할 점은 이 가이드에서 우리 로봇이 자율 이동 로봇 이 될 것이라는 점입니다. 이것은 그것이 공간에서 자유롭게 움직일 것이며 자신의 통제하에 움직일 것임을 의미합니다. 이것은 원격 제어 로봇(자율이 아님) 또는 공장 로봇 팔(이동이 아님)과 대조됩니다. 로봇은 목표를 달성하고 환경에서 생존하는 방법을 스스로 파악해야 합니다. 이것은 초보 로봇 공학 프로그래머에게 놀랍도록 어려운 도전임이 입증되었습니다.
제어 입력: 센서
로봇이 환경을 모니터링하기 위해 장착할 수 있는 다양한 방법이 있습니다. 여기에는 근접 센서, 광 센서, 범퍼, 카메라 등이 포함될 수 있습니다. 또한 로봇은 스스로 직접 관찰할 수 없는 정보를 제공하는 외부 센서와 통신할 수 있습니다.
우리의 기준 로봇에는 9개의 적외선 센서 가 장착되어 있습니다. 최신 모델에는 8개의 적외선과 5개의 초음파 근접 센서가 모든 방향으로 "스커트"에 배열되어 있습니다. 로봇이 뒤에 있는 것보다 앞에 있는 것을 아는 것이 일반적으로 더 중요하기 때문에 로봇의 앞면을 향하는 센서가 뒷면보다 많습니다.
로봇에는 근접 센서 외에도 휠 움직임을 추적하는 한 쌍의 휠 티커 가 있습니다. 이를 통해 각 바퀴가 얼마나 많은 회전을 하는지 추적할 수 있으며 바퀴를 한 바퀴 앞으로 완전히 돌리면 2,765틱이 됩니다. 반대 방향으로 돌리면 틱 카운트가 증가하는 대신 감소합니다. 우리가 작성할 소프트웨어는 미터로 표시된 이동 거리를 사용하기 때문에 이 튜토리얼에서 특정 숫자에 대해 걱정할 필요가 없습니다. 나중에 쉬운 Python 함수로 틱에서 계산하는 방법을 보여 드리겠습니다.
제어 출력: 이동성
일부 로봇은 다리로 움직입니다. 일부는 공처럼 굴러갑니다. 일부는 뱀처럼 미끄러지기도 합니다.
우리 로봇은 차동 구동 로봇으로 두 바퀴로 굴러갑니다. 두 바퀴가 같은 속도로 회전하면 로봇이 직선으로 움직입니다. 바퀴가 다른 속도로 움직이면 로봇이 회전합니다. 따라서 이 로봇의 움직임을 제어하는 것은 이 두 바퀴 각각이 회전하는 속도를 적절하게 제어하는 것으로 귀결됩니다.
API
Sobot Rimulator에서 로봇 "컴퓨터"와 (시뮬레이션된) 물리적 세계 사이의 분리는 "실제 로봇" 센서 및 모터와 상호 작용하기 위한 전체 API를 정의하는 robot_supervisor_interface.py
파일에 의해 구현됩니다.
-
read_proximity_sensors()
는 센서의 기본 형식으로 9개 값의 배열을 반환합니다. -
read_wheel_encoders()
는 시작 이후 총 틱을 나타내는 두 값의 배열을 반환합니다. -
set_wheel_drive_rates( v_l, v_r )
는 두 개의 값(초당 라디안 단위)을 사용하고 바퀴의 왼쪽 및 오른쪽 속도를 이 두 값으로 설정합니다.
이 인터페이스는 내부적으로 센서의 데이터와 모터나 바퀴를 움직일 수 있는 가능성을 제공하는 로봇 개체를 사용합니다. 다른 로봇을 만들고 싶다면 동일한 인터페이스에서 사용할 수 있는 다른 Python 로봇 클래스를 제공하기만 하면 됩니다. 그러면 나머지 코드(컨트롤러, 감독자 및 시뮬레이터)는 즉시 사용할 수 있습니다!
시뮬레이터
관련된 물리학 법칙에 너무 많은 관심을 기울이지 않고 실제 세계에서 실제 로봇을 사용하는 것처럼 로봇이 시뮬레이션되는 방식을 무시하고 컨트롤러 소프트웨어가 프로그래밍되는 방식으로 바로 건너뛸 수 있습니다. 현실 세계와 시뮬레이션 사이. 하지만 궁금하시다면 여기에서 간단히 소개하겠습니다.
world.py
파일은 내부에 로봇과 장애물이 있는 시뮬레이션된 세계를 나타내는 Python 클래스입니다. 이 클래스 내의 단계 함수는 다음과 같은 방법으로 간단한 세계를 발전시킵니다.
- 로봇의 움직임에 물리 법칙 적용하기
- 장애물과의 충돌 고려
- 로봇 센서의 새로운 가치 제공
결국 로봇 두뇌 소프트웨어 실행을 책임지는 로봇 감독자를 부른다.
step 함수는 robot.step_motion()
이 이전 시뮬레이션 단계에서 감독자가 계산한 휠 속도를 사용하여 로봇을 이동하도록 루프에서 실행됩니다.
# step the simulation through one time interval def step( self ): dt = self.dt # step all the robots for robot in self.robots: # step robot motion robot.step_motion( dt ) # apply physics interactions self.physics.apply_physics() # NOTE: The supervisors must run last to ensure they are observing the "current" world # step all of the supervisors for supervisor in self.supervisors: supervisor.step( dt ) # increment world time self.world_time += dt
apply_physics()
함수는 감독자가 현재 시뮬레이션 단계에서 환경을 추정할 수 있도록 로봇 근접 센서의 값을 내부적으로 업데이트합니다. 인코더에도 동일한 개념이 적용됩니다.
단순한 모델
첫째, 우리 로봇은 매우 간단한 모델을 가질 것입니다. 그것은 세상에 대해 많은 가정을 할 것입니다. 중요한 것 중 일부는 다음과 같습니다.
- 지형은 항상 평평하고 균일합니다.
- 장애물은 결코 둥글지 않다
- 바퀴는 절대 미끄러지지 않는다
- 아무것도 로봇을 이리저리 밀지 않을 것입니다
- 센서는 절대 고장나거나 잘못된 판독값을 제공하지 않습니다.
- 바퀴는 지시가 있을 때 항상 회전합니다.
이러한 가정의 대부분은 집과 같은 환경에서 합리적이지만 원형 장애물이 존재할 수 있습니다. 우리의 장애물 회피 소프트웨어는 구현이 간단하며 장애물을 우회하기 위해 장애물의 경계를 따릅니다. 원형 장애물을 피하기 위한 추가 점검으로 로봇의 제어 프레임워크를 개선하는 방법에 대해 독자들에게 힌트를 줄 것입니다.
제어 루프
이제 제어 소프트웨어의 핵심으로 들어가 로봇 내부에서 프로그래밍하려는 동작을 설명합니다. 이 프레임워크에 추가 동작을 추가할 수 있으며 읽기를 마친 후에 자신의 아이디어를 시도해야 합니다! 행동 기반 로봇 공학 소프트웨어는 20년 이상 전에 제안되었으며 여전히 모바일 로봇 공학을 위한 강력한 도구입니다. 예를 들어, 2007년에는 DARPA Urban Challenge(자율주행 자동차를 위한 첫 번째 경쟁)에서 일련의 행동이 사용되었습니다!
로봇은 동적 시스템입니다. 로봇의 상태, 센서 판독값, 제어 신호의 영향은 일정하게 유동적입니다. 이벤트가 진행되는 방식을 제어하는 데는 다음 세 단계가 포함됩니다.
- 제어 신호를 적용합니다.
- 결과를 측정합니다.
- 목표에 더 가까워지도록 계산된 새로운 제어 신호를 생성합니다.
이러한 단계는 목표를 달성할 때까지 계속 반복됩니다. 초당 이 작업을 수행할 수 있는 횟수가 많을수록 시스템을 더 세밀하게 제어할 수 있습니다. Sobot Rimulator 로봇은 이러한 단계를 초당 20회(20Hz) 반복하지만 많은 로봇은 적절한 제어를 위해 초당 수천 또는 수백만 번 이 단계를 반복해야 합니다. 다양한 로봇 시스템 및 속도 요구 사항에 대한 다양한 로봇 프로그래밍 언어에 대한 이전 소개를 기억하십시오.
일반적으로 로봇은 센서로 측정을 할 때마다 이러한 측정을 사용하여 세계 상태에 대한 내부 추정값(예: 목표로부터의 거리)을 업데이트합니다. 이 상태를 원하는 상태(거리의 경우 0이 되기를 원함)의 기준 값과 비교하여 원하는 상태와 실제 상태 사이의 오차를 계산합니다. 이 정보가 알려지면 새로운 제어 신호를 생성 하는 것은 오류를 최소화 하는 문제로 축소되어 궁극적으로 로봇이 목표를 향해 이동하게 됩니다.
멋진 트릭: 모델 단순화
프로그래밍하려는 로봇을 제어하려면 왼쪽 바퀴에 신호를 보내어 회전 속도를 알려주고 오른쪽 바퀴에 신호를 보내 회전 속도를 알려야 합니다. 이 신호를 v L 및 v R 이라고 합시다. 그러나 v L 과 v R 의 관점에서 끊임없이 생각하는 것은 매우 번거로운 일입니다. "왼쪽 바퀴가 얼마나 빨리 회전하기를 원하고 오른쪽 바퀴가 얼마나 빨리 회전하기를 원합니까?"라고 묻는 대신 "로봇이 앞으로 얼마나 빨리 움직이기를 원하고 얼마나 빨리 회전하거나 방향을 바꾸기를 원합니까?"라고 묻는 것이 더 자연스럽습니다. 이러한 매개변수를 속도 v 및 각(회전) 속도 ω ("오메가"로 읽음)라고 합시다. 전체 모델을 v L 및 v R 대신 v 및 ω 기반으로 할 수 있으며 프로그래밍된 로봇이 어떻게 움직이기를 원하는지 결정한 후에만 이 두 값을 수학적으로 필요한 v L 및 v R 로 변환할 수 있습니다. 실제로 로봇 바퀴를 제어합니다. 이것은 외발 자전거 제어 모델 로 알려져 있습니다.
다음은 supervisor.py
에서 최종 변환을 구현하는 Python 코드입니다. ω 가 0이면 두 바퀴가 같은 속도로 회전합니다.
# generate and send the correct commands to the robot def _send_robot_commands( self ): # ... v_l, v_r = self._uni_to_diff( v, omega ) self.robot.set_wheel_drive_rates( v_l, v_r ) def _uni_to_diff( self, v, omega ): # v = translational velocity (m/s) # omega = angular velocity (rad/s) R = self.robot_wheel_radius L = self.robot_wheel_base_length v_l = ( (2.0 * v) - (omega*L) ) / (2.0 * R) v_r = ( (2.0 * v) + (omega*L) ) / (2.0 * R) return v_l, v_r
상태 추정: 로봇, 너 자신을 알라
로봇은 센서를 사용하여 자신의 상태뿐 아니라 환경의 상태도 추정해야 합니다. 이 추정치는 결코 완벽할 수 없지만 로봇은 이러한 추정치를 기반으로 모든 결정을 내리기 때문에 상당히 양호해야 합니다. 근접 센서와 휠 티커만 사용하여 다음을 추측해야 합니다.
- 장애물 방향
- 장애물과의 거리
- 로봇의 위치
- 로봇의 표제
처음 두 속성은 근접 센서 판독값에 의해 결정되며 매우 간단합니다. API 함수 read_proximity_sensors()
는 각 센서에 대해 하나씩 9개 값의 배열을 반환합니다. 예를 들어 일곱 번째 판독값이 로봇의 오른쪽으로 75도를 가리키는 센서에 해당한다는 것을 미리 알고 있습니다.
따라서 이 값이 0.1미터 거리에 해당하는 판독값을 표시하면 왼쪽으로 75도, 0.1미터 떨어진 곳에 장애물이 있다는 것을 알 수 있습니다. 장애물이 없으면 센서는 최대 범위 0.2미터의 판독값을 반환합니다. 따라서 센서 7에서 0.2미터를 읽으면 실제로 그 방향에 장애물이 없다고 가정합니다.
적외선 센서가 작동하는 방식(적외선 반사 측정) 때문에 반환되는 숫자는 감지된 실제 거리의 비선형 변환입니다. 따라서 표시된 거리를 결정하기 위한 Python 함수는 이러한 판독값을 미터로 변환해야 합니다. 이것은 다음과 같이 supervisor.py
에서 수행됩니다.
# update the distances indicated by the proximity sensors def _update_proximity_sensor_distances( self ): self.proximity_sensor_distances = [ 0.02-( log(readval/3960.0) )/30.0 for readval in self.robot.read_proximity_sensors() ]
다시 말하지만, 이 Python 로봇 프레임워크에는 특정 센서 모델이 있지만 실제 세계에서 센서는 비선형 값에서 미터로 유사한 변환 기능을 제공해야 하는 소프트웨어와 함께 제공됩니다.
로봇의 위치와 방향을 결정하는 것(로봇 프로그래밍에서 포즈 로 통칭)은 다소 어렵습니다. 우리 로봇은 주행 거리 측정 을 사용하여 포즈를 추정합니다. 이것은 바퀴 티커가 들어오는 곳입니다. 제어 루프의 마지막 반복 이후로 각 바퀴가 얼마나 많이 회전했는지 측정함으로써 로봇의 자세가 어떻게 변했는지에 대한 좋은 추정치를 얻을 수 있습니다. 그러나 변화가 작은 경우에만 가능합니다 .
이것이 바퀴를 움직이는 모터가 완벽하지 않을 수 있는 실제 로봇에서 제어 루프를 매우 자주 반복하는 것이 중요한 이유 중 하나입니다. 휠 티커를 측정하기 위해 너무 오래 기다렸다면 두 휠 모두 꽤 많은 일을 할 수 있었고 우리가 어디에서 끝났는지 추정하는 것은 불가능할 것입니다.
현재 소프트웨어 시뮬레이터가 주어지면 컨트롤러와 동일한 주파수인 20Hz에서 주행 거리 계산을 실행할 수 있습니다. 그러나 티커의 작은 움직임을 포착하기 위해 더 빠르게 실행되는 별도의 Python 스레드를 갖는 것이 좋습니다.
다음은 로봇 포즈 추정을 업데이트하는 supervisor.py
의 전체 주행 거리 측정 기능입니다. 로봇의 포즈는 좌표 x
및 y
와 양의 X축에서 라디안으로 측정되는 헤딩 theta
로 구성됩니다. 양수 x
는 동쪽이고 양수 y
는 북쪽입니다. 따라서 헤딩이 0
로봇이 동쪽을 향하고 있음을 나타냅니다. 로봇은 항상 초기 포즈가 (0, 0), 0
이라고 가정합니다.
# update the estimated position of the robot using it's wheel encoder readings def _update_odometry( self ): R = self.robot_wheel_radius N = float( self.wheel_encoder_ticks_per_revolution ) # read the wheel encoder values ticks_left, ticks_right = self.robot.read_wheel_encoders() # get the difference in ticks since the last iteration d_ticks_left = ticks_left - self.prev_ticks_left d_ticks_right = ticks_right - self.prev_ticks_right # estimate the wheel movements d_left_wheel = 2*pi*R*( d_ticks_left / N ) d_right_wheel = 2*pi*R*( d_ticks_right / N ) d_center = 0.5 * ( d_left_wheel + d_right_wheel ) # calculate the new pose prev_x, prev_y, prev_theta = self.estimated_pose.scalar_unpack() new_x = prev_x + ( d_center * cos( prev_theta ) ) new_y = prev_y + ( d_center * sin( prev_theta ) ) new_theta = prev_theta + ( ( d_right_wheel - d_left_wheel ) / self.robot_wheel_base_length ) # update the pose estimate with the new values self.estimated_pose.scalar_update( new_x, new_y, new_theta ) # save the current tick count for the next iteration self.prev_ticks_left = ticks_left self.prev_ticks_right = ticks_right
이제 로봇이 실제 세계에 대한 적절한 추정치를 생성할 수 있으므로 이 정보를 사용하여 목표를 달성해 보겠습니다.

Python 로봇 프로그래밍 방법: Go-to-Goal 동작
이 프로그래밍 튜토리얼에서 우리의 작은 로봇이 존재하는 최고의 목적은 목표 지점에 도달하는 것입니다. 그렇다면 바퀴를 회전시켜 거기에 도달하게 하려면 어떻게 해야 할까요? 우리의 세계관을 조금 단순화하는 것부터 시작하고 그 길에 장애물이 없다고 가정합시다.
그러면 이것은 간단한 작업이 되며 Python으로 쉽게 프로그래밍할 수 있습니다. 목표를 향해 나아가면 우리는 거기에 도달할 것입니다. 주행 거리 측정 덕분에 현재 좌표와 방향이 무엇인지 알 수 있습니다. 우리는 또한 미리 프로그래밍되어 있기 때문에 목표의 좌표가 무엇인지 알고 있습니다. 따라서 약간의 선형 대수를 사용하여 go_to_goal_controller.py
에서와 같이 위치에서 목표까지의 벡터를 결정할 수 있습니다.
# return a go-to-goal heading vector in the robot's reference frame def calculate_gtg_heading_vector( self ): # get the inverse of the robot's pose robot_inv_pos, robot_inv_theta = self.supervisor.estimated_pose().inverse().vector_unpack() # calculate the goal vector in the robot's reference frame goal = self.supervisor.goal() goal = linalg.rotate_and_translate_vector( goal, robot_inv_theta, robot_inv_pos ) return goal
세계 좌표 가 아니라 로봇의 기준 좌표계에서 목표에 대한 벡터를 얻고 있다는 점에 유의하십시오. 목표가 로봇 기준 좌표계의 X축에 있으면 로봇 바로 앞에 있다는 의미입니다. 따라서 X축에서 이 벡터의 각도는 방향과 원하는 방향 간의 차이입니다. 즉, 현재 상태와 현재 상태가 원하는 것 사이의 오류 입니다. 따라서 방향과 목표 사이의 각도가 0으로 변경되도록 회전 속도 ω 를 조정 하려고 합니다. 오류를 최소화하려고 합니다.
# calculate the error terms theta_d = atan2( self.gtg_heading_vector[1], self.gtg_heading_vector[0] ) # calculate angular velocity omega = self.kP * theta_d
컨트롤러 Python 구현의 위 스니펫에서 self.kP
는 제어 이득입니다. 우리가 직면한 목표에서 얼마나 멀리 떨어져 있는지에 비례 하여 얼마나 빨리 회전하는지를 결정하는 계수입니다. 헤딩의 오류가 0
이면 회전율도 0
입니다. go_to_goal_controller.py
파일 내의 실제 Python 함수에서 단순한 비례 계수 대신 PID 컨트롤러를 사용했기 때문에 더 유사한 이득을 볼 수 있습니다.
이제 우리는 각속도 ω 를 얻었으므로 앞으로의 속도 v 를 어떻게 결정합니까? 좋은 일반적인 경험 법칙은 본능적으로 알고 있을 것입니다. 선회하지 않으면 전속력으로 전진할 수 있으며 선회 속도가 빠를수록 감속해야 합니다. 이것은 일반적으로 시스템을 안정적으로 유지하고 모델의 범위 내에서 작동하는 데 도움이 됩니다. 따라서 v 는 ω 의 함수입니다. go_to_goal_controller.py
에서 방정식은 다음과 같습니다.
# calculate translational velocity # velocity is v_max when omega is 0, # drops rapidly to zero as |omega| rises v = self.supervisor.v_max() / ( abs( omega ) + 1 )**0.5
이 공식을 자세히 설명하기 위한 제안은 0의 속도로 목표에 도달하기 위해 목표 근처에 있을 때 일반적으로 속도를 늦추는 것을 고려하는 것입니다. 이 공식은 어떻게 변할까요? v_max()
를 거리에 비례하는 것으로 어떻게든 교체하는 것을 포함해야 합니다. 좋습니다. 단일 제어 루프를 거의 완료했습니다. 남은 것은 이 두 개의 외발자전거 모델 매개변수를 차동 휠 속도로 변환하고 신호를 휠로 보내는 것뿐입니다. 다음은 장애물이 없는 go-to-goal 컨트롤러 아래의 로봇 궤적의 예입니다.
우리가 볼 수 있듯이 목표에 대한 벡터는 제어 계산의 기반이 되는 효과적인 참조입니다. 그것은 "우리가 가고 싶은 곳"의 내부 표현입니다. 앞으로 보게 되겠지만 go-to-goal과 다른 행동 사이의 유일한 주요 차이점은 목표를 향해 가는 것이 때때로 나쁜 생각이므로 다른 참조 벡터를 계산해야 한다는 것입니다.
Python 로봇 프로그래밍 방법: 장애물 회피 동작
그 방향에 장애물이 있을 때 목표를 향해 가는 것이 좋은 예입니다. 앞길을 막는 것 대신에 로봇이 그것들을 피하도록 하는 제어 법칙을 프로그래밍해 봅시다.
시나리오를 단순화하기 위해 이제 목표 지점을 완전히 잊어버리고 다음을 목표로 설정 합니다. 앞에 장애물이 없을 때 전진합니다. 장애물을 만나면 더 이상 우리 앞에 있지 않을 때까지 그 곳에서 돌아서십시오.
따라서 우리 앞에 장애물이 없을 때 우리는 참조 벡터가 단순히 앞으로 가리키기를 원합니다. 그러면 ω 는 0이 되고 v 는 최대 속도가 됩니다. 그러나 근접 센서로 장애물을 감지하는 즉시 참조 벡터가 장애물에서 멀어지는 방향을 가리켜야 합니다. 이것은 우리를 장애물로부터 멀어지게 하기 위해 ω 를 쏘아 올리게 하고, 우리가 그 과정에서 우연히 장애물에 부딪치지 않도록 하기 위해 v 를 떨어뜨릴 것입니다.
원하는 참조 벡터를 생성하는 깔끔한 방법은 9개의 근접 판독값을 벡터로 변환하고 가중치 합을 취하는 것입니다. 장애물이 감지되지 않으면 벡터가 대칭적으로 합산되어 원하는 대로 정면을 가리키는 참조 벡터가 생성됩니다. 그러나 예를 들어 오른쪽에 있는 센서가 장애물을 포착하면 합에 더 작은 벡터가 기여하고 결과는 왼쪽으로 이동하는 참조 벡터가 됩니다.
센서의 배치가 다른 일반 로봇의 경우 동일한 아이디어를 적용할 수 있지만 센서가 로봇의 앞과 뒤에서 대칭인 경우 가중치의 변경 및/또는 추가 주의가 필요할 수 있습니다. 가중치 합이 0이 될 수 있기 때문입니다. .
다음은 avoid_obstacles_controller.py
에서 이 작업을 수행하는 코드입니다.
# sensor gains (weights) self.sensor_gains = [ 1.0+( (0.4*abs(p.theta)) / pi ) for p in supervisor.proximity_sensor_placements() ] # ... # return an obstacle avoidance vector in the robot's reference frame # also returns vectors to detected obstacles in the robot's reference frame def calculate_ao_heading_vector( self ): # initialize vector obstacle_vectors = [ [ 0.0, 0.0 ] ] * len( self.proximity_sensor_placements ) ao_heading_vector = [ 0.0, 0.0 ] # get the distances indicated by the robot's sensor readings sensor_distances = self.supervisor.proximity_sensor_distances() # calculate the position of detected obstacles and find an avoidance vector robot_pos, robot_theta = self.supervisor.estimated_pose().vector_unpack() for i in range( len( sensor_distances ) ): # calculate the position of the obstacle sensor_pos, sensor_theta = self.proximity_sensor_placements[i].vector_unpack() vector = [ sensor_distances[i], 0.0 ] vector = linalg.rotate_and_translate_vector( vector, sensor_theta, sensor_pos ) obstacle_vectors[i] = vector # store the obstacle vectors in the robot's reference frame # accumulate the heading vector within the robot's reference frame ao_heading_vector = linalg.add( ao_heading_vector, linalg.scale( vector, self.sensor_gains[i] ) ) return ao_heading_vector, obstacle_vectors
결과 ao_heading_vector
를 로봇이 일치시키려는 참조로 사용하여 목표 지점을 완전히 무시하고 장애물 회피 컨트롤러만 사용하여 시뮬레이션에서 로봇 소프트웨어를 실행한 결과는 다음과 같습니다. 로봇은 목적 없이 이리저리 튀지만 장애물과 충돌하지 않으며 매우 협소한 공간도 탐색할 수 있습니다.
Python 로봇 프로그래밍 방법: Hybrid Automata(동작 상태 머신)
지금까지 우리는 목표 달성과 장애물 회피라는 두 가지 행동을 개별적으로 설명했습니다. 둘 다 훌륭하게 기능을 수행하지만 장애물로 가득 찬 환경에서 목표에 성공적으로 도달하려면 이들을 결합해야 합니다.
우리가 개발할 솔루션은 하이브리드 오토마타 라는 매우 멋진 이름을 가진 기계 클래스에 있습니다. 하이브리드 오토마톤은 감독 상태 머신뿐만 아니라 여러 가지 다른 동작 또는 모드로 프로그래밍됩니다. 감독 상태 머신은 개별 시간(목표가 달성되거나 환경이 갑자기 너무 많이 변한 경우)에 한 모드에서 다른 모드로 전환하는 반면, 각 동작은 센서와 휠을 사용하여 환경 변화에 지속적으로 반응합니다. 이 솔루션은 이산적이고 연속적인 방식으로 발전하기 때문에 하이브리드 라고 불렸습니다.
Python 로봇 프레임워크는 supervisor_state_machine.py
파일에서 상태 머신을 구현합니다.
두 가지 편리한 동작을 갖춘 간단한 논리가 자체 제안합니다. 장애물이 감지되지 않으면 목표 달성 동작을 사용합니다. 장애물이 감지되면 장애물이 더 이상 감지되지 않을 때까지 장애물 회피 동작으로 전환합니다.
그러나 밝혀진 바와 같이 이 논리는 많은 문제를 야기할 것입니다. 이 시스템이 장애물을 만났을 때 하려는 경향은 장애물에서 돌아서고, 장애물에서 멀어지자 마자 우회전하여 다시 장애물에 부딪치는 것입니다. 그 결과 로봇을 쓸모없게 만드는 빠른 전환의 끝없는 루프가 생성됩니다. In the worst case, the robot may switch between behaviors with every iteration of the control loop—a state known as a Zeno condition .
There are multiple solutions to this problem, and readers that are looking for deeper knowledge should check, for example, the DAMN software architecture.
What we need for our simple simulated robot is an easier solution: One more behavior specialized with the task of getting around an obstacle and reaching the other side.
Python Robot Programming Methods: Follow-Wall Behavior
Here's the idea: When we encounter an obstacle, take the two sensor readings that are closest to the obstacle and use them to estimate the surface of the obstacle. Then, simply set our reference vector to be parallel to this surface. Keep following this wall until A) the obstacle is no longer between us and the goal, and B) we are closer to the goal than we were when we started. Then we can be certain we have navigated the obstacle properly.
With our limited information, we can't say for certain whether it will be faster to go around the obstacle to the left or to the right. To make up our minds, we select the direction that will move us closer to the goal immediately. To figure out which way that is, we need to know the reference vectors of the go-to-goal behavior and the avoid-obstacle behavior, as well as both of the possible follow-wall reference vectors. Here is an illustration of how the final decision is made (in this case, the robot will choose to go left):
Determining the follow-wall reference vectors turns out to be a bit more involved than either the avoid-obstacle or go-to-goal reference vectors. Take a look at the Python code in follow_wall_controller.py
to see how it's done.
Final Control Design
The final control design uses the follow-wall behavior for almost all encounters with obstacles. However, if the robot finds itself in a tight spot, dangerously close to a collision, it will switch to pure avoid-obstacles mode until it is a safer distance away, and then return to follow-wall. Once obstacles have been successfully negotiated, the robot switches to go-to-goal. Here is the final state diagram, which is programmed inside the supervisor_state_machine.py
:
Here is the robot successfully navigating a crowded environment using this control scheme:
An additional feature of the state machine that you can try to implement is a way to avoid circular obstacles by switching to go-to-goal as soon as possible instead of following the obstacle border until the end (which does not exist for circular objects!)
Tweak, Tweak, Tweak: Trial and Error
The control scheme that comes with Sobot Rimulator is very finely tuned. It took many hours of tweaking one little variable here, and another equation there, to get it to work in a way I was satisfied with. Robotics programming often involves a great deal of plain old trial-and-error. Robots are very complex and there are few shortcuts to getting them to behave optimally in a robot simulator environment…at least, not much short of outright machine learning, but that's a whole other can of worms.
I encourage you to play with the control variables in Sobot Rimulator and observe and attempt to interpret the results. Changes to the following all have profound effects on the simulated robot's behavior:
- The error gain
kP
in each controller - The sensor gains used by the avoid-obstacles controller
- The calculation of v as a function of ω in each controller
- The obstacle standoff distance used by the follow-wall controller
- The switching conditions used by
supervisor_state_machine.py
- Pretty much anything else
When Programmable Robots Fail
We've done a lot of work to get to this point, and this robot seems pretty clever. Yet, if you run Sobot Rimulator through several randomized maps, it won't be long before you find one that this robot can't deal with. Sometimes it drives itself directly into tight corners and collides. Sometimes it just oscillates back and forth endlessly on the wrong side of an obstacle. Occasionally it is legitimately imprisoned with no possible path to the goal. After all of our testing and tweaking, sometimes we must come to the conclusion that the model we are working with just isn't up to the job, and we have to change the design or add functionality.
In the mobile robot universe, our little robot's “brain” is on the simpler end of the spectrum. Many of the failure cases it encounters could be overcome by adding some more advanced software to the mix. More advanced robots make use of techniques such as mapping , to remember where it's been and avoid trying the same things over and over; heuristics , to generate acceptable decisions when there is no perfect decision to be found; and machine learning , to more perfectly tune the various control parameters governing the robot's behavior.
A Sample of What's to Come
Robots are already doing so much for us, and they are only going to be doing more in the future. While even basic robotics programming is a tough field of study requiring great patience, it is also a fascinating and immensely rewarding one.
In this tutorial, we learned how to develop reactive control software for a robot using the high-level programming language Python. But there are many more advanced concepts that can be learned and tested quickly with a Python robot framework similar to the one we prototyped here. I hope you will consider getting involved in the shaping of things to come!
Acknowledgement: I would like to thank Dr. Magnus Egerstedt and Jean-Pierre de la Croix of the Georgia Institute of Technology for teaching me all this stuff, and for their enthusiasm for my work on Sobot Rimulator.