ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

UR3- real hardware and moveIT

asked 2021-03-01 05:32:34 -0500

RB_Code gravatar image

updated 2021-03-01 09:52:05 -0500

gvdhoorn gravatar image

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
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2021-03-02 09:30:08 -0500

fvd gravatar image

updated 2021-03-02 09:30:34 -0500

I'd check these things:

  • Does it work without setting sim:=true? You shouldn't need to do that if you run the real robot, since you're not running a simulation.

  • Is the controllers.yaml or ros_controllers.yaml in your ur3_moveit_config package intact? Does it look like this file? If not, please add it to your question.

edit flag offensive delete link more

Comments

Thank you very much for responding.

Yes. I don´t need the sim:=true to work.

My file controllers.yaml

controller_list:
  - name: "scaled_pos_traj_controller/follow_joint_trajectory"
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    joints:
      - shoulder_pan_joint
      - shoulder_lift_joint
      - elbow_joint
      - wrist_1_joint
      - wrist_2_joint
      - wrist_3_joint

I put the name "scaled_pos_traj_controller/follow_joint_trajectory" as this is what they recommend to correct the error: [https://github.com/UniversalRobots/Un...].

But I have the same error:

[ERROR] [1614701456.667050492]: 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] [1614701456.667172781]: Known controllers and their joints:
RB_Code gravatar image RB_Code  ( 2021-03-02 10:17:26 -0500 )edit

I managed to connect the robot however the trajectory it calculates is always absurd.

For example: I see where you are and I have to move for example +0.1 on x, but this movement is huge for what it should be.

Has anyone had the same problem? What can it be? I use the planner: RRTConnectkConfigDefault

RB_Code gravatar image RB_Code  ( 2021-03-02 15:26:22 -0500 )edit

Please don't follow-up questions in answers, that's not how this site works. Explain how you solved your problem, accept the answer (with the checkmark on the left) and then post a new question instead.

fvd gravatar image fvd  ( 2021-03-02 18:44:41 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-03-01 05:32:34 -0500

Seen: 517 times

Last updated: Mar 02 '21