Re: Navigation Localization 실패현상
페이지 정보
본문
안녕하세요.
엔티렉스 강규하 전임연구원입니다.
문의주신 내용에 대해 답변드리겠습니다.
1. 말씀해주신 문제의 경우 여러가지 원인이 있을 수 있어, 현재 말씀해주신 정보 만으로는 정확한 문제점 및 원인 파악이 어렵습니다.
번거롭더라도 현재 어떻게 실행하고 있는지, 또 어떠한 오류메세지가 뜨는지 스크린샷을 찍어서 다시한번 문의주시기 바랍니다.
Localization 사용 시 초기위치는 자동으로 잡히지 않습니다.
초기위치의 경우에는 2D Pose Estimate 버튼을 눌러 위치를 어느정도 맞춰준 후 진행하셔야 Localization이 정확히 작동하게 됩니다.
위의 문제일 경우 위 방법으로 사용해보시기 바랍니다.
2. 말씀해주신 좌표계는 기준을 어떻게 잡느냐에 따라 다르므로 정해진 것이 없습니다.
저희는 해당 IMU 좌표계로 기준을 잡아서 ROS 패키지를 만들었습니다.
메뉴얼에 나와있는대로 설치 후 사용하시면 됩니다.
3. 말씀해주신 부분에 대해서는 문제점을 확인하고 바로 수정을 진행할 예정입니다.
기존 그대로 사용하더라도 laser_frame과 base_scan의 TF가 서로 동일한 위치에, 동일한 방향으로 생성되고, base_link를 통해 서로 연결되어 있기 때문에 문제를 파악하지 못하였었습니다.
죄송합니다.
직접 수정해서 사용하실 경우, stella_lds.launch 파일의 내용을 다음과 같이 수정 후 사용해주시기 바랍니다.
<launch>
<node name="ydlidar_node" pkg="ydlidar" type="ydlidar_node" output="screen">
<param name="port" type="string" value="/dev/YDLIDAR"/>
<param name="baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="base_scan"/>
<param name="angle_fixed" type="bool" value="true"/>
<param name="low_exposure" type="bool" value="false"/>
<param name="heartbeat" type="bool" value="false"/>
<param name="resolution_fixed" type="bool" value="true"/>
<param name="angle_min" type="double" value="-180" />
<param name="angle_max" type="double" value="180" />
<param name="range_min" type="double" value="0.08" />
<param name="range_max" type="double" value="16.0" />
<param name="ignore_array" type="string" value="" />
<param name="samp_rate" type="int" value="9"/>
<param name="frequency" type="double" value="7"/>
</node>
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.145 0.0 0.229 3.14 0.0 0.0 /base_footprint /base_scan 40" />
</launch>
감사합니다.
4. amcl.launch 파일의 경우 오타가 있었던 것을 확인하였습니다.
수정 진행하였습니다.
감사합니다.
5.말씀해주신 부분에 대해서는 저희 측에서는 오류 메시지가 발생하지 않습니다.
PC 사용환경이 Ubuntu 18.04, ROS Melodic 버전이 아닐 경우 오류가 발생할 수 있습니다.
위의 사용환경이 맞는데도 오류 메세지가 발생하는 경우에는 1번과 마찬가지로 스크린샷을 첨부하여 다시한번 문의주시면 감사하겠습니다.
STELLA N1 사용에 있어 번거롭게 해드려서 죄송합니다.
감사합니다.
엔티렉스 강규하 전임연구원입니다.
문의주신 내용에 대해 답변드리겠습니다.
1. 말씀해주신 문제의 경우 여러가지 원인이 있을 수 있어, 현재 말씀해주신 정보 만으로는 정확한 문제점 및 원인 파악이 어렵습니다.
번거롭더라도 현재 어떻게 실행하고 있는지, 또 어떠한 오류메세지가 뜨는지 스크린샷을 찍어서 다시한번 문의주시기 바랍니다.
Localization 사용 시 초기위치는 자동으로 잡히지 않습니다.
초기위치의 경우에는 2D Pose Estimate 버튼을 눌러 위치를 어느정도 맞춰준 후 진행하셔야 Localization이 정확히 작동하게 됩니다.
위의 문제일 경우 위 방법으로 사용해보시기 바랍니다.
2. 말씀해주신 좌표계는 기준을 어떻게 잡느냐에 따라 다르므로 정해진 것이 없습니다.
저희는 해당 IMU 좌표계로 기준을 잡아서 ROS 패키지를 만들었습니다.
메뉴얼에 나와있는대로 설치 후 사용하시면 됩니다.
3. 말씀해주신 부분에 대해서는 문제점을 확인하고 바로 수정을 진행할 예정입니다.
기존 그대로 사용하더라도 laser_frame과 base_scan의 TF가 서로 동일한 위치에, 동일한 방향으로 생성되고, base_link를 통해 서로 연결되어 있기 때문에 문제를 파악하지 못하였었습니다.
죄송합니다.
직접 수정해서 사용하실 경우, stella_lds.launch 파일의 내용을 다음과 같이 수정 후 사용해주시기 바랍니다.
<launch>
<node name="ydlidar_node" pkg="ydlidar" type="ydlidar_node" output="screen">
<param name="port" type="string" value="/dev/YDLIDAR"/>
<param name="baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="base_scan"/>
<param name="angle_fixed" type="bool" value="true"/>
<param name="low_exposure" type="bool" value="false"/>
<param name="heartbeat" type="bool" value="false"/>
<param name="resolution_fixed" type="bool" value="true"/>
<param name="angle_min" type="double" value="-180" />
<param name="angle_max" type="double" value="180" />
<param name="range_min" type="double" value="0.08" />
<param name="range_max" type="double" value="16.0" />
<param name="ignore_array" type="string" value="" />
<param name="samp_rate" type="int" value="9"/>
<param name="frequency" type="double" value="7"/>
</node>
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.145 0.0 0.229 3.14 0.0 0.0 /base_footprint /base_scan 40" />
</launch>
감사합니다.
4. amcl.launch 파일의 경우 오타가 있었던 것을 확인하였습니다.
수정 진행하였습니다.
감사합니다.
5.말씀해주신 부분에 대해서는 저희 측에서는 오류 메시지가 발생하지 않습니다.
PC 사용환경이 Ubuntu 18.04, ROS Melodic 버전이 아닐 경우 오류가 발생할 수 있습니다.
위의 사용환경이 맞는데도 오류 메세지가 발생하는 경우에는 1번과 마찬가지로 스크린샷을 첨부하여 다시한번 문의주시면 감사하겠습니다.
STELLA N1 사용에 있어 번거롭게 해드려서 죄송합니다.
감사합니다.
- 이전글Navigation Localization 실패현상 22.05.27
- 다음글stell_md_node-1 로드 관련 22.05.02
댓글목록
등록된 댓글이 없습니다.