rossrv - cannot deserialize custom msg
Hello all,
I am trying to create a node service with custom messages. Let me start with the messages:
I have pose.msg
float32 xx
float32 yy
float32 zz
float32 roll
float32 pitch
float32 yaw
and movement.msg
float32 distance
float32 angle
these files are in <package_anme>/msg folder. I also added message_generation and message_runtime where ever needed in the CMakeLists.txt and package.xml.
Also in the CMakeLists.txt I have added:
add_message_files(
FILES
pose.msg
movement.msg
)
Now for the service. The file motion.srv is located in the srv folder and containes the following code:
pose p
movement m
---
pose pb
In the CMakeLists.txt I have added:
add_service_files(
FILES
motion.srv
)
Not sure how important but the CMakeLists.txt has:
generate_messages(
DEPENDENCIES
std_msgs
)
So now lets go to the code. I am using rospy. My package name is otacon.
The Service Node:
#!/usr/bin/env python
import rospy
from otacon.srv import *
import otacon.msg as ms
def forward(robot):
x = robot.p.xx
y = robot.p.yy
theta = robot.p.yaw
d = robot.m.distance
ntheta = robot.m.angle
… do some stuff ...
npose = ms.pose
npose.xx = x+Dx+Dx*q
npose.yy = y+Dy+Dy*q
npose.zz = 0
npose.roll = 0
npose.pitch = 0
npose.yaw = ntheta+Dtheta+Dtheta*q
return (npose)
def motion_server():
rospy.init_node('motion_model_server')
s = rospy.Service('motion_model', motion, forward)
print "Ready to move robot"
rospy.spin()
if __name__ == "__main__":
motion_server()
and the client node is as follows:
#!/usr/bin/env python
import rospy
from otacon.srv import *
import otacon.msg as ms
def move(Pose, action)
rospy.wait_for_service('motion_model')
try:
motion_model = rospy.ServiceProxy('motion_model', motion)
pp = ms.pose
mm = ms.movement
pp.xx = Pose[0]
pp.yy = Pose[1]
pp.zz = Pose[2]
pp.roll = Pose[3]
pp.pitch = Pose[4]
pp.yaw = Pose[5]
mm.distance = action[0]
mm.angle = action[1]
l = motion_model(pp,mm)
except rospy.ServiceException, e:
print "Motion failed: %s"%e
move([1,2,3,4,5,6],[1,1.5707])
The error I get is
Motion failed: transport error completing service call: receive_once[/motion_model]: DeserializationError cannot deserialize: 'pose' object attribute 'xx' is read-only
I have spend the last 2 hours trying to find a solution but nothing. Every time I fixed something, I got a different error. This is the farthest I was able to get. I am very tired now so sorry if I misses some important information. I really hope somebody can help me. I don't know what else to do :/. Also if there are any improvements I can do on the current code (so I have less of it) please tell me.
I'm having similar a similar issue. Did you ever figure this out?
Looks like the issue comes from de-serializing the values. I have same issue when doing a
rosservice call
or viarqt
, but when calling the service in c++ code it seams to work.