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

How to use response of service

asked 2019-10-12 06:21:25 -0600

SunnyKatyara gravatar image

Since, i have written my own service which takes float values [x, y, z, a, b, c, d] and respond Pose. When i run the server node, i can see the service and call it. But i create the client, i am unable to use the service values.

I want to call my service from terminal and sending it pose for commanding robot through moveit.

My code for server #

import sys
import copy
import rospy
import geometry_msgs.msg
import tf

from move_to_pose_iit.srv import getPoseArray, getPoseArrayResponse

from geometry_msgs.msg import Pose

def handle_get_pose_array(req):
    my_array = Pose()
    my_array.position.x = req.x
    my_array.position.y = req.y
    my_array.position.z = req.z


 my_array.orientation.x = req.a
    my_array.orientation.y = req.b
    my_array.orientation.z = req.c
    my_array.orientation.w = req.d

    return getPoseArrayResponse(my_array)

def get_pose_array_server():
rospy.init_node('get_pose_array_server')
s =rospy.Service('get_pose_array', getPoseArray, handle_get_pose_array)

rospy.spin()

if __name__ == "__main__":
    get_pose_array_server()

For client

import rospy
from move_to_pose_iit.srv import *

    from geometry_msgs.msg import Pose

import sys
import copy
import rospy
import moveit_commander
import moveit_msgs.msg
import geometry_msgs.msg
import tf


def get_pose_array_client(pose):
    rospy.wait_for_service('get_pose_array')
    try:
        # bind our local service proxy
        svc_set_joint_states = rospy.ServiceProxy('get_pose_array', getPoseArray)



     # create the service request
        req = getPoseArrayRequest()
# populate the fields of the request
        req.x = pose[0]
        req.y = pose[1]
        req.z = pose[2]
        req.a = pose[3]
        req.b = pose[4]


req.c = pose[5]
    req.d = pose[6]

# invoke the service, passing it the request
resp = scv_set_joint_states(req)

# 'resp' is here of type 'SetJointStatesReponse'

# perhaps do something with the response

except rospy.ServiceException, e:
        print "Service call failed: %s"%e


if __name__ == "__main__":
    if len(sys.argv) == 6:
       pose[0] = float(sys.argv[1])
       pose[1] = float(sys.argv[2])
       pose[2] = float(sys.argv[3])
       pose[3] = float(sys.argv[4])
       pose[4] = float(sys.argv[5])



     pose[5] = float(sys.argv[6])
       pose[6] = float(sys.argv[7])

       get_pose_array_client(pose)

robot=moveit_commander.RobotCommander()
scene=moveit_commander.PlanningSceneInterface()

group=moveit_commander.MoveGroupCommander("panda_arm")
display=rospy.Publisher('/move_group/display_planned_path', moveit_msgs.msg.DisplayTrajectory, queue_size=10)

pose_target = Pose()


pose_target.position.x = pose[0]
pose_target.position.y = pose[1]
pose_target.position.z = pose[2]
pose_target.orientation.x = pose[3]

pose_target.orientation.y = pose[4]
pose_target.orientation.z = pose[5]
pose_target.orientation.w = pose[6]

group.set_pose_target(pose_target)

plan1 = group.plan()
group.go(wait=True)

rospy.sleep(20)

moveit_commander.roscpp_shutdown()
edit retag flag offensive close merge delete

Comments

Please post the contents of your custom service getPoseArray

pavel92 gravatar image pavel92  ( 2019-10-15 06:07:10 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-10-15 06:34:24 -0600

pavel92 gravatar image

updated 2019-10-15 06:39:44 -0600

'resp' is here of type 'SetJointStatesReponse

Why is this so? Aren't you using your custom service getPoseArray? And why is it an array? Shouldn't it be a pose? It looks like you have some inconsistencies with the srv files. Dont confuse the geometry_msgs/Pose with geometry_msgs/PoseArray.

The svc_set_joint_states is a service proxy. Based on:

i have written my own service which takes float values [x, y, z, a, b, c, d] and respond Pose

your custom srv should be getPose and look something like this:

float32 x
float32 y
float32 z
float32 a 
float32 b
float32 c
float32 d
---
geometry_msgs/Pose pose

If the response of your service is a geometry_msgs/Pose message can access the response fields like this:

try:
    svc_set_joint_states = rospy.ServiceProxy('get_pose_array', getPoseArray)

    req = getPoseRequest()
    req.x = pose[0]
    req.y = pose[1]
    req.z = pose[2]
    req.a = pose[3]
    req.b = pose[4]
    req.c = pose[5]
    req.d = pose[6]

    resp = scv_set_joint_states(req)

except rospy.ServiceException, e:
        print "Service call failed: %s"%e

resp.pose  ... # do something with the response

where resp.pose should be a geometry_msgs/Pose.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-10-12 06:21:25 -0600

Seen: 1,273 times

Last updated: Oct 15 '19