Not able to control real robot using MoveIt!
Hi,
I am new to moveit and ROS. I have Schunk Lwa4p arm for which I created moveit config package (using set up assistant). But I am struggling to control the real arm from moveit.
Upon running moveit_planning_execution.launch
and clicking on Execute button in RViz, I got following errors:
[ INFO] [1458896804.810438377]: Waiting for operationmode service to become available
[ERROR] [1458896804.974349026]: MoveitSimpleControllerManager: Action client not connected: arm/joint_trajectory_controller
[ INFO] [1458896805.079746996]: Returned 0 controllers in list
[ INFO] [1458896805.119044800]: Trajectory execution is managing controllers
and
[ INFO] [1458896900.940527967]: Waiting for operationmode service to become available
[ INFO] [1458896901.933728220]: Combined planning and execution request received for MoveGroup action. Forwarding to planning and execution pipeline.
[ WARN] [1458896901.933887039]: Execution of motions should always start at the robot's current state. Ignoring the state supplied as start state in the motion planning request
[ INFO] [1458896901.933944449]: Planning attempt 1 of at most 1
[ INFO] [1458896901.935989122]: No planner specified. Using default.
[ INFO] [1458896901.936155554]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1458896901.938471980]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1458896901.941578311]: Waiting for operationmode service to become available
[ INFO] [1458896902.432168629]: LBKPIECE1: Created 184 (87 start + 97 goal) states in 176 cells (86 start (86 on boundary) + 90 goal (90 on boundary))
[ INFO] [1458896902.434038979]: Solution found in 0.496061 seconds
[ INFO] [1458896902.434911366]: SimpleSetup: Path simplification took 0.000396 seconds and changed from 167 to 2 states
[ INFO] [1458896902.440256320]: Returned 0 controllers in list
[ERROR] [1458896902.440616352]: Unable to identify any set of controllers that can actuate the specified joints: [ arm_1_joint arm_2_joint arm_3_joint arm_4_joint arm_5_joint arm_6_joint ]
[ERROR] [1458896902.440879514]: Known controllers and their joints:
[ERROR] [1458896902.441217545]: Apparently trajectory initialization failed
[ INFO] [1458896902.942730273]: Waiting for operationmode service to become available
Following are the additional details:
I am using ROS Indigo devel on Ubuntu 14.04
Planning in RViz was successful and it displayed the planned path.
rostopic doesn't list the topics related to moveit_simple_controller_manager
moveit_planning_execution.launch
used: It is similar to the one given at http://wiki.ros.org/Industrial/Tutori...controllers.yaml
used:controller_manager_ns: moveit_simple_controller_manager controller_list: - name: "arm" action_ns: joint_trajectory_controller type: FollowJointTrajectory default: true joints: [arm_1_joint, arm_2_joint, arm_3_joint, arm_4_joint, arm_5_joint, arm_6_joint]
Please help me on how to resolve this and control my robot using moveit. Thanks in advance!