Custom Message with uint8[] Reads as string dtype
I'm trying to pass a custom message through a service . I have a C++ node using this service just fine, however in Python I can't seem to pull information from the custom message. When I try to take the passed array, it reads it as a 'str' type. Is there anything I am doing wrong here?
Edit: in Visual Studio Code, when I create a variable field = DensityField() and type "field.data", hovering over "data" reveals that it thinks its a string. Is it possible to force catkin_make to regenerate the messages? I have no idea why it thinks its a string.
GetDensity.srv:
---
DensityField densityfield
DensityField.msg:
uint8 width
uint8 height
uint8[] data
Service Client:
def get_density():
"""
:rtype: list[int]
"""
rospy.wait_for_service("static_density")
try:
get_density = rospy.ServiceProxy("static_density", GetDensity)
resp = get_density()
return resp.densityfield
except rospy.ServiceException as e:
rospy.logerr("static_density server is not responding: %s" % (e))
...
density = get_density()
occupancy_grid = get_map()
print(type(density)) # Prints <class 'voronoi_msgs.msg._DensityField.DensityField'>
print(type(occupancy_grid)) # Prints <class 'nav_msgs.msg._OccupancyGrid.OccupancyGrid'>
print(density.data[0] + density.data[1])
np_density = np.array(density.data)
np_density_filtered = np.multiply(np_density, np_og)
# Gives error TypeError: ufunc 'multiply' did not contain a loop with signature matching types dtype('S62500') dtype('S62500') dtype('S62500')
The server:
data = []
width = 0
height = 0
def handle_density_request(msg):
global data, width, height
response = DensityField()
response.data = data
response.height = height
response.width = width
print(type(data)) # Prints <type 'list'>
print(type(data[0])) # Prints <type 'int'>
return GetDensityResponse(
densityfield=response
)
def main():
global data, width, height
rospy.init_node("density_server")
rospy.Service("static_density", GetDensity, handle_density_request)
rospack = rospkg.RosPack()
path = rospack.get_path('voronoi_node_generator') + \
'/data/' + rospy.get_param("~data_name")
img = cv2.imread(path, 0)
print(img)
img = np.flip(img, 0)
height, width = img.shape
img = img.flatten()
data = img.tolist()
rospy.loginfo("Data length: %d | Width: %d | Height: %d" %
(len(data), width, height))
rospy.loginfo("Data type: %s" % img.dtype)
rospy.spin()
Not sure, but #q59827 and #q341940 are probably duplicates.