UR3- real hardware and moveIT
I'm using the ur_robot_driver library to try to control ur3.
I use two launches:
roslaunch ur_robot_driver ur3_bringup.launch robot_ip:=my_ip
roslaunch ur3_moveit_config ur3_moveit_planning_execution.launch sim:=true
Only when I calculate for example a trajectory I can have its output but when I want the robot to move it does not move and always gives this error:
[ERROR] [1614597453.624769915]: Unable to identify any set of controllers that can actuate the specified joints: [ elbow_joint shoulder_lift_joint shoulder_pan_joint wrist_1_joint wrist_2_joint wrist_3_joint ]
[ERROR] [1614597453.624881946]: Known controllers and their joints:
[ERROR] [1614597453.624988060]: Apparently trajectory initialization failed
[ INFO] [1614597453.626108828]: Received event 'stop'
When I run my script:
[ INFO] [1614597451.133445691]: Loading robot model 'ur3'...
[ WARN] [1614597451.152041768]: Skipping virtual joint 'fixed_base' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1614597451.152117696]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ WARN] [1614597451.581841077]: Kinematics solver doesn't support #attempts anymore, but only a timeout.
Please remove the parameter '/robot_description_kinematics/manipulator/kinematics_solver_attempts' from your configuration.
[ WARN] [1614597452.238029661]: TF_OLD_DATA ignoring data from the past for frame base_link at time 1.6146e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ INFO] [1614597453.375938898]: Ready to take commands for planning group manipulator.
[ INFO] [1614597453.625619764]: ABORTED: Solution found but controller failed during execution
This is the code I am using:
#!/usr/bin/env python
import sys
import rospy
import moveit_commander
from geometry_msgs.msg import Point, Pose
from moveit_msgs.msg import MoveGroupActionFeedback
import moveit_msgs.msg
from std_msgs.msg import Int8
from math import pi
class trajectory:
# Initialize class
def __init__(self):
# setup movie commander
moveit_commander.roscpp_initialize(sys.argv)
# setup robot, scene, and move group
self.robot = moveit_commander.RobotCommander()
self.scene = moveit_commander.PlanningSceneInterface()
self.group = moveit_commander.MoveGroupCommander('manipulator')
# setup some configs
self.group.set_goal_position_tolerance(0.05)
self.group.set_planner_id('RRTConnectkConfigDefault')
self.group.set_planning_time(5)
self.group.set_num_planning_attempts(5)
# set status to ready
self.status = 0
joint_goal = self.group.get_current_joint_values()
joint_goal[0] = 0
joint_goal[1] = 0
joint_goal[2] = 0
joint_goal[3] = -pi/4
joint_goal[4] = 0
joint_goal[5] = 0
# The go command can be called with joint values, poses, or without any
# parameters if you have already set the pose or joint target for the group
self.group.go(joint_goal, wait=True)
# Calling ``stop()`` ensures that there is no residual movement
self.group.stop()
if __name__=='__main__':
rospy.init_node('Trajecory_UR3')
trajectory()
try:
rospy.spin()
except rospy.ROSInterruptException:
pass