Subscriber failed Deserialization Error : Rosserial
HI, I'm trying to create a subscriber but I'm getting the following error
rosrun rosserial_python serial_node.py /dev/ttyACM0
[INFO] [1580450261.541002]: ROS Serial Python Node
[INFO] [1580450261.554769]: Connecting to /dev/ttyACM0 at 57600 baud
[INFO] [1580450263.710550]: Note: publish buffer size is 280 bytes
[INFO] [1580450263.711406]: Setup publisher on my_topic [dbw_mkz_msgs/SteeringCmd]
[INFO] [1580450263.720098]: Note: subscribe buffer size is 280 bytes
[INFO] [1580450263.721023]: Setup subscriber on /vehicle/steering_cmd [dbw_mkz_msgs/SteeringCmd]
Traceback (most recent call last):
File "/opt/ros/kinetic/lib/rosserial_python/serial_node.py", line 89, in <module>
client.run()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosserial_python/SerialClient.py", line 504, in run
self.callbacks[topic_id](msg)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosserial_python/SerialClient.py", line 107, in handlePacket
m.deserialize(data)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/dbw_mkz_msgs/msg/_SteeringCmd.py", line 133, in deserialize
raise genpy.DeserializationError(e) #most likely buffer underfill
genpy.message.DeserializationError: unpack requires a string argument of length 18
The code im using is as follows
#include <ros.h>
#include <dbw_mkz_msgs/SteeringCmd.h>
#include <std_msgs/Float64.h>
#include <std_msgs/Float32.h>
float t;
ros::NodeHandle nh;
dbw_mkz_msgs::SteeringCmd msg;
void messageCb(const dbw_mkz_msgs::SteeringCmd& msg1)
{
msg.count = msg1.count;
digitalWrite(13, HIGH - digitalRead(13));
}
ros::Subscriber<dbw_mkz_msgs::SteeringCmd> sub("/vehicle/steering_cmd", &messageCb);
ros::Publisher p("my_topic", &msg);
void setup()
{
Serial.begin(115200);
pinMode(13, OUTPUT);
nh.initNode();
nh.subscribe(sub);
nh.advertise(p);
}
void loop()
{
t = msg.count;
p.publish(&msg);
nh.spinOnce();
delay(1);
}
Any idea on what i'm doing wrong here?
Asked by alam121 on 2020-01-31 01:11:38 UTC
Comments
Just as in #q341697, you appear to have a very short
delay(1)
. Would be worth checking whether increasing that helps.Asked by gvdhoorn on 2020-01-31 03:21:24 UTC
Naah didn't work. It is not setting up the subscriber.
Asked by alam121 on 2020-02-02 02:10:25 UTC
Try removing the Serial.begin statement as that is setting the Serial speed to 115200; but your terminal output from your serial_node says it is reading data at 57600. A mismatch in speed will mean it cannot decode the data correctly.
Asked by nickw on 2020-02-05 01:48:11 UTC
That was my inital guess as well. However no it didn't work.
Asked by alam121 on 2020-02-05 02:16:17 UTC
Regardless of whether it fixed your issue: it needs to go, as what @nickw writes is true. It will never work this way.
Asked by gvdhoorn on 2020-02-05 03:35:45 UTC
The next thing I would try would be to change
to
as you are using t to set one of the fields in msg in the main loop and then publishing the message, but t will not be initialised to a known value until you receive a message on the topic you subscribe to.
Asked by nickw on 2020-02-05 04:22:41 UTC