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

How to move specific joint only using MoveIt?

asked 2017-12-05 13:56:17 -0500

Ahmad gravatar image

I'm using MoveIt interface to control my Yumi Robot either by setting the joints value or the Pose values. What I need to do is changing the value of one joint only (joint-6) without changing the other joint values.

Thank you in advance.

edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
1

answered 2017-12-06 12:33:22 -0500

Ahmad gravatar image

I just solved it by some coding I get the current state of joints and copy them to a variable, and then just edit the needed joint only.

here is the code

std::vector<double> x;
group.getCurrentState() ->copyJointGroupPositions(group.getCurrentState() ->getRobotModel() ->getJointModelGroup(group.getName()), x);
x[/joint number/]=/value/;

The code is available in ROS book chapter 6 6.2 Planning to a joint goal

edit flag offensive delete link more
0

answered 2023-02-16 06:32:54 -0500

As mentioned above, one solution is to read the current joint values, build a dictionary of "joint names" vs "current joint angles", modify the ones you need, then send to moveit for planning and execution, here a python example of how to do it (for our robot):

#!/usr/bin/env python3

'''
example on how to control specific arm joints with moveit
'''

import sys
import rospy
import moveit_commander

rospy.init_node('move_joints_test', anonymous=False)

try:
    rospy.loginfo('waiting for move_group action server')
    moveit_commander.roscpp_initialize(sys.argv)
    robot = moveit_commander.RobotCommander()
    # robot.arm.set_planning_time(20.0)
    # robot.arm.set_goal_tolerance(0.01)
    rospy.loginfo('found move_group action server')
except RuntimeError:
    # moveit_commander.roscpp_initialize overwrites the signal handler,
    # so if a RuntimeError occurs here, we have to manually call
    # signal_shutdown() in order for the node to properly exit.
    rospy.logfatal('could not connect to Moveit in time, exiting! \n')
    rospy.signal_shutdown('fatal error')

# to test if arm and moveit work
#arm_posture_name = 'observe100cm_right'
#robot.arm.set_named_target(arm_posture_name)
#robot.arm.go()

# give only the arm joints that we want to affect, NOTE: for some reason this does not work!
#arm_dic = {'mobipick/ur5_shoulder_pan_joint':-1.25, 'mobipick/ur5_elbow_joint':1.8}

# get current joint angles
joint_states = robot.arm.get_current_state().joint_state

arm_joints_dic = {}

joints_of_interest = ['mobipick/ur5_shoulder_pan_joint', 'mobipick/ur5_shoulder_lift_joint', 'mobipick/ur5_elbow_joint', 'mobipick/ur5_wrist_1_joint', 'mobipick/ur5_wrist_2_joint', 'mobipick/ur5_wrist_3_joint']
for joint_of_interest in joints_of_interest:
    # find index
    for i, joint_name in enumerate(joint_states.name):
        if joint_of_interest == joint_name:
            # print(f'{joint_of_interest}:{joint_states.position[i]}') # uncomment for debug purposes
            arm_joints_dic[joint_of_interest] = joint_states.position[i]

# rospy.logwarn(f'current arm state: {robot.arm.get_current_state().joint_state}')

# modify required joints
arm_joints_dic['mobipick/ur5_shoulder_pan_joint'] = -1.25
arm_joints_dic['mobipick/ur5_elbow_joint'] = 1.8

robot.arm.set_joint_value_target(arm_joints_dic)
robot.arm.go()

rospy.spin()
edit flag offensive delete link more
0

answered 2017-12-06 07:22:16 -0500

v4hn gravatar image

You can setup JointModelGroups (planning groups) for each single joint in your srdf to plan with these joints only.

How to actuate these trajectories on your robot arm depends on the concrete hardware driver. I've not worked with Yumi up to now, so I can't help you there.

edit flag offensive delete link more

Comments

Thank you for your answer, I've tried it work well with the simulation but when executing to the real robot it abort the execution process

Ahmad gravatar image Ahmad  ( 2017-12-06 10:30:53 -0500 )edit
0

answered 2018-01-18 17:43:34 -0500

AndyZe gravatar image

MoveIt! added a method for this recently. Cool.

bool setJointValueTarget (const std::string &joint_name, double value)

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-12-05 13:56:17 -0500

Seen: 1,391 times

Last updated: Feb 16 '23