• ROS之arduino交互


    一、第一种安装方式(不支持自定义消息)

    第一步打开官网

    http://wiki.ros.org/rosserial_arduino/Tutorials/Arduino%20IDE%20Setup

    第二步按第一种方式安装

    第三步生成arduino ros库

    第四步编译arduino等等等

    二、第一种安装方式的问题

    一切正常了吧,但如果使用自定义数据类型,会发现source /opt/ros/indigo/setup.bash会找不到在catkin_ws中的自定义类型。

    但如果使用source catkin_ws/devel/setup.bash,你会发现无法找到ros_rosserial这个包。

    所以需要再进行一次第二种安装(也许第一种还有其他改进方法)

    三、接着进行第二种安装方式

    之后可以开始自定义消息类型了

    四、自定义消息类型

    参见官网

    http://wiki.ros.org/ROS/Tutorials/CreatingMsgAndSrv

    在自己包里创建自定义数据类型后,catkin_make

    重复一中的第三步,生成arduino ros库,之后就会在arduino的roslibaray中找到自定义消息类型的.h文件了。

    如图mycat包中cat自定义消息类型

    四、如果只用第二种方法

    用第二种方法安装ros_rosserial,在生成arduino ros库后,arduino无法编译ros内容

    五、备注

    也许是我出错了

    我第一个电脑中默认source catkin_ws/devel/setup.bash

    但后来只用第二种方法时忘了source究竟是不是指向了catkin_ws/devel/setup.bash

    第一种方法是否还可以挽救下??使用rospack profile。

    六、arduino代码

    事实上在rosrun rosserial_python serial_node.py /dev/ttyUSB0后

    在arduino端生成一个节点,含有发布器或订阅器。

    代码里的数据类型就是ros里的消息类型,必须先导入消息的头文件。

    七、发布器(publisher)(多线程)

    *
    * rosserial Publisher Example
    * Prints "hello world!"
    */
    #include <NewPing.h>
    #include <ros.h>
    #include <std_msgs/Float32.h>
    
    ros::NodeHandle nh;
    const int TrigPin2 = 4;
    const int EchoPin2 = 5; 
    const int TrigPin1 = 2;
    const int EchoPin1 = 3; 
    const int TrigPin3= 8;
    const int EchoPin3 = 9; 
    std_msgs::Float32 str_msg1;
    std_msgs::Float32 str_msg2;
    std_msgs::Float32 str_msg3;
    ros::Publisher chatter1("chatter1", &str_msg1);
    ros::Publisher chatter2("chatter2", &str_msg2);
    ros::Publisher chatter3("chatter3", &str_msg3);
    float distance1; 
    float distance2;
    float distance3;
    NewPing sonar1(TrigPin1, EchoPin1, 200); 
    NewPing sonar2(TrigPin2, EchoPin2, 200); 
    NewPing sonar3(TrigPin3, EchoPin3, 200); 
    void setup()
    {
    // 初始化串口通信及连接SR04的引脚
    Serial.begin(9600); Serial.println("Ultrasonic sensor:");
    
    
    
    
    nh.initNode();
    nh.advertise(chatter1);
    nh.advertise(chatter2);
    nh.advertise(chatter3);
    }
    
    void loop()
    {
    distance1 = sonar1.ping_cm();
    str_msg1.data =distance1;
    chatter1.publish( &str_msg1 );
    
    
    // 检测脉冲宽度,并计算出距离
    distance2 = sonar2.ping_cm();
    str_msg2.data =distance2;
    chatter2.publish( &str_msg2 );
    
    
    distance3 = sonar3.ping_cm();
    str_msg3.data =distance3;
    chatter3.publish( &str_msg3);
    
    
    nh.spinOnce();
    delay(15);
    }
    

    八、订阅器

    实例一无参实例


    /*
    * rosserial Subscriber Example
    * Blinks an LED on callback
    */
    
    #include <Servo.h> 
    #include <ros.h>
    #include <std_msgs/Empty.h>
    Servo myservo; 
    ros::NodeHandle nh;
    int pos;
    
    void messageCb( const std_msgs::Empty& toggle_msg){
    digitalWrite(13, HIGH-digitalRead(13)); // blink the led
    for(pos = 0; pos < 180; pos += 1) // goes from 0 degrees to 180 degrees 
    { // in steps of 1 degree 
    myservo.write(pos); // tell servo to go to position in variable 'pos' 
    delay(15); // waits 15ms for the servo to reach the position 
    } 
    for(pos = 180; pos>=1; pos-=1) // goes from 180 degrees to 0 degrees 
    { 
    myservo.write(pos); // tell servo to go to position in variable 'pos' 
    delay(15); // waits 15ms for the servo to reach the position 
    } 
    }
    
    ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );
    ///toggle_led is pubisher in ros
    
    void setup()
    { myservo.attach(9); 
    pinMode(13, OUTPUT);
    nh.initNode();
    nh.subscribe(sub);
    }
    
    void loop()
    {
    nh.spinOnce();
    delay(1);
    }
    
    在nh节点激活后
    void messageCb()函数会被调用执行。
    

    实例二有参实例

    *
    * rosserial Servo Control Example
    *
    * This sketch demonstrates the control of hobby R/C servos
    * using ROS and the arduiono
    * 
    * For the full tutorial write up, visit
    * www.ros.org/wiki/rosserial_arduino_demos
    *
    * For more information on the Arduino Servo Library
    * Checkout :
    * http://www.arduino.cc/en/Reference/Servo
    */
    
    #if defined(ARDUINO) && ARDUINO >= 100
    #include "Arduino.h"
    #else
    #include <WProgram.h>
    #endif
    
    #include <Servo.h> 
    #include <ros.h>
    #include <std_msgs/UInt16.h>
    
    ros::NodeHandle nh;
    
    Servo servo;
    
    void servo_cb( const std_msgs::UInt16& cmd_msg){
    servo.write(cmd_msg.data); //set servo angle, should be from 0-180 
    digitalWrite(13, HIGH-digitalRead(13)); //toggle led 
    }
    
    
    ros::Subscriber<std_msgs::UInt16> sub("servo", servo_cb);
    
    void setup(){
    pinMode(13, OUTPUT);
    
    nh.initNode();
    nh.subscribe(sub);
    servo.attach(9); //attach it to pin 9
    }
    
    void loop(){
    nh.spinOnce();
    delay(1);
    }

    九、自定义消息类型

    (原ros_rosserial自带adc.h自定义消息类型)(自定义消息还可以,但自定义数组一直搞不定)

    发布器

    #include <ros.h>
    #include <mycat/cat.h>
    
    ros::NodeHandle nh;
    
    mycat::cat cat_msg;
    ros::Publisher p("cat", &cat_msg);
    
    void setup()
    { 
    
    nh.initNode();
    
    nh.advertise(p);
    }
    
    //We average the analog reading to elminate some of the noise
    
    void loop()
    {
    cat_msg.num = 1;
    cat_msg.num1 = 2;
    cat_msg.num2 = 3;
    cat_msg.num3 = 4;
    p.publish(&cat_msg);
    
    nh.spinOnce();
    }
    
    
    订阅器
    
    #include <Servo.h> 
    #include <ros.h>
    #include <mycat/cat.h>
    
    ros::NodeHandle nh;
    
    Servo servo;
    
    void servo_cb( const mycat::cat& cmd_msg){
    servo.write(cmd_msg.num); //set servo angle, should be from 0-180 
    delay(1000); 
    servo.write(cmd_msg.num1); //set servo angle, should be from 0-180 
    delay(1000); 
    servo.write(cmd_msg.num2); //set servo angle, should be from 0-180 
    delay(1000); 
    servo.write(cmd_msg.num3); //set servo angle, should be from 0-180 
    delay(1000); 
    
    }
    
    
    ros::Subscriber<mycat::cat> sub("cat", servo_cb);
    
    void setup(){
    
    
    nh.initNode();
    nh.subscribe(sub);
    servo.attach(9); //attach it to pin 9
    }
    
    void loop(){
    nh.spinOnce();
    delay(100);
    }
    
    





  • 相关阅读:
    I/O中断处理详细过程
    移动端事件touchstart、touchmove、touchend
    页面刷新整理
    transform:rotate在手机上显示有锯齿的解决方案大全
    CSS3盒模型温故
    CSS3颜色特征温故
    CSS3文本温故
    CSS3背景温故
    怪诞咖啡的简介
    CSS3边框温故
  • 原文地址:https://www.cnblogs.com/fengmao31/p/13880194.html
Copyright © 2020-2023  润新知