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

service state request callback function, error: Invalid number of arguments

asked 2017-02-08 07:58:06 -0500

RSA_kustar gravatar image

updated 2017-02-08 12:09:47 -0500

Hi,

I created a service with the following definition and i called it navigation.srv:

float64 srvtype
float64 wayPointX
float64 wayPointY
float64 wayPointZ
float64 LDFlag
---
std_msgs/String navResponse

Then I used the service state machine provided from smach and following the tutorials:

import roslib;  
import rospy
import actionlib 
import smach
import smach_ros
import time
from std_msgs.msg import String
from sensor_msgs.msg import RegionOfInterest
from geometry_msgs.msg import PoseStamped 
from kuri_msgs.srv import navigation

from kuri_msgs.msg import Object
from sensor_msgs.msg import NavSatFix
from nav_msgs.msg import Odometry
from smach_ros import ServiceState

 FixPoseX = 0   
 FixPoseY = 0 
 FixPoseZ = 10  


class Ch1():
 rospy.init_node('ch1_state_machine')
 sm = smach.StateMachine(outcomes=['Done'])

 with sm:

    def exploration_request_cb (userdata,request):
        exploration_request = navigation().Request  
        exploration_request.srvtype=1
        exploration_request.wayPointX = FixPoseX
        exploration_request.wayPointY = FixPoseY
        exploration_request.wayPointZ = FixPoseZ
        exploration_request.LDFlag = 0
        return exploration_request



        smach.StateMachine.add('EXPLORATION',
                ServiceState('controller_service',
                navigation,
                request  = exploration_request_cb),
                       transitions={'succeeded':'MARKER_DETECTION' , 'aborted':'Done', 'preempted':'EXPLORATION'})

    ### MORE STATES HERE

 sis = smach_ros.IntrospectionServer('server_name', sm, '/SM_ROOT')
     sis.start()

     # Execute SMACH plan
     outcome = sm.execute()
     rospy.spin()
     sis.stop()


if __name__ == '__main__':
   Ch1()

The Service the I am using to be called ( I am also having a problem in sending back a response is as follow)

when I run the state machine it says that it is waiting for the service then I run the service the output is the following:

 import roslib
 import rospy
 from kuri_msgs.msg import *
 from kuri_msgs.srv import navigation
 from kuri_msgs.srv import navigationResponse
 from geometry_msgs.msg import PoseStamped 
 from nav_msgs.msg import Odometry 

 class ControllerService:
         def __init__(self):
               print 'Starting Service 1'
               self.s = rospy.Service('controller_service', navigation , self.pos_vel_controller)   

        def pos_vel_controller(self , req):
            self.landFlagDone = req.LDFlag 
                if req.srvtype == 1 :
                         x = req.wayPointX
             y  = req.wayPointY
                 z = req.wayPointZ
             if self.landFlagDone >0:
#######################3 How to return a response here ???????????????????
                 return 'succeeded'
             else: 
                    return 'aborted'


def main(args):
  rospy.init_node('Controller_Service')
  Controller = ControllerService()
  try:
     rospy.spin()
 except KeyboardInterrupt:
    print "Shutting down"

if __name__ == '__main__':
    main(sys.argv)

In the service terminal Killed

In the state machine terminal

 TypeError: Invalid number of arguments, args should be ['srvtype', 'wayPointX', 'wayPointY', 'wayPointZ', 'LDFlag'] args are(<function exploration_request_cb at 0x7f0f3fae6140>,)

What is the mistake in this code and how can I fix it ?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2017-02-08 10:02:01 -0500

gvdhoorn gravatar image

updated 2017-02-08 12:32:35 -0500

exploration_request = navigation().Request

that is not the correct type for a Python ROS Service request.

It should probably be navigationRequest.

PS: ROS naming conventions are actually to CamelCase service definitions, so Navigation would be better (although it's still way too generically named).


Edit: you've probably seen it, but just to make sure: Writing a Simple Service and Client (Python). Section 1.1 shows how to instantiate a Response, but the principle is the same for Requests.


Edit2:

from kuri_msgs.srv import navigation

Just add the Request type to this line, something like:

from kuri_msgs.srv import navigation, navigationRequest

like you do in the Controller_Service file.

edit flag offensive delete link more

Comments

@avdhoorn Thanks for answering. I tried using navigationRequest but I got the following error NameError: global name 'navigationRequest' is not defined

RSA_kustar gravatar image RSA_kustar  ( 2017-02-08 10:29:44 -0500 )edit

@avdhoorn I am defining a string as you can see in the srv file for the response( i can change it to be string navResponse) variable .. but how can I fill it with a string data and return it as a response. I tried too much but without any luck

RSA_kustar gravatar image RSA_kustar  ( 2017-02-08 10:33:08 -0500 )edit

NameError: global name 'navigationRequest' is not defined

please include all relevant parts of your program in your OP. Especially your import .. statements.

gvdhoorn gravatar image gvdhoorn  ( 2017-02-08 11:05:19 -0500 )edit

@gvdhoorn I edited the question and I added the service the I am using

RSA_kustar gravatar image RSA_kustar  ( 2017-02-08 12:10:14 -0500 )edit

@gvdhoorn I tried adding this import library but it is not working It give me this error

return navigationResponse.navResponse("succeeded")\n', "TypeError: 'member_descriptor' object is not callable\n"]
RSA_kustar gravatar image RSA_kustar  ( 2017-02-09 00:39:53 -0500 )edit

I don't understand what you copy-pasted. Please update your question with the complete error output.

Also: navigationResponse.navResponse does not make sense to me.

gvdhoorn gravatar image gvdhoorn  ( 2017-02-09 02:52:10 -0500 )edit

@gvdhoorn what is the type of the response that I should provide in case of using the service state machine ?? is it string or something else ? because when using service state machine there are only three options of response which are the succeeded, aborted and pre-empted

RSA_kustar gravatar image RSA_kustar  ( 2017-02-12 01:28:58 -0500 )edit

@gcdhoorn for your last question I changed the way of returning the response to be like this

return navigationResponse.navResponse("succeeded")

which is the name if the srv response msg followed by the variable for the response and then filling it with the response msg. Then I got that error

RSA_kustar gravatar image RSA_kustar  ( 2017-02-12 01:31:37 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2017-02-08 07:58:06 -0500

Seen: 3,150 times

Last updated: Feb 08 '17