Rosserial checksum error
When running "rosrun rosserial_python serial_node.py /dev/ttyACM0" I get the error message "wrong checksum for topic id and msg". After that it may continue to connect but the error "Serial Port read returned short (expected 78 bytes, received 5 instead)." comes up, or it may just not connect and keep trying. Whats weirder is if I restart the PC and run the code it works fine, I can launch RVIZ, with "roslaunch robot_description robot_description.py" and it will show me the range sensor and move about as i move my hand to and from the sensor. The next time I run it I get the above errors.
The code I am using is below. pretty basic for the tf stuff, really just copied the arduino copy as a test
//////////////////LIBRARIES///////////////////
#include <NewPing.h>
#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>
#include <tf/transform_broadcaster.h>
//////////////////LIBRARIES///////////////////
//////////////////ROS Vars and OBJECTS///////////////////
ros::NodeHandle nh;
sensor_msgs::Range range_msg;
ros::Publisher pub_range( "/ultrasound", &range_msg);
geometry_msgs::TransformStamped t;
tf::TransformBroadcaster sonar_broadcaster;
char base_link[] = "/base_link"; //set the TF child frame
char odom[] = "/odom";
char frameid[] = "/ultrasound";
//////////////////ROS Vars and OBJECTS///////////////////
//////////////////SONAR Vars and OBJECT///////////////////
int sonar_pin =12;
NewPing sensor(sonar_pin, sonar_pin, 25);
//////////////////SONAR Vars and OBJECT///////////////////
void setup()
{
nh.initNode();
nh.advertise(pub_range);
sonar_broadcaster.init(nh);
t.header.frame_id = frameid;
t.child_frame_id = base_link;
range_msg.radiation_type = sensor_msgs::Range::ULTRASOUND; //set the message type and the sensor radiation type
range_msg.header.frame_id = frameid;
range_msg.field_of_view = (10.0/180.0) * 3.14;
range_msg.min_range = 0.0;
range_msg.max_range = 10;
digitalWrite(sonar_pin, HIGH); //turn internal pull-up resistor on
}
long range_time;
void loop()
{
//publish the adc value every 50 milliseconds
//since it takes that long for the sensor to stablize
if ( millis() >= range_time )
{
t.header.frame_id = frameid;
t.child_frame_id = base_link;
t.transform.translation.x = 1.0;
t.transform.rotation.x = 0.0;
t.transform.rotation.y = 0.0;
t.transform.rotation.z = 0.0;
t.transform.rotation.w = 1.0;
t.header.stamp = nh.now();
sonar_broadcaster.sendTransform(t);
range_msg.range = sensor.ping_in();
range_msg.header.stamp = nh.now();
pub_range.publish(&range_msg);
range_time = millis() + 28;
}
nh.spinOnce();
}