ros_indigo_arduino
1、arduino_IDE_setup
下载arduino-1.6.9-linux-64bit
解压
xz -d arduino-XXX-tar.xz
tar -xvf arduino-XXX.tar -C ~/SofeWare/arduino
2、Installing
the Sofeware
sudo apt-get install ros-indigo-rosserial-arduino
sudo apt-get install ros-indigo-rosserial
或源码安装
mkdir -p catkin_ws/src
cd catkin_ws/src
catkin_init_workspace
cd catkin_ws
catkin_make
cd catkin_ws/src
git clone https://github.com/ros-drivers/rosserial.git
cd catkin_ws
catkin_make
catkin_make install
source install/setup.bash
3、Install
ros_lib into the Arduino Environment
cd ~/Arduino/libraries/
rm -rf ros_lib
rosrun rosserial_arduino make_libraries.py .
4、安装完成
点开arduino_IDE在文件->示例出现ros_lib说明安装成功
5、example
publisher
/*
* rosserial Publisher Example
* Prints "hello world!"
*/
#include <ros.h>
#include <std_msgs/String.h>
ros::NodeHandle nh;
std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);
char hello[13] = "hello world!";
void setup()
{
nh.initNode();
nh.advertise(chatter);
}
void loop()
{
str_msg.data = hello;
chatter.publish( &str_msg );
nh.spinOnce();
delay(1000);
}
验证代码上传代码
上传权限
~/SoftWare/arduino/arduino-1.6.9$ ll /dev/ttyACM0
crw-rw---- 1 root dialout 166, 0 Aug 14 18:15 /dev/ttyACM0
更改用户组
sudo usermod -a -G dialout shuifu
6、演示
roscore
rosrun rosserial_python serial_node.py /dev/ttyACM0
rostopic echo chatter 7、example subscriber
/*
* rosserial Subscriber Example
* Blinks an LED on callback
*/
#include <ros.h>
#include <std_msgs/Empty.h>
ros::NodeHandle nh;
void messageCb( const std_msgs::Empty& toggle_msg){
digitalWrite(13, HIGH-digitalRead(13)); // blink the led
}
ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );
void setup()
{
pinMode(13, OUTPUT);
nh.initNode();
nh.subscribe(sub);
}
void loop()
{
nh.spinOnce();
delay(1);
}
8、演示
roscore
rosrun rosserial_python serial_node.py /dev/ttyACM0
rostopic pub toggle_led std_msgs/Empty --once
9、Push Button
/*
* Button Example for Rosserial
*/
#include <ros.h>
#include <std_msgs/Bool.h>
ros::NodeHandle nh;
std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);
const int button_pin = 7;
const int led_pin = 13;
bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;
void setup()
{
nh.initNode();
nh.advertise(pub_button);
//initialize an LED output pin
//and a input pin for our push button
pinMode(led_pin, OUTPUT);
pinMode(button_pin, INPUT);
//Enable the pullup resistor on the button
digitalWrite(button_pin, HIGH);
//The button is a normally button
last_reading = ! digitalRead(button_pin);
}
void loop()
{
bool reading = ! digitalRead(button_pin);
if (last_reading!= reading){
last_debounce_time = millis();
published = false;
}
//if the button value has not changed during the debounce delay
// we know it is stable
if ( !published && (millis() - last_debounce_time) > debounce_delay) {
digitalWrite(led_pin, reading);
pushed_msg.data = reading;
pub_button.publish(&pushed_msg);
published = true;
}
last_reading = reading;
nh.spinOnce();
}
10、演示
roscore
rosrun rosserial_python serial_node.py /dev/ttyACM0
rostopic list
/diagnostics
/pusher
/rosout
/rosout_agg
rostopic echo /pusher
data: True
---
data: False
---
data: True
---
data: False
11、Arduino Oscilloscope(示波器)
/*
* rosserial ADC Example
*
* This is a poor man's Oscilloscope. It does not have the sampling
* rate or accuracy of a commerical scope, but it is great to get
* an analog value into ROS in a pinch.
*/
#include <Arduino.h>
#include <ros.h>
#include <rosserial_arduino/Adc.h>
ros::NodeHandle nh;
rosserial_arduino::Adc adc_msg;
ros::Publisher p("adc", &adc_msg);
void setup()
{
pinMode(13, OUTPUT);
nh.initNode();
nh.advertise(p);
}
//We average the analog reading to eliminate some of the noise
int averageAnalog(int pin){
int v=0;
for(int i=0; i<4; i++) v+= analogRead(pin);
return v/4;
}
long adc_timer;
void loop()
{
adc_msg.adc0 = averageAnalog(0);
adc_msg.adc1 = averageAnalog(1);
adc_msg.adc2 = averageAnalog(2);
adc_msg.adc3 = averageAnalog(3);
adc_msg.adc4 = averageAnalog(4);
adc_msg.adc5 = averageAnalog(5);
p.publish(&adc_msg);
nh.spinOnce();
}
12、演示
roscore
rqt_plot
rosrun rosserial_python serial_node.py /dev/ttyACM0
rostopic list
/adc
/diagnostics
/rosout
/rosout_agg
rqt_plot adc
13、lightSensor
#include <ros.h>
#include <std_msgs/UInt16.h>
ros::NodeHandle nh;
std_msgs::UInt16 light_msg;
ros::Publisher light("lightSensor", &light_msg);
void setup() {
// put your setup code here, to run once:
Serial.begin(57600); //open serial port, set the baud rate to 57600 bps
nh.initNode();
nh.advertise(light);
}
void loop() {
// put your main code here, to run repeatedly:
int val;
val = analogRead(0); // connect grayscale sensor to Analog 0
Serial.println(val, DEC); // print the value to serial
light_msg.data = val;
light.publish(&light_msg);
nh.spinOnce();
delay(100);
}
14、演示
roscore
rosrun rosserial_python serial_node.py /dev/ttyACM0
rostopic echo /lightSensor
15、keyTouch(按键传感器)
#include <Wire.h>
#include <mpr121.h>
#include <ros.h>
#include <std_msgs/Int32.h>
int key = 0;
ros::NodeHandle nh;
std_msgs::Int32 num_msg;
ros::Publisher pub_num("inputNum", &num_msg);
void setup() {
// put your setup code here, to run once:
nh.initNode();
nh.advertise(pub_num);
Serial.begin(19200);
Wire.begin();
CapaTouch.begin();
delay(500);
Serial.println("START");
}
void loop() {
// put your main code here, to run repeatedly:
key = CapaTouch.keyPad();
if(key == 11)
{
Serial.print("key:");
Serial.println("*");
}
else if(key == 12)
{
Serial.print("key:");
Serial.println("#");
}
else if(key >= 0)
{
Serial.print("key:");
Serial.println(key);
}
delay(200);
num_msg.data = key;
pub_num.publish(&num_msg);
nh.spinOnce();
delay(200);
}
16、演示
roscore
rosrun rosserial_python serial_node.py /dev/ttyACM0
rostopic echo /inputNum