ROS (Robot Operating System) provides libraries and tools to help software developers create robot applications. ROS is released under the terms of the BSD license, and is open source software. It is free for commercial and research use. Most of my future tutorials will be based on ROS.
A small custom robot integrated with ROS can help you make various project easily and effectively.
Today's tutorial will be on making ROS node for SparkV robot. The prerequisite for this tutorial is basic understanding of ROS and SparkV robot.
Package summary :
ROS_SparkV is basic ROS package that integrates SparkV robot and ROS. It is build using rosserial Stack. It lets you to send velocity commands to SparkV and read states of various sensors and position encoders.
Installation :
Download the beta testing version of hex file for ATmega32. Upload it and use it, it's as simple as this. Also you need to have sparkV_msg package in your ros workspace and make this package using rosmake.
Due less SRAM (1kb) in ATmega16, the first version of code does not work reliably with ATmega16.
Source code will be released soon.
Published topics:
sparkV (sparkV_msg/sparkV)
SparkV sensors values, battery voltage, buzzer state, encoders reading are published on this topic. Default publishing frequency is 10Hz.
Subscribed topics :
motor (sparkV_msg/velocity)
receives velocity commands.
buzzer (std_msgs/bool)
receives buzzer on/off signal.
Message types :
uint8 LlS
uint8 ClS
uint8 RlS
uint8 Lir
uint8 Cir
uint8 Rir
uint8 bat
bool buz
uint16 tL
uint16 tR
Message description:
LlS Left line sensor current reading
ClS Center line sensor current reading
RlS Right line sensor current reading
Lir Left IR sensor current reading
Cir Center IR sensor current reading
Rir Right IR sensor current reading
bat Battery current voltage reading ( in scale of 0 to 255 )
buz Buzzer present state on or off
tL Left position encoder reading
tR Right position encoder reading
bool left
bool right
bool start
bool s2L
bool s1L
bool s0L
bool s2R
bool s1R
bool s0R
Message description:
left To rotate left motor, true means in fwd direction false means in backward direction
right To rotate right motor, true means in fwd direction false means in backward direction
start To enable motors, true means motor enabled, false means disabled.
s2L To control speed of left motor, 8 possible speed combination are available selected using s2L (MSB) , s1L, s0L (LSB)
s1L
s0L
s2R To control speed of right motor, 8 possible speed combination are available selected using s2R (MSB) , s1R, s0R (LSB)
s1R
s0R
Usage :
In a terminal window, launch roscore
roscore
Start the rosserial client (replace /dev/ttyUSB0 with the serial port your SparkV is connected to (serial port can be checked by command : dmesg | grep tty):
rosrun rosserial_python serial_node.py /dev/ttyUSB0
Now see the sensor state using
rostopic echo /sparkV
Testing steps:
- To turn on buzzer
rostopic echo /sparkV
- To rotate both motors forward with full speed
rostopic pub -1 /motor sparkV_msg/velocity -- true true true true true true true true true
- To rotate both motors backward with full speed
rostopic pub -1 /motor sparkV_msg/velocity -- true true true true true true true true true
- To rotate both motors forward at half speed
rostopic pub -1 /motor sparkV_msg/velocity -- true true true true false false true false false
NOTE:If you are using Xbee, it must be configured for 57600 baud rate.
Using the above node we controlled SparkV using android phone's accelerometer!.
Comments and feedback are welcomed :)
More on PlaywithRobots
avr-tutorials
- Introduction to AVR microcontrollers
- Basic hardware and software required for AVR
- AVR fuse bits
- Input/Output Concept