MoveItSimpleControllerManager: Action client not connected [closed]
Hi all. I roslaunch the moveit_planning_execution.launch, but got some errors like this
[ERROR] [1510493735.221182418]: MoveItSimpleControllerManager: Action client not connected: jakaUr/jaka_joint_controller/follow_joint_trajectory
Here are the related files moveit_planning_execution.lsunch:
<launch>
<arg name="sim" default="true" />
<arg name="robot_ip" unless="$(arg sim)" />
<include file="$(find jaka_ur_moveit_config2)/launch/planning_context.launch" >
<arg name="load_robot_description" value="true" />
</include>
<group if="$(arg sim)">
<include file="$(find industrial_robot_simulator)/launch/robot_interface_simulator.launch" />
</group>
<group unless="$(arg sim)">
<include file="$(find [robot_interface_pkg])/launch/robot_interface.launch" >
<arg name="robot_ip" value="$(arg robot_ip)"/>
</include>
</group>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<include file="$(find jaka_ur_moveit_config2)/launch/move_group.launch">
<arg name="publish_monitored_planning_scene" value="true" />
</include>
<include file="$(find jaka_ur_moveit_config2)/launch/moveit_rviz.launch">
<arg name="config" value="true"/>
</include>
<include file="$(find jaka_ur_moveit_config2)/launch/default_warehouse_db.launch" />
</launch>
the planning_context.launch
<launch>
<!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->
<arg name="load_robot_description" default="false"/>
<!-- The name of the parameter under which the URDF is loaded -->
<arg name="robot_description" default="robot_description"/>
<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="$(find xacro)/xacro.py '$(find jaka_ur_description_pkg)/urdf/jaka.urdf.xacro'"/>
<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find jaka_ur_moveit_config2)/config/jakaUr.srdf" />
<!-- Load updated joint limits (override information from URDF) -->
<group ns="$(arg robot_description)_planning">
<rosparam command="load" file="$(find jaka_ur_moveit_config2)/config/joint_limits.yaml"/>
</group>
<!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->
<group ns="$(arg robot_description)_kinematics">
<rosparam command="load" file="$(find jaka_ur_moveit_config2)/config/kinematics.yaml"/>
</group>
</launch>
the robot_interface_simulator.launch
<!-- industrial_robot_simulator: accepts robot commands and reports status -->
<node pkg="industrial_robot_simulator" type="industrial_robot_simulator" name="industrial_robot_simulator"/>
<!-- joint_trajectory_action: provides actionlib interface for high-level robot control -->
<node pkg="industrial_robot_client" type="joint_trajectory_action" name="joint_trajectory_action"/>
</launch>
Here is the output of rostopic list
![/attached_collision_object
/collision_object
/execute_trajectory/cancel
/execute_trajectory/feedback
/execute_trajectory/goal](/upfiles/1510498793189035.jpeg)
/execute_trajectory/result
/execute_trajectory/status
/feedback_states
/joint_path_command
/joint_states
/joint_trajectory_action/cancel
/joint_trajectory_action/feedback
/joint_trajectory_action/goal
/joint_trajectory_action/result
/joint_trajectory_action/status
/move_group/cancel
/move_group/display_contacts
/move_group/display_planned_path
/move_group/feedback
/move_group/goal
/move_group/monitored_planning_scene
/move_group/ompl/parameter_descriptions
/move_group/ompl/parameter_updates
/move_group/plan_execution/parameter_descriptions
/move_group/plan_execution/parameter_updates
/move_group/planning_scene_monitor/parameter_descriptions
/move_group/planning_scene_monitor/parameter_updates
/move_group/result
/move_group/sense_for_plan/parameter_descriptions
/move_group/sense_for_plan/parameter_updates
/move_group/status
/move_group/trajectory_execution/parameter_descriptions
/move_group/trajectory_execution/parameter_updates
/pickup/cancel
/pickup/feedback
/pickup/goal
/pickup/result
/pickup/status
/place/cancel
/place/feedback
/place/goal
/place/result
/place/status
/planning_scene
/planning_scene_world
/recognized_object_array
/robot_status
/rosout
/rosout_agg
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/feedback
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update_full
/rviz_shantengfei_pc_5217_6285278760314515870/motionplanning_planning_scene_monitor/parameter_descriptions
/rviz_shantengfei_pc_5217_6285278760314515870/motionplanning_planning_scene_monitor/parameter_updates
/tf
/tf_static
/trajectory_execution_event
the picture is the output of rosrun rqt_graph rqt_graph
.I searched the similar quesition here here but I cannot solve my problem.Could anyone give me some suggestions? Thank you!
update:
I tried to solve it but I have some new problem. The origin controllers.yaml is
controller_manager_ns: controller_manager
controller_list:
- name: "jakaUr/jaka_joint_controller"
action_ns: followJointTrajectory
type: FollowJointTrajectory
default: true
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
and the node name is joint_trajectory_action which ...
Where is the original question then ? @tengfei