This section requires the catkin_ws to be initialized and the turtlebot_dabit package created.
Please click here to learn how to initialize the catkin workspace
This section requires the rosserial_arduino package to be setup.
Please click here to learn how to set up rosserial_arduino
As an example to receive data from the Arduino, we will have the Arduino print the milliseconds since it has started.
More information can be pulled up, here
/*
* rosserial Publisher Example
* Publishes the Arduino millis to the topic /arduino/millis
*/
/* Include the ROS library */
#include <ros.h>
/* Include the ROS message for an unsigned 32-bit integer
Arduino's millis() command returns a `long`,
which is an unsigned 32-bit integer */
#include <std_msgs/UInt32.h>
ros::NodeHandle nh;
std_msgs::UInt32 millis_msg;
ros::Publisher pub_millis("/arduino/millis", &millis_msg);
void setup()
{
// Initialize ROS Node
nh.initNode();
// Advertise the publisher topic
nh.advertise(pub_millis);
}
void loop()
{
// Set the millis_msg data to the millis() output
millis_msg.data = millis();
// Tell ROS to publish the data
pub_millis.publish( &millis_msg );
// Send the ROS message to the ROS Master
nh.spinOnce();
delay(5);
}
source ~/catkin_ws/devel/setup.sh
roslaunch turtlebot_dabit arduino.launch
rostopic list
rostopic info /arduino/millis
rostopic echo /arduino/millis
ROSSERIAL has recently improved their tutorials, and have a very wide selection of examples. Check out the ROSSerial_Arduino Tutorials