topic details & publisher manual (ERP42)

ERP42를 위한 /move_car topic의 상세 정보와 publish할 때 유의사항입니다.

세부사항 정리 도표

Float32MultiArray type인 /move_car topic의 index별 기능에 대한 도표입니다.

index

what

valid value

When you should use

0

car_type

0.0: Ioniq, 1.0: ERP42

reset code 제외 모든 모드

1

mode

원하는 mode 선택

0.0 : E-STOP

1.0 : 사용자 핸들 개입 Cruise Control

2.0 : Cruise Control with Steering

3.0 : Developer Mode (Dealing with Whatever)

4.0 : Cruise Control with Steering & Gear

5.0 : for nav_pilot (plz read FOR KASA)

6.0 : for mission manager (plz read FOR KASA)

reset code 제외 모든 모드

2

desired_speed

원하는 속도 (km/h)

mode 1.0, 2.0, 4.0, 5.0, 6.0

3

accel

pub하고싶은 direct accel값

0.0 <= val <= 200.0

mode 3.0

4

brake

pub하고싶은 direct brake값

0.0 <= val <= 200.0

mode 3.0

5

steer

pub하고싶은 steer 값

-2000.0 <= val <= 2000.0

+가 오른쪽 회전

-가 왼쪽 회전 (71로 나누면 degree가 된답니다.)

mode 2.0, 3.0, 4.0, 5.0, 6.0

6

gear

pub하고싶은 gear 값

gear_dict = {0:"Forward",1:"Neutral",2:"Backward"}

mode 3.0, 4.0, 5.0, 6.0

7

angular (Ioniq only)

Not used (Ioniq Only)

Not used (Ioniq Only)

8

status

(ERP42 only)

Not used directly

Not used directly

9

estop

(ERP42 only)

Not used directly

Not used directly

Data sturcture:

[car_type = 1.0(ERP42), mode, speed, accel, brake, steer, gear, 0.0, 0.0, 0.0]

len = 10, Input data type should be float!

세줄 요약

현재 ERP42를 위해 사용되는 index는 0,1,2,3,4,5,6이다.

reset을 제외하고, 0,1번째 index는 무조건 의미가 있는 index이고 나머지들은 mode별로 사용여부가 결정된다.

아래에 상술한다.

How to Publish topic

매우 간단한 ros2기반 publisher입니다. /move_car topic을 publish하는 과정만 확인해보세요.

import rclpy
from rclpy.node import Node
from std_msgs.msg import Float32MultiArray
from rclpy.qos import qos_profile_default

NODE_NAME = 'move_car_test'

class MinimalPublisher(Node):

    def __init__(self):
        super().__init__(NODE_NAME)
        self.publisher_ = self.create_publisher(Float32MultiArray, '/move_car',qos_profile_default)
        self.move_carmsg = Float32MultiArray()
        self.move_carmsg.data = [1.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0]
        timer_period = 0.1  # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)

    def timer_callback(self):
        self.publisher_.publish(self.move_carmsg)
        self.get_logger().info('Publishing: "%s"' % self.move_carmsg.data)


def main(args=None):
    rclpy.init(args=args)

    minimal_publisher = MinimalPublisher()

    rclpy.spin(minimal_publisher)

    # Destroy the node explicitly
    # (optional - otherwise it will be done automatically
    # when the garbage collector destroys the node object)
    minimal_publisher.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

위 파이썬 파일을 실행하면 rqt에서 아래와 같은 ros2 노드 그래프를 확인할 수 있다.

위 코드에서 핵심 부분은 line 12~ 14이다.

self.publisher_ = self.create_publisher(Float32MultiArray, '/move_car',qos_profile_default)
self.move_carmsg = Float32MultiArray()
self.move_carmsg.data = [1.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0]

위 코드는 ERP42E-Stop mode이다. 차량선택을 위한 0번째에 1.0을 입력하여 ERP42를 선택했고,

mode에 해당하는 1번째에 0.0을 입력하여 E-Stop mode가 선택되었다.

여기서, list의 불필요한 부분에 대한 불만과 굳이 float값으로만 채운 이유가 궁금할 것이다. 이와 더불어 위의 표에서 언급한 reset code도 혼란스러울 것이다. publish할 때의 유의사항을 종합하여 안내한다.

Publisher 유의사항 (필독!!!)

  1. reset code [119.0]

매우 특수한 case로, 안전을 위해 도입된 개념이다. 일단 E-Stop 모드가 한 번 들어오면, 탈출코드인 [119.0]이 들어올때까지 다른 모든 제어 코드를 무시한다. 그렇기에, 매우 강력하고 예외적인 코드이다.

2. list의 len은 무조건 10을 맞추고, 안에 들어가는 값은 float이 되어야한다!

reset코드([119.0])를 제외한 다른 모든 코드는 해당하는 인덱스의 값을 쓰지 않더라도, 0.0과 같은 쓰레기 float값으로 채워주어야한다.

그 이유는, 코드 상에서 reset 코드를 제외한 다른 모든 코드는 len이 10이 아닐경우에 이상한 토픽으로 보고, 실제 함수 동작을 아무것도 하지 않도록 설계했다.

Modes Details

위쪽 코드블럭에 등장했던, move_carmsg.data로 설명을 이어가겠다.

KASA 준비하는 사람들은 mode 0.0, 5.0, 6.0만 봐도 된다.

Data sturcture:
[car_type = 1.0(ERP42), mode, speed, accel, brake, steer, gear, 0.0, 0.0, 0.0]

len = 10, Input data type should be float!

mode 0.0 : E-Stop mode

python 예시 :

move_carmsg.data = [1.0, 0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0]

해석 >> ERP42에서 E_Stop한다.

reset code는 다음과 같다. move_carmsg.data = [119.0] 해석 >> ERP42에서 E_Stop한 뒤 탈출한다.

mode 1.0 : Cruise Control

python 예시 :

move_carmsg.data = [1.0,1.0,20.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0]

해석 >> ERP42에서 속도만 20km/h으로 cruise control을 한다.

일반 차량의 cruise mode라고 생각하면 됨.

mode 2.0 : Cruise Control with Steering

python 예시 :

move_carmsg.data = [1.0,2.0,20.0,0.0,0.0,200.0,0.0,0.0,0.0,0.0]

해석 >> ERP42에서 20km/h의 속도로 cruise control을 하며 steer를 200으로 pub한다.

mode 3.0 : Developer Mode (Dealing with Whatever)

python 예시 :

move_carmsg.data = [1.0, 3.0,0.0,180.0, 0.0, 200.0, 0.0,0.0,0.0,0.0]

해석 >> ERP42에서 accel에 direct로 180.0의 값을 입력하고, break에는 direct로 0.0의 값을 입력, steer는 200.0, gear는 driving에 해당하는 0.0을 입력한다.

cmd_node를 통한 직접적인 통신방식이라고 생각하면 된다. 다른 코드들은 속도를 입력하여 해당속도가 되게끔

mode 4.0 : Cruise Control with Steering & Gear

python 예시 :

move_carmsg.data = [1.0, 4.0,20.0,0.0, 0.0, 200.0, 0.0,0.0,0.0,0.0]

해석 >> ERP42에서 0.0에 해당하는 driving gear로 20km/h의 속도로 cruise control을 하며 steer를 200pub한다.

속도만 Cruise Control을 하고, Steer랑 Gear를 모두 제어할 수 있는 모드이다.

mode 5.0 : for nav_pilot (plz read FOR KASA)

python 예시 :

move_carmsg.data = [1.0, 5.0,20.0,0.0, 0.0, 200.0, 0.0,0.0,0.0,0.0]

해석 >> ERP42에서 0.0에 해당하는 driving gear로 20km/h의 속도로 cruise control을 하며 steer를 200pub한다.

mode 4.0의 기능을 통신 충돌이 일어나지 않도록, 대회용으로 만든 것이다. 더불어 index 3번째에 해당하는 속도칸에 원하는 속도를 입력할 수 있는데, 주행팀 설계상 7km/h 이하까지만 PID 기반으로 돌아가고, 그 이상은 PID없이 direct accel 값을 발행한다.

mode 6.0 : for mission manager (plz read FOR KASA)

python 예시 :

move_carmsg.data = [1.0, 6.0,20.0,0.0, 0.0, 200.0, 0.0,0.0,0.0,0.0]

해석 >> ERP42에서 0.0에 해당하는 driving gear로 20km/h의 속도로 cruise control을 하며 steer를 200pub한다.

mode 4.0의 기능을 통신 충돌이 일어나지 않도록, 대회용으로 만든 것이다. 더불어 index 3번째에 해당하는 속도칸에 원하는 속도를 입력할 수 있는데, 주행팀 설계상 7km/h 이하까지만 PID 기반으로 돌아가고, 그 이상은 PID없이 direct accel 값을 발행한다.

추가적인 핵심 기능은, mode 5.0에 해당하는 nav_pilot은 계속 돌아가지만, /mission_manager/nav_pilot topic이 off되면, 해당 모드의 통신을 무시하고, 6.0만 수행하도록 설계되었다.

Last updated

Was this helpful?