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

What is the best way to control Sawyer robot if I already have the trajectory?

asked 2021-03-04 19:00:48 -0500

wifier gravatar image

updated 2021-03-06 09:53:52 -0500

gvdhoorn gravatar image

Hello everyone!

Currently, I am working with Sawyer robotic arm and coded up an artificial intelligence code in Matlab to find a trajectory that avoids obstacles and minimizes control effort (joint movement). Now, I have the joint space trajectory (Sawyer has 7 joints, so this is a 7x100 matrix, 100 points), a time vector (1x100) and I can also obtain joint speeds and joint accelerations by simply differentiating. My question is: what is the best way to use this information (7x100 trajectory) to control the real robot? I have the actual robotic arm, but I started working in Gazebo and my first try was using MoveIt!. I thought that it would be helpful to ask this question here before trying anything ineffective. Thank you!


Edit: Thank you for your replies! I tried setting up a simple code and eventually succeeded in controlling the joint positions using limb.move_to_joint_positions. Also, I found that there is another command that can help me limb.set_joint_trajectory. However, it does not work - after I run the Python script the Robot does not move. Has anyone used limb.set_joint_trajectory before? I attached my piece of code below where I am trying to use the existing trajectory on joint 2. Possibly I am not using the self._limb.set_joint_trajectory('right_j2',pos,vel,acc)correctly. I could not find anything close to this problem. The self._limb.move_to_joint_positions({'right_j0':0,'right_j1':0, 'right_j2':0,'right_j3':0,'right_j4':0,'right_j5':0,'right_j6':0}) are working just fine, that is why I commented them out of the attached code.

#!/usr/bin/env python

# Import math modules

    import math
    import numpy as np

# Import robot interface modules

    import rospy
    import intera_interface
    from intera_interface import CHECK_VERSION

# Initialize robot

    rospy.init_node("Test")
    intera_interface.RobotEnable(
    CHECK_VERSION).enable()

# Main class

    class Main:##

# Initialize application

    def __init__(self):

# Create robot
        self.robot = Robot()
        self.robot.run()

# Robot

    class Robot(object):

# Initialize window
    def __init__(self):
        self._limb = intera_interface.Limb()
        self._target_angle = 0



    def run(self):
        # Move to neutral position
        print("Moving to neutral...")
        #self._limb.move_to_neutral()
        #self._limb.set_joint_position_speed(1)
        #self._limb.move_to_joint_positions({'right_j0':0,'right_j1':0, 'right_j2':0,'right_j3':0,'right_j4':0,'right_j5':0,'right_j6':0})
        #self._limb.move_to_joint_positions({'right_j0':1,'right_j1':0, 'right_j2':0,'right_j3':0,'right_j4':0,'right_j5':0,'right_j6':0})
        #self._limb.move_to_joint_positions({'right_j0':0,'right_j1':0, 'right_j2':0,'right_j3':0,'right_j4':0,'right_j5':0,'right_j6':0})
        #self._limb.move_to_joint_positions({'right_j0':1,'right_j1':0, 'right_j2':0,'right_j3':0,'right_j4':0,'right_j5':0,'right_j6':0})
        #self._limb.move_to_joint_positions({'right_j0':0,'right_j1':0, 'right_j2':0,'right_j3':0,'right_j4':0,'right_j5':0,'right_j6':0})
        pos = [0,0.278521147421560,0.334311794594397,0.418267057180151,0.419262882688881,0.422556967444284,0.425164455138498,0.431006517211002,0.444412714223080,0.467013462886176,0.487570813194810,0.521244082754868,0.572498161392207,0.615699683910449,0.652258704653838,0.688486332506119,0.712269045528898,0.714783340982971,0.753313779601416,0.790976143848783,0.828967448333042,0.871415882700251,0.920906176488521,0.936397404556755,0.979800613969219,1.02083077359423]
        vel=[2.18381763515172,0.730617806133591,0.258549873450524,0.120452729287060,0.0701927980567305,0.0397948807240920,0.0246668664822685,0.0316916864038248,0.0612174375119867 ...
(more)
edit retag flag offensive close merge delete

Comments

1

Just to clarify: you can actually send trajectories to Sawyer without MoveIt.

At a high-level, you'd:

  • create a FollowJointTrajectory action client
  • create a Goal
  • put the JointTrajectory@fvd mentions inside that Goal message
  • submit the goal to the FollowJointTrajectory server

Matlab supports action client in their ROS Toolbox. If you have it, it may be the leanest way to control Sawyer from Matlab.

gvdhoorn gravatar image gvdhoorn  ( 2021-03-05 06:10:05 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-03-05 00:40:39 -0500

fvd gravatar image

updated 2021-03-05 06:30:38 -0500

You can create a JointTrajectory message and send it to a controller's follow_joint_trajectory action, as described by @gvdhoorn above. There are more detailed tutorials here. Just make sure that your robot is at the start position of your trajectory when you send it, or it will be dangerous.

Using MoveIt (a sawyer_moveit_config package) will be helpful for your debugging, since you can confirm that the robot is connected to your system (are the joint_states being read? can MoveIt send movement commands to the robot?), and visualize the trajectory you want to execute.

The easiest (if somewhat hacky-looking) way to send a trajectory through the MoveGroupInterface should be to replace the trajectory in a Plan and execute it, somewhat like this:

moveit::planning_interface::MoveGroupInterface::Plan your_plan;
moveit_msgs::RobotTrajectory your_trajectory;
// Fill your trajectory message
your_plan.trajectory_ = scaled_trajectory;
your_group->execute(your_plan);

And again, don't send a trajectory unless your robot is at the trajectory's first start position, or the movement will be sudden and dangerous. Even cobots can hurt.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-03-04 19:00:48 -0500

Seen: 585 times

Last updated: Mar 06 '21