안녕하세요,
저는 경희대학교를 다니고 있는 대학원생입니다.
현재 저는 연구실에서 UR3를 이용해서 양팔 로봇을 제작 중인데요.
지금까지 진행된 상황은,
universal robot 사에서 제공하는 패키지들(http://wiki.ros.org/universal_robot)을 이용해서
제가 하고자 하는 양팔 로봇의 URDF 작성 및 moveit! 패키지, gazebo 시뮬레이션 환경까지 작성했습니다.

시스템 사양은 Linux-min(16.04), ROS Kinetic 1.12.12 입니다.
그래서 작성한 gazebo를 띄우고, moveit! rviz를 띄워서 plan --> execute를 진행했는데요,
여기서 plan 은 성공하나, execute 시에 아래와 같은 에러를 확인했습니다.
<moveit! 을 실행시킨 cmd 창>
[ INFO] [1519281586.410268867, 9.183000000]: Execution request received for ExecuteTrajectory action.
[ WARN] [1519281590.729237772, 9.791000000]: Controller l_arm_controller_dual failed with error code PATH_TOLERANCE_VIOLATED
[ WARN] [1519281590.729375753, 9.791000000]: Controller handle l_arm_controller_dual reports status ABORTED
[ INFO] [1519281590.729495866, 9.791000000]: Execution completed: ABORTED
[ INFO] [1519281590.738399432, 9.792000000]: ABORTED: Solution found but controller failed during execution
아무래도 gazebo와 controller 간의 소통(?)이 되지 않아 발생 된 것 같아 gazebo를 실행 시킨 창을 보니 아래와 같은 에러를 발견했습니다.
<gazebo를 실행시킨 창> <!-- 핵심 질문 -->
[ INFO] [1519281519.268396686, 0.163000000]: Loading gazebo_ros_control plugin
[ INFO] [1519281519.268549975, 0.163000000]: Starting gazebo_ros_control plugin in namespace: /
[ INFO] [1519281519.269636949, 0.163000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [robot_description] on the ROS param server.
[ INFO] [1519281519.401388285, 0.163000000]: Loaded gazebo_ros_control.
[ INFO] [1519281519.401612659, 0.163000000]: Loading gazebo_ros_control plugin
[ INFO] [1519281519.401677732, 0.163000000]: Starting gazebo_ros_control plugin in namespace: /
Loaded l_arm_controller_dual
[ERROR] [1519281519.527780162, 0.163000000]: Tried to advertise a service that is already advertised in this node [/controller_manager/list_controllers]
[ERROR] [1519281519.527820775, 0.163000000]: Tried to advertise a service that is already advertised in this node [/controller_manager/list_controller_types]
[ERROR] [1519281519.527837622, 0.163000000]: Tried to advertise a service that is already advertised in this node [/controller_manager/load_controller]
[ERROR] [1519281519.527853349, 0.163000000]: Tried to advertise a service that is already advertised in this node [/controller_manager/unload_controller]
[ERROR] [1519281519.527869669, 0.163000000]: Tried to advertise a service that is already advertised in this node [/controller_manager/switch_controller]
[ERROR] [1519281519.527887135, 0.163000000]: Tried to advertise a service that is already advertised in this node [/controller_manager/reload_controller_libraries]
[ INFO] [1519281519.527936241, 0.163000000]: Loaded gazebo_ros_control.
[INFO] [1519281519.534601, 0.169000]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1519281519.536754, 0.171000]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1519281519.538781, 0.173000]: Loading controller: joint_state_controller
Loaded r_arm_controller_dual
Started ['l_arm_controller_dual'] successfully
[INFO] [1519281519.592000, 0.188000]: Controller Spawner: Loaded controllers: joint_state_controller
Started ['r_arm_controller_dual'] successfully
[INFO] [1519281519.603280, 0.190000]: Started controllers: joint_state_controller
[l_arm_controller_spawner-7] process has finished cleanly
log file: /home/mint-phj/.ros/log/026079a0-179b-11e8-9196-f0d5bf83d45c/l_arm_controller_spawner-7*.log
[r_arm_controller_spawner-8] process has finished cleanly
log file: /home/mint-phj/.ros/log/026079a0-179b-11e8-9196-f0d5bf83d45c/r_arm_controller_spawner-8*.log
[ WARN] [1519281586.472481010, 9.191000000]: Dropping first 1 trajectory point(s) out of 29, as they occur before the current time.
First valid point will be reached in 0.157s
제 짧은 소견으로는, 빨간 색으로 보이는 에러만 해결하면 될 것 같은데요....
도움을 주시면 정말 감사하겠습니다.
gazebo launch 코드:
<dual_arm_bringup.launch>
<launch>
<include file="$(find violin_dual_gazebo)/launch/violin_dual_arm_world.launch" />
<!--include file="$(find violin_dual_gazebo)/launch/controller_utils.launch" /-->
<include file="$(find violin_dual_gazebo)/launch/dual_arm_joint_state_controller.launch" />
<include file="$(find violin_dual_gazebo)/launch/dual_arm_l_controller.launch" />
<include file="$(find violin_dual_gazebo)/launch/dual_arm_r_controller.launch" />
</launch>
<violin_dual_arm_world.launch>
<launch>
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find violin_dual_gazebo)/worlds/violin_dual_arm.world"/>
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<param name="robot_description"
command="$(find xacro)/xacro.py $(find violin_description)/urdf/violin_dual_arm_v1.xacro" />
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model dual_robot -param robot_description"/>
</launch>
다음은 각 팔에 대한 controller launch 파일입니다.
<dual_arm_l_controller.launch>
<launch>
<rosparam file="$(find violin_dual_gazebo)/controller/l_arm_controller_dual.yaml" command="load"/>
<node name="l_arm_controller_spawner" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="spawn l_arm_controller_dual" />
</launch>
<dual_arm_r_controller.launch>
<launch>
<rosparam file="$(find violin_dual_gazebo)/controller/r_arm_controller_dual.yaml" command="load"/>
<node name="r_arm_controller_spawner" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="spawn r_arm_controller_dual" />
</launch>
<dual_arm_joint_state_controller.launch>
<launch>
<rosparam file="$(find violin_dual_gazebo)/controller/joint_state_controller.yaml" command="load"/>
<!-- joint_state_controller -->
<node name="joint_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="joint_state_controller" />
<!-- Robot state publisher -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false"
output="screen"/>
</launch>