0

Rosanswers logo

I am following a tutorial from theConstructSim in which I am trying to create a service which when called will write the current coordinate position of the robot to a file.

However, the rospy.service function call is immediately triggering the following error when I perform a rosrun on the code:

Traceback (most recent call last):
  File "/home/user/catkin_ws/src/my_summit_xl_tools/src/spots_to_file.py", line 79, in <module>
    startPoseService()

File "/home/user/catkin_ws/src/my_summit_xl_tools/src/spots_to_file.py", line 75, in startPoseService summitpose = SummitXLPose()

File "/home/user/catkin_ws/src/my_summit_xl_tools/src/spots_to_file.py", line 35, in init self.pose_service = rospy.Service('/get_pose_summitxl_service', SummitXLPose , self.pose_service_callback)

File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/impl/tcpros_service.py", line 711,in init error_handler)

File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/impl/tcpros_service.py", line 544,in init super(ServiceImpl, self).init(name, service_class)

File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/service.py", line 59, in init self.request_class = service_class._request_class

AttributeError: type object 'SummitXLPose' has no attribute '_request_class'

Here's the code I am running:

#! /usr/bin/env python
import os
import rospy
from my_summit_xl_tools.srv import SummitXLPose, SummitXLPoseResponse, SummitXLPoseRequest
from geometry_msgs.msg import PoseWithCovarianceStamped
import rospkg

"""

topic: /amcl_pose

geometry_msgs/PoseWithCovarianceStamped

std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/Pose pose
geometry_msgs/Point position
float64 x
float64 y
float64 z
geometry_msgs/Quaternion orientation
float64 x
float64 y
float64 z
float64 w
float64[36] covariance """

class SummitXLPose(object): def init(self): rospy.loginfo("---> Starting Service ...") print(dir(SummitXLPose)) self.pose_service = rospy.Service('/get_pose_summitxl_service', SummitXLPose , self.pose_service_callback) ...

def start_loop_service(self):
    rospy.spin() # mantain the service open.

def pose_service_callback(self, request):
    rospy.loginfo(&quot;... testing ...&quot;)
    spot_name = request.label

    with open(self.spot_file_path, &quot;a&quot;) as myfile:
        spot_pose = self.pose_now.pose.pose
        myfile.write(spot_name+&quot;:\n&quot;+str(spot_pose)+&quot;\n\n&quot;)

    response = SummitXLPoseResponse()
    response.navigation_successfull = True
    response.message = &quot;Spot &lt;&quot;+spot_name+&quot;&gt; Saved&quot;

    return response

def amcl_pose_callback(self, message):
    self.pose_now = message

def startPoseService(): rospy.init_node('summitxl_poseservice_server') summitpose = SummitXLPose() summitpose.start_loop_service()

if name == "main": startPoseService()

My SummitXLPose service is defined as follows:

# request
string label
---
#response
bool navigation_successfull
string message

Degugging the SummitXLPose class shows a lot of data but nothing of the request and response of the service that I expected to see as denoted in this question:

[INFO] [1613683896.890733, 0.000000]: ---> Starting Service ...
[
    '__class__', 
    '__delattr__', 
    '__dict__', 
    '__doc__', 
    '__format__', 
    '__getattribute__', 
    '__hash__', 
    '__init__', 
    '__module__', 
    '__new__', 
    '__reduce__', 
    '__reduce_ex__', 
    '__repr__', 
    '__setattr__', 
    '__sizeof__', 
    '__str__', 
    '__subclasshook__', 
    '__weakref__', 
    'amcl_pose_callback', 
    'pose_service_callback', 
    'start_loop_service'
]

It seems to me the absence of a _request_class attribute in the debug information is clearly the reason for my issue (as shown in the error above as compared to the question linked above) but I don't know how to resolve this issue.

I'd appreciate any help.


Originally posted by sisko on ROS Answers with karma: 247 on 2021-02-18

Post score: 0

1 Answers1

0

Rosanswers logo

This one proved to be as simple as it is embarrassing. The code in the tutorial was a bit flawed in that the class had the same name as the service class. So as far as ROS was concerned, I was attempting to call the same python class.

Instead of the code above, I now have the following:

#! /usr/bin/env python
...
from my_summit_xl_tools.srv import SummitXLPose, SummitXLPoseResponse, SummitXLPoseRequest
...

class SummitXLPoseX(object): def init(self): rospy.loginfo("---> Starting Service ...") print(dir(SummitXLPose)) self.pose_service = rospy.Service('/get_pose_summitxl_service', SummitXLPose , self.pose_service_callback) ...

def startPoseService(): ... summitpose = SummitXLPoseX() ...

That simple distintion between the python class name and the class name of the service solved my problem.


Originally posted by sisko with karma: 247 on 2021-02-19

This answer was ACCEPTED on the original site

Post score: 0