ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

fake LaserScan on Arduino 2560 gives error Unable to sync with device possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino

asked 2015-06-24 21:42:51 -0500

charlie gravatar image

updated 2018-02-07 23:35:07 -0500

jayess gravatar image

Hi,

I am having trouble making LaserScan run on Arduino. I have modified the c version of the fake laserscan code to run on an Arduino Mega 2560 using Indigo rosserial. I am receiving the error

Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino.

I have reinstalled the ros_lib and confirmed other tutorials such as TEMP102 work correctly so I know the basic functionality is OK.

This is my procedure

Terminal 1 -

roscore
  • The ros core starts and run w/o error

Terminal 2

source /opt/ros/indigo/setup.bash
rosrun rosserial_python serial_node.py/dev/ttyACM0

after a few second I see the error as described above.

Here is my Arduino code for the fake laser.

#include "math.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif

// ROS includes
#include <ros.h>
#include <ros/time.h>
//#include<std_msgs/Float32.h>
#include <sensor_msgs/LaserScan.h>

sensor_msgs::LaserScan Laser_msg;
ros:: Publisher pub_Laser("LaserData", &Laser_msg);
ros::NodeHandle nh;

double ranges[100];
double Intensities[100];

void setup()
{
  nh.initNode();
  nh.advertise(pub_Laser);

  for (int z = 0 ; z<90; z++)
   {
      Laser_msg.ranges[z] = z/3;
      Laser_msg.intensities[z] = z/3;
   }
}

void loop()
{
   Laser_msg.header.stamp = nh.now();
 // Laser_msg.header.frame.id = "laser_frame";
  Laser_msg.angle_min = -1.57;  // start angle of the scan in Radians
  Laser_msg.angle_max = 1.57;  // stop angle of the scan in Radians
  Laser_msg.angle_increment = 0.34;   // angular distance between measurements in Radians 3.14/90
  Laser_msg.time_increment = 4; // seconds between measurements
  Laser_msg.range_min = 0.1;  // min dist in meters
  Laser_msg.range_max = 30;  // max dist in meters

  pub_Laser.publish(&Laser_msg);
  nh.spinOnce();
}

any help would be apprciated -C

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
2

answered 2015-06-27 15:54:30 -0500

ahendrix gravatar image

The rosserial wire protocol is not designed for very large messages. You may want to try publishing a smaller message and transform it into the desired message on the host computer.

edit flag offensive delete link more
0

answered 2016-11-22 14:31:16 -0500

hardy gravatar image

"publisher timer" needs to be of type long that is why it stops after a few cycles as the variable publisher_timer gets out of bound.

long publisher_timer

edit flag offensive delete link more
0

answered 2015-07-05 20:11:52 -0500

charlie gravatar image

updated 2015-07-07 22:28:29 -0500

I have come to realize that rosserial cannot handle large amount of data. I have been able to resolve some of my issues. I think it would be useful to see the fake laser example complete for the arduino just as an example on how to serialize the data variables properly. Therefore, I have restricted the data size to five ranges and intensities and continues to see if I can make this work.

The Groovy/ Hydro issue is resolved

  • I can now see the individual variables transferred correctly

  • I still have problems with 1) The range and intensities arrays are not handled correctly 2) The program hangs up after ~ 18 data transfers (probably runs out of memory)

Suggestions - C

Terminal 1

cd@M755:~$ roscore ... logging to /home/cd/.ros/log/8b28ee40-218d-11e5-9c0a-48f8b391f66d/roslaunch-M755-2182.log Checking log directory for disk usage. This may take awhile. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://M755:54111/ ros_comm version 1.11.13

SUMMARY

PARAMETERS * /rosdistro: indigo * /rosversion: 1.11.13

NODES

auto-starting new master process[master]: started with pid [2238] ROS_MASTER_URI=http://M755:11311/

setting /run_id to 8b28ee40-218d-11e5-9c0a-48f8b391f66d process[rosout-1]: started with pid [2251] started core service [/rosout]

Terminal 2

cd@M755:~$ source /opt/ros/indigo/setup.bash cd@M755:~$ rosrun rosserial_python serial_node.py /dev/ttyACM0 [INFO] [WallTime: 1435932768.452098] ROS Serial Python Node [INFO] [WallTime: 1435932768.456914] Connecting to /dev/ttyACM0 at 57600 baud /opt/ros/indigo/lib/python2.7/dist-packages/rosserial_python/SerialClient.py:336: SyntaxWarning: The publisher should be created with an explicit keyword argument 'queue_size'. Please see http://wiki.ros.org/rospy/Overview/Pu... for more information. self.pub_diagnostics = rospy.Publisher('/diagnostics', diagnostic_msgs.msg.DiagnosticArray) /opt/ros/indigo/lib/python2.7/dist-packages/rosserial_python/SerialClient.py:101: SyntaxWarning: The publisher should be created with an explicit keyword argument 'queue_size'. Please see http://wiki.ros.org/rospy/Overview/Pu... for more information. self.publisher = rospy.Publisher(self.topic, self.message) [INFO] [WallTime: 1435932771.823503] Note: publish buffer size is 512 bytes [INFO] [WallTime: 1435932771.824101] Setup publisher on LaserData [sensor_msgs/LaserScan]

Terminal 3

cd@M755:~$ rostopic echo LaserData header: seq: 1 stamp: secs: 1435932785 nsecs: 11943992 frame_id: laser_frame angle_min: -1.57000005245 angle_max: 1.57000005245 angle_increment: 0.785000026226 time_increment: 10.0 scan_time: 4.0 range_min: 0.10000000149 range_max: 30.0 ranges: [0.0, 1.0, 4.0, 9.00011920928955, 1.5519318162641656e-36]

intensities: [0.0, 1.0, 4.0, 9.00011920928955, 1.5519318162641656e-36]

. . .


header: seq: 18 stamp: secs: 1435932802 nsecs: 189945055 frame_id: laser_frame angle_min: -1.57000005245 angle_max: 1.57000005245 angle_increment: 0.785000026226 time_increment: 10.0 scan_time: 4.0 range_min: 0.10000000149 range_max: 30.0 ranges: [0.0, 1.0, 4.0, 9.00011920928955, 1.5519318162641656e-36]

intensities: [0.0, 1.0, 4.0, 9.00011920928955, 1.5519318162641656e-36]

#include "math.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif

// ROS includes
#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/LaserScan.h>

sensor_msgs::LaserScan CDLaser_msg;

//
float f_angle_min;
float f_angle_max;
float f_angle_increment;
float f_time_increment ...
(more)
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2015-06-24 21:42:51 -0500

Seen: 989 times

Last updated: Feb 07 '18