ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_jade

ROSSerial_mbed for Jade Distribution

The Robot Operating System (ROS) is a flexible framework for writing robot software. It is a collection of tools, libraries, and conventions that aim to simplify the task of creating complex and robust robot behavior across a wide variety of robotic platforms.

The rosserial_mbed package allows to write ROS nodes on any mbed enabled devices and have them connected to a running ROS system on your computer using the serial port.

Hello World (example publisher)

Import programrosserial_mbed_hello_world_publisher_jade

rosserial_mbed Hello World example for jade distribution

Running the Code

Now, launch the roscore in a new terminal window:

Quote:

$ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

Quote:

$ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

Quote:

$ rostopic echo chatter

See Also

More examples

Blink

/*
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle nh;
DigitalOut myled(LED1);

void messageCb(const std_msgs::Empty& toggle_msg){
    myled = !myled;   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);

    while (1) {
        nh.spinOnce();
        wait_ms(1);
    }
}

Push

/*
 * Button Example for Rosserial
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Bool.h>

PinName button = p20;

ros::NodeHandle nh;

std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);

DigitalIn button_pin(button);
DigitalOut led_pin(LED1);

bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;

Timer t;
int main() {
    t.start();
    nh.initNode();
    nh.advertise(pub_button);

    //Enable the pullup resistor on the button
    button_pin.mode(PullUp);

    //The button is a normally button
    last_reading = ! button_pin;

    while (1) {
        bool reading = ! button_pin;

        if (last_reading!= reading) {
            last_debounce_time = t.read_ms();
            published = false;
        }

        //if the button value has not changed for the debounce delay, we know its stable
        if ( !published && (t.read_ms() - last_debounce_time)  > debounce_delay) {
            led_pin = reading;
            pushed_msg.data = reading;
            pub_button.publish(&pushed_msg);
            published = true;
        }

        last_reading = reading;

        nh.spinOnce();
    }
}
Committer:
garyservin
Date:
Thu Mar 31 23:23:15 2016 +0000
Revision:
0:a906bb7c7831
ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:a906bb7c7831 1 /*
garyservin 0:a906bb7c7831 2 * Software License Agreement (BSD License)
garyservin 0:a906bb7c7831 3 *
garyservin 0:a906bb7c7831 4 * Copyright (c) 2011, Willow Garage, Inc.
garyservin 0:a906bb7c7831 5 * All rights reserved.
garyservin 0:a906bb7c7831 6 *
garyservin 0:a906bb7c7831 7 * Redistribution and use in source and binary forms, with or without
garyservin 0:a906bb7c7831 8 * modification, are permitted provided that the following conditions
garyservin 0:a906bb7c7831 9 * are met:
garyservin 0:a906bb7c7831 10 *
garyservin 0:a906bb7c7831 11 * * Redistributions of source code must retain the above copyright
garyservin 0:a906bb7c7831 12 * notice, this list of conditions and the following disclaimer.
garyservin 0:a906bb7c7831 13 * * Redistributions in binary form must reproduce the above
garyservin 0:a906bb7c7831 14 * copyright notice, this list of conditions and the following
garyservin 0:a906bb7c7831 15 * disclaimer in the documentation and/or other materials provided
garyservin 0:a906bb7c7831 16 * with the distribution.
garyservin 0:a906bb7c7831 17 * * Neither the name of Willow Garage, Inc. nor the names of its
garyservin 0:a906bb7c7831 18 * contributors may be used to endorse or promote prducts derived
garyservin 0:a906bb7c7831 19 * from this software without specific prior written permission.
garyservin 0:a906bb7c7831 20 *
garyservin 0:a906bb7c7831 21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
garyservin 0:a906bb7c7831 22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
garyservin 0:a906bb7c7831 23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
garyservin 0:a906bb7c7831 24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
garyservin 0:a906bb7c7831 25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
garyservin 0:a906bb7c7831 26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
garyservin 0:a906bb7c7831 27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
garyservin 0:a906bb7c7831 28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
garyservin 0:a906bb7c7831 29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
garyservin 0:a906bb7c7831 30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
garyservin 0:a906bb7c7831 31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
garyservin 0:a906bb7c7831 32 * POSSIBILITY OF SUCH DAMAGE.
garyservin 0:a906bb7c7831 33 */
garyservin 0:a906bb7c7831 34
garyservin 0:a906bb7c7831 35 #ifndef ROS_NODE_HANDLE_H_
garyservin 0:a906bb7c7831 36 #define ROS_NODE_HANDLE_H_
garyservin 0:a906bb7c7831 37
garyservin 0:a906bb7c7831 38 #include <stdint.h>
garyservin 0:a906bb7c7831 39
garyservin 0:a906bb7c7831 40 #include "std_msgs/Time.h"
garyservin 0:a906bb7c7831 41 #include "rosserial_msgs/TopicInfo.h"
garyservin 0:a906bb7c7831 42 #include "rosserial_msgs/Log.h"
garyservin 0:a906bb7c7831 43 #include "rosserial_msgs/RequestParam.h"
garyservin 0:a906bb7c7831 44
garyservin 0:a906bb7c7831 45 #define SYNC_SECONDS 5
garyservin 0:a906bb7c7831 46
garyservin 0:a906bb7c7831 47 #define MODE_FIRST_FF 0
garyservin 0:a906bb7c7831 48 /*
garyservin 0:a906bb7c7831 49 * The second sync byte is a protocol version. It's value is 0xff for the first
garyservin 0:a906bb7c7831 50 * version of the rosserial protocol (used up to hydro), 0xfe for the second version
garyservin 0:a906bb7c7831 51 * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable
garyservin 0:a906bb7c7831 52 * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy
garyservin 0:a906bb7c7831 53 * rosserial_arduino. It must be changed in both this file and in
garyservin 0:a906bb7c7831 54 * rosserial_python/src/rosserial_python/SerialClient.py
garyservin 0:a906bb7c7831 55 */
garyservin 0:a906bb7c7831 56 #define MODE_PROTOCOL_VER 1
garyservin 0:a906bb7c7831 57 #define PROTOCOL_VER1 0xff // through groovy
garyservin 0:a906bb7c7831 58 #define PROTOCOL_VER2 0xfe // in hydro
garyservin 0:a906bb7c7831 59 #define PROTOCOL_VER PROTOCOL_VER2
garyservin 0:a906bb7c7831 60 #define MODE_SIZE_L 2
garyservin 0:a906bb7c7831 61 #define MODE_SIZE_H 3
garyservin 0:a906bb7c7831 62 #define MODE_SIZE_CHECKSUM 4 // checksum for msg size received from size L and H
garyservin 0:a906bb7c7831 63 #define MODE_TOPIC_L 5 // waiting for topic id
garyservin 0:a906bb7c7831 64 #define MODE_TOPIC_H 6
garyservin 0:a906bb7c7831 65 #define MODE_MESSAGE 7
garyservin 0:a906bb7c7831 66 #define MODE_MSG_CHECKSUM 8 // checksum for msg and topic id
garyservin 0:a906bb7c7831 67
garyservin 0:a906bb7c7831 68
garyservin 0:a906bb7c7831 69 #define MSG_TIMEOUT 20 //20 milliseconds to recieve all of message data
garyservin 0:a906bb7c7831 70
garyservin 0:a906bb7c7831 71 #include "msg.h"
garyservin 0:a906bb7c7831 72
garyservin 0:a906bb7c7831 73 namespace ros {
garyservin 0:a906bb7c7831 74
garyservin 0:a906bb7c7831 75 class NodeHandleBase_{
garyservin 0:a906bb7c7831 76 public:
garyservin 0:a906bb7c7831 77 virtual int publish(int id, const Msg* msg)=0;
garyservin 0:a906bb7c7831 78 virtual int spinOnce()=0;
garyservin 0:a906bb7c7831 79 virtual bool connected()=0;
garyservin 0:a906bb7c7831 80 };
garyservin 0:a906bb7c7831 81 }
garyservin 0:a906bb7c7831 82
garyservin 0:a906bb7c7831 83 #include "publisher.h"
garyservin 0:a906bb7c7831 84 #include "subscriber.h"
garyservin 0:a906bb7c7831 85 #include "service_server.h"
garyservin 0:a906bb7c7831 86 #include "service_client.h"
garyservin 0:a906bb7c7831 87
garyservin 0:a906bb7c7831 88 namespace ros {
garyservin 0:a906bb7c7831 89
garyservin 0:a906bb7c7831 90 using rosserial_msgs::TopicInfo;
garyservin 0:a906bb7c7831 91
garyservin 0:a906bb7c7831 92 /* Node Handle */
garyservin 0:a906bb7c7831 93 template<class Hardware,
garyservin 0:a906bb7c7831 94 int MAX_SUBSCRIBERS=25,
garyservin 0:a906bb7c7831 95 int MAX_PUBLISHERS=25,
garyservin 0:a906bb7c7831 96 int INPUT_SIZE=512,
garyservin 0:a906bb7c7831 97 int OUTPUT_SIZE=512>
garyservin 0:a906bb7c7831 98 class NodeHandle_ : public NodeHandleBase_
garyservin 0:a906bb7c7831 99 {
garyservin 0:a906bb7c7831 100 protected:
garyservin 0:a906bb7c7831 101 Hardware hardware_;
garyservin 0:a906bb7c7831 102
garyservin 0:a906bb7c7831 103 /* time used for syncing */
garyservin 0:a906bb7c7831 104 uint32_t rt_time;
garyservin 0:a906bb7c7831 105
garyservin 0:a906bb7c7831 106 /* used for computing current time */
garyservin 0:a906bb7c7831 107 uint32_t sec_offset, nsec_offset;
garyservin 0:a906bb7c7831 108
garyservin 0:a906bb7c7831 109 uint8_t message_in[INPUT_SIZE];
garyservin 0:a906bb7c7831 110 uint8_t message_out[OUTPUT_SIZE];
garyservin 0:a906bb7c7831 111
garyservin 0:a906bb7c7831 112 Publisher * publishers[MAX_PUBLISHERS];
garyservin 0:a906bb7c7831 113 Subscriber_ * subscribers[MAX_SUBSCRIBERS];
garyservin 0:a906bb7c7831 114
garyservin 0:a906bb7c7831 115 /*
garyservin 0:a906bb7c7831 116 * Setup Functions
garyservin 0:a906bb7c7831 117 */
garyservin 0:a906bb7c7831 118 public:
garyservin 0:a906bb7c7831 119 NodeHandle_() : configured_(false) {
garyservin 0:a906bb7c7831 120
garyservin 0:a906bb7c7831 121 for(unsigned int i=0; i< MAX_PUBLISHERS; i++)
garyservin 0:a906bb7c7831 122 publishers[i] = 0;
garyservin 0:a906bb7c7831 123
garyservin 0:a906bb7c7831 124 for(unsigned int i=0; i< MAX_SUBSCRIBERS; i++)
garyservin 0:a906bb7c7831 125 subscribers[i] = 0;
garyservin 0:a906bb7c7831 126
garyservin 0:a906bb7c7831 127 for(unsigned int i=0; i< INPUT_SIZE; i++)
garyservin 0:a906bb7c7831 128 message_in[i] = 0;
garyservin 0:a906bb7c7831 129
garyservin 0:a906bb7c7831 130 for(unsigned int i=0; i< OUTPUT_SIZE; i++)
garyservin 0:a906bb7c7831 131 message_out[i] = 0;
garyservin 0:a906bb7c7831 132
garyservin 0:a906bb7c7831 133 req_param_resp.ints_length = 0;
garyservin 0:a906bb7c7831 134 req_param_resp.ints = NULL;
garyservin 0:a906bb7c7831 135 req_param_resp.floats_length = 0;
garyservin 0:a906bb7c7831 136 req_param_resp.floats = NULL;
garyservin 0:a906bb7c7831 137 req_param_resp.ints_length = 0;
garyservin 0:a906bb7c7831 138 req_param_resp.ints = NULL;
garyservin 0:a906bb7c7831 139 }
garyservin 0:a906bb7c7831 140
garyservin 0:a906bb7c7831 141 Hardware* getHardware(){
garyservin 0:a906bb7c7831 142 return &hardware_;
garyservin 0:a906bb7c7831 143 }
garyservin 0:a906bb7c7831 144
garyservin 0:a906bb7c7831 145 /* Start serial, initialize buffers */
garyservin 0:a906bb7c7831 146 void initNode(){
garyservin 0:a906bb7c7831 147 hardware_.init();
garyservin 0:a906bb7c7831 148 mode_ = 0;
garyservin 0:a906bb7c7831 149 bytes_ = 0;
garyservin 0:a906bb7c7831 150 index_ = 0;
garyservin 0:a906bb7c7831 151 topic_ = 0;
garyservin 0:a906bb7c7831 152 };
garyservin 0:a906bb7c7831 153
garyservin 0:a906bb7c7831 154 /* Start a named port, which may be network server IP, initialize buffers */
garyservin 0:a906bb7c7831 155 void initNode(char *portName){
garyservin 0:a906bb7c7831 156 hardware_.init(portName);
garyservin 0:a906bb7c7831 157 mode_ = 0;
garyservin 0:a906bb7c7831 158 bytes_ = 0;
garyservin 0:a906bb7c7831 159 index_ = 0;
garyservin 0:a906bb7c7831 160 topic_ = 0;
garyservin 0:a906bb7c7831 161 };
garyservin 0:a906bb7c7831 162
garyservin 0:a906bb7c7831 163 protected:
garyservin 0:a906bb7c7831 164 //State machine variables for spinOnce
garyservin 0:a906bb7c7831 165 int mode_;
garyservin 0:a906bb7c7831 166 int bytes_;
garyservin 0:a906bb7c7831 167 int topic_;
garyservin 0:a906bb7c7831 168 int index_;
garyservin 0:a906bb7c7831 169 int checksum_;
garyservin 0:a906bb7c7831 170
garyservin 0:a906bb7c7831 171 bool configured_;
garyservin 0:a906bb7c7831 172
garyservin 0:a906bb7c7831 173 /* used for syncing the time */
garyservin 0:a906bb7c7831 174 uint32_t last_sync_time;
garyservin 0:a906bb7c7831 175 uint32_t last_sync_receive_time;
garyservin 0:a906bb7c7831 176 uint32_t last_msg_timeout_time;
garyservin 0:a906bb7c7831 177
garyservin 0:a906bb7c7831 178 public:
garyservin 0:a906bb7c7831 179 /* This function goes in your loop() function, it handles
garyservin 0:a906bb7c7831 180 * serial input and callbacks for subscribers.
garyservin 0:a906bb7c7831 181 */
garyservin 0:a906bb7c7831 182
garyservin 0:a906bb7c7831 183
garyservin 0:a906bb7c7831 184 virtual int spinOnce(){
garyservin 0:a906bb7c7831 185
garyservin 0:a906bb7c7831 186 /* restart if timed out */
garyservin 0:a906bb7c7831 187 uint32_t c_time = hardware_.time();
garyservin 0:a906bb7c7831 188 if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){
garyservin 0:a906bb7c7831 189 configured_ = false;
garyservin 0:a906bb7c7831 190 }
garyservin 0:a906bb7c7831 191
garyservin 0:a906bb7c7831 192 /* reset if message has timed out */
garyservin 0:a906bb7c7831 193 if ( mode_ != MODE_FIRST_FF){
garyservin 0:a906bb7c7831 194 if (c_time > last_msg_timeout_time){
garyservin 0:a906bb7c7831 195 mode_ = MODE_FIRST_FF;
garyservin 0:a906bb7c7831 196 }
garyservin 0:a906bb7c7831 197 }
garyservin 0:a906bb7c7831 198
garyservin 0:a906bb7c7831 199 /* while available buffer, read data */
garyservin 0:a906bb7c7831 200 while( true )
garyservin 0:a906bb7c7831 201 {
garyservin 0:a906bb7c7831 202 int data = hardware_.read();
garyservin 0:a906bb7c7831 203 if( data < 0 )
garyservin 0:a906bb7c7831 204 break;
garyservin 0:a906bb7c7831 205 checksum_ += data;
garyservin 0:a906bb7c7831 206 if( mode_ == MODE_MESSAGE ){ /* message data being recieved */
garyservin 0:a906bb7c7831 207 message_in[index_++] = data;
garyservin 0:a906bb7c7831 208 bytes_--;
garyservin 0:a906bb7c7831 209 if(bytes_ == 0) /* is message complete? if so, checksum */
garyservin 0:a906bb7c7831 210 mode_ = MODE_MSG_CHECKSUM;
garyservin 0:a906bb7c7831 211 }else if( mode_ == MODE_FIRST_FF ){
garyservin 0:a906bb7c7831 212 if(data == 0xff){
garyservin 0:a906bb7c7831 213 mode_++;
garyservin 0:a906bb7c7831 214 last_msg_timeout_time = c_time + MSG_TIMEOUT;
garyservin 0:a906bb7c7831 215 }
garyservin 0:a906bb7c7831 216 else if( hardware_.time() - c_time > (SYNC_SECONDS)){
garyservin 0:a906bb7c7831 217 /* We have been stuck in spinOnce too long, return error */
garyservin 0:a906bb7c7831 218 configured_=false;
garyservin 0:a906bb7c7831 219 return -2;
garyservin 0:a906bb7c7831 220 }
garyservin 0:a906bb7c7831 221 }else if( mode_ == MODE_PROTOCOL_VER ){
garyservin 0:a906bb7c7831 222 if(data == PROTOCOL_VER){
garyservin 0:a906bb7c7831 223 mode_++;
garyservin 0:a906bb7c7831 224 }else{
garyservin 0:a906bb7c7831 225 mode_ = MODE_FIRST_FF;
garyservin 0:a906bb7c7831 226 if (configured_ == false)
garyservin 0:a906bb7c7831 227 requestSyncTime(); /* send a msg back showing our protocol version */
garyservin 0:a906bb7c7831 228 }
garyservin 0:a906bb7c7831 229 }else if( mode_ == MODE_SIZE_L ){ /* bottom half of message size */
garyservin 0:a906bb7c7831 230 bytes_ = data;
garyservin 0:a906bb7c7831 231 index_ = 0;
garyservin 0:a906bb7c7831 232 mode_++;
garyservin 0:a906bb7c7831 233 checksum_ = data; /* first byte for calculating size checksum */
garyservin 0:a906bb7c7831 234 }else if( mode_ == MODE_SIZE_H ){ /* top half of message size */
garyservin 0:a906bb7c7831 235 bytes_ += data<<8;
garyservin 0:a906bb7c7831 236 mode_++;
garyservin 0:a906bb7c7831 237 }else if( mode_ == MODE_SIZE_CHECKSUM ){
garyservin 0:a906bb7c7831 238 if( (checksum_%256) == 255)
garyservin 0:a906bb7c7831 239 mode_++;
garyservin 0:a906bb7c7831 240 else
garyservin 0:a906bb7c7831 241 mode_ = MODE_FIRST_FF; /* Abandon the frame if the msg len is wrong */
garyservin 0:a906bb7c7831 242 }else if( mode_ == MODE_TOPIC_L ){ /* bottom half of topic id */
garyservin 0:a906bb7c7831 243 topic_ = data;
garyservin 0:a906bb7c7831 244 mode_++;
garyservin 0:a906bb7c7831 245 checksum_ = data; /* first byte included in checksum */
garyservin 0:a906bb7c7831 246 }else if( mode_ == MODE_TOPIC_H ){ /* top half of topic id */
garyservin 0:a906bb7c7831 247 topic_ += data<<8;
garyservin 0:a906bb7c7831 248 mode_ = MODE_MESSAGE;
garyservin 0:a906bb7c7831 249 if(bytes_ == 0)
garyservin 0:a906bb7c7831 250 mode_ = MODE_MSG_CHECKSUM;
garyservin 0:a906bb7c7831 251 }else if( mode_ == MODE_MSG_CHECKSUM ){ /* do checksum */
garyservin 0:a906bb7c7831 252 mode_ = MODE_FIRST_FF;
garyservin 0:a906bb7c7831 253 if( (checksum_%256) == 255){
garyservin 0:a906bb7c7831 254 if(topic_ == TopicInfo::ID_PUBLISHER){
garyservin 0:a906bb7c7831 255 requestSyncTime();
garyservin 0:a906bb7c7831 256 negotiateTopics();
garyservin 0:a906bb7c7831 257 last_sync_time = c_time;
garyservin 0:a906bb7c7831 258 last_sync_receive_time = c_time;
garyservin 0:a906bb7c7831 259 return -1;
garyservin 0:a906bb7c7831 260 }else if(topic_ == TopicInfo::ID_TIME){
garyservin 0:a906bb7c7831 261 syncTime(message_in);
garyservin 0:a906bb7c7831 262 }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){
garyservin 0:a906bb7c7831 263 req_param_resp.deserialize(message_in);
garyservin 0:a906bb7c7831 264 param_recieved= true;
garyservin 0:a906bb7c7831 265 }else if(topic_ == TopicInfo::ID_TX_STOP){
garyservin 0:a906bb7c7831 266 configured_ = false;
garyservin 0:a906bb7c7831 267 }else{
garyservin 0:a906bb7c7831 268 if(subscribers[topic_-100])
garyservin 0:a906bb7c7831 269 subscribers[topic_-100]->callback( message_in );
garyservin 0:a906bb7c7831 270 }
garyservin 0:a906bb7c7831 271 }
garyservin 0:a906bb7c7831 272 }
garyservin 0:a906bb7c7831 273 }
garyservin 0:a906bb7c7831 274
garyservin 0:a906bb7c7831 275 /* occasionally sync time */
garyservin 0:a906bb7c7831 276 if( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){
garyservin 0:a906bb7c7831 277 requestSyncTime();
garyservin 0:a906bb7c7831 278 last_sync_time = c_time;
garyservin 0:a906bb7c7831 279 }
garyservin 0:a906bb7c7831 280
garyservin 0:a906bb7c7831 281 return 0;
garyservin 0:a906bb7c7831 282 }
garyservin 0:a906bb7c7831 283
garyservin 0:a906bb7c7831 284
garyservin 0:a906bb7c7831 285 /* Are we connected to the PC? */
garyservin 0:a906bb7c7831 286 virtual bool connected() {
garyservin 0:a906bb7c7831 287 return configured_;
garyservin 0:a906bb7c7831 288 };
garyservin 0:a906bb7c7831 289
garyservin 0:a906bb7c7831 290 /********************************************************************
garyservin 0:a906bb7c7831 291 * Time functions
garyservin 0:a906bb7c7831 292 */
garyservin 0:a906bb7c7831 293
garyservin 0:a906bb7c7831 294 void requestSyncTime()
garyservin 0:a906bb7c7831 295 {
garyservin 0:a906bb7c7831 296 std_msgs::Time t;
garyservin 0:a906bb7c7831 297 publish(TopicInfo::ID_TIME, &t);
garyservin 0:a906bb7c7831 298 rt_time = hardware_.time();
garyservin 0:a906bb7c7831 299 }
garyservin 0:a906bb7c7831 300
garyservin 0:a906bb7c7831 301 void syncTime(uint8_t * data)
garyservin 0:a906bb7c7831 302 {
garyservin 0:a906bb7c7831 303 std_msgs::Time t;
garyservin 0:a906bb7c7831 304 uint32_t offset = hardware_.time() - rt_time;
garyservin 0:a906bb7c7831 305
garyservin 0:a906bb7c7831 306 t.deserialize(data);
garyservin 0:a906bb7c7831 307 t.data.sec += offset/1000;
garyservin 0:a906bb7c7831 308 t.data.nsec += (offset%1000)*1000000UL;
garyservin 0:a906bb7c7831 309
garyservin 0:a906bb7c7831 310 this->setNow(t.data);
garyservin 0:a906bb7c7831 311 last_sync_receive_time = hardware_.time();
garyservin 0:a906bb7c7831 312 }
garyservin 0:a906bb7c7831 313
garyservin 0:a906bb7c7831 314 Time now()
garyservin 0:a906bb7c7831 315 {
garyservin 0:a906bb7c7831 316 uint32_t ms = hardware_.time();
garyservin 0:a906bb7c7831 317 Time current_time;
garyservin 0:a906bb7c7831 318 current_time.sec = ms/1000 + sec_offset;
garyservin 0:a906bb7c7831 319 current_time.nsec = (ms%1000)*1000000UL + nsec_offset;
garyservin 0:a906bb7c7831 320 normalizeSecNSec(current_time.sec, current_time.nsec);
garyservin 0:a906bb7c7831 321 return current_time;
garyservin 0:a906bb7c7831 322 }
garyservin 0:a906bb7c7831 323
garyservin 0:a906bb7c7831 324 void setNow( Time & new_now )
garyservin 0:a906bb7c7831 325 {
garyservin 0:a906bb7c7831 326 uint32_t ms = hardware_.time();
garyservin 0:a906bb7c7831 327 sec_offset = new_now.sec - ms/1000 - 1;
garyservin 0:a906bb7c7831 328 nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL;
garyservin 0:a906bb7c7831 329 normalizeSecNSec(sec_offset, nsec_offset);
garyservin 0:a906bb7c7831 330 }
garyservin 0:a906bb7c7831 331
garyservin 0:a906bb7c7831 332 /********************************************************************
garyservin 0:a906bb7c7831 333 * Topic Management
garyservin 0:a906bb7c7831 334 */
garyservin 0:a906bb7c7831 335
garyservin 0:a906bb7c7831 336 /* Register a new publisher */
garyservin 0:a906bb7c7831 337 bool advertise(Publisher & p)
garyservin 0:a906bb7c7831 338 {
garyservin 0:a906bb7c7831 339 for(int i = 0; i < MAX_PUBLISHERS; i++){
garyservin 0:a906bb7c7831 340 if(publishers[i] == 0){ // empty slot
garyservin 0:a906bb7c7831 341 publishers[i] = &p;
garyservin 0:a906bb7c7831 342 p.id_ = i+100+MAX_SUBSCRIBERS;
garyservin 0:a906bb7c7831 343 p.nh_ = this;
garyservin 0:a906bb7c7831 344 return true;
garyservin 0:a906bb7c7831 345 }
garyservin 0:a906bb7c7831 346 }
garyservin 0:a906bb7c7831 347 return false;
garyservin 0:a906bb7c7831 348 }
garyservin 0:a906bb7c7831 349
garyservin 0:a906bb7c7831 350 /* Register a new subscriber */
garyservin 0:a906bb7c7831 351 template<typename MsgT>
garyservin 0:a906bb7c7831 352 bool subscribe(Subscriber< MsgT> & s){
garyservin 0:a906bb7c7831 353 for(int i = 0; i < MAX_SUBSCRIBERS; i++){
garyservin 0:a906bb7c7831 354 if(subscribers[i] == 0){ // empty slot
garyservin 0:a906bb7c7831 355 subscribers[i] = (Subscriber_*) &s;
garyservin 0:a906bb7c7831 356 s.id_ = i+100;
garyservin 0:a906bb7c7831 357 return true;
garyservin 0:a906bb7c7831 358 }
garyservin 0:a906bb7c7831 359 }
garyservin 0:a906bb7c7831 360 return false;
garyservin 0:a906bb7c7831 361 }
garyservin 0:a906bb7c7831 362
garyservin 0:a906bb7c7831 363 /* Register a new Service Server */
garyservin 0:a906bb7c7831 364 template<typename MReq, typename MRes>
garyservin 0:a906bb7c7831 365 bool advertiseService(ServiceServer<MReq,MRes>& srv){
garyservin 0:a906bb7c7831 366 bool v = advertise(srv.pub);
garyservin 0:a906bb7c7831 367 for(int i = 0; i < MAX_SUBSCRIBERS; i++){
garyservin 0:a906bb7c7831 368 if(subscribers[i] == 0){ // empty slot
garyservin 0:a906bb7c7831 369 subscribers[i] = (Subscriber_*) &srv;
garyservin 0:a906bb7c7831 370 srv.id_ = i+100;
garyservin 0:a906bb7c7831 371 return v;
garyservin 0:a906bb7c7831 372 }
garyservin 0:a906bb7c7831 373 }
garyservin 0:a906bb7c7831 374 return false;
garyservin 0:a906bb7c7831 375 }
garyservin 0:a906bb7c7831 376
garyservin 0:a906bb7c7831 377 /* Register a new Service Client */
garyservin 0:a906bb7c7831 378 template<typename MReq, typename MRes>
garyservin 0:a906bb7c7831 379 bool serviceClient(ServiceClient<MReq, MRes>& srv){
garyservin 0:a906bb7c7831 380 bool v = advertise(srv.pub);
garyservin 0:a906bb7c7831 381 for(int i = 0; i < MAX_SUBSCRIBERS; i++){
garyservin 0:a906bb7c7831 382 if(subscribers[i] == 0){ // empty slot
garyservin 0:a906bb7c7831 383 subscribers[i] = (Subscriber_*) &srv;
garyservin 0:a906bb7c7831 384 srv.id_ = i+100;
garyservin 0:a906bb7c7831 385 return v;
garyservin 0:a906bb7c7831 386 }
garyservin 0:a906bb7c7831 387 }
garyservin 0:a906bb7c7831 388 return false;
garyservin 0:a906bb7c7831 389 }
garyservin 0:a906bb7c7831 390
garyservin 0:a906bb7c7831 391 void negotiateTopics()
garyservin 0:a906bb7c7831 392 {
garyservin 0:a906bb7c7831 393 rosserial_msgs::TopicInfo ti;
garyservin 0:a906bb7c7831 394 int i;
garyservin 0:a906bb7c7831 395 for(i = 0; i < MAX_PUBLISHERS; i++)
garyservin 0:a906bb7c7831 396 {
garyservin 0:a906bb7c7831 397 if(publishers[i] != 0) // non-empty slot
garyservin 0:a906bb7c7831 398 {
garyservin 0:a906bb7c7831 399 ti.topic_id = publishers[i]->id_;
garyservin 0:a906bb7c7831 400 ti.topic_name = (char *) publishers[i]->topic_;
garyservin 0:a906bb7c7831 401 ti.message_type = (char *) publishers[i]->msg_->getType();
garyservin 0:a906bb7c7831 402 ti.md5sum = (char *) publishers[i]->msg_->getMD5();
garyservin 0:a906bb7c7831 403 ti.buffer_size = OUTPUT_SIZE;
garyservin 0:a906bb7c7831 404 publish( publishers[i]->getEndpointType(), &ti );
garyservin 0:a906bb7c7831 405 }
garyservin 0:a906bb7c7831 406 }
garyservin 0:a906bb7c7831 407 for(i = 0; i < MAX_SUBSCRIBERS; i++)
garyservin 0:a906bb7c7831 408 {
garyservin 0:a906bb7c7831 409 if(subscribers[i] != 0) // non-empty slot
garyservin 0:a906bb7c7831 410 {
garyservin 0:a906bb7c7831 411 ti.topic_id = subscribers[i]->id_;
garyservin 0:a906bb7c7831 412 ti.topic_name = (char *) subscribers[i]->topic_;
garyservin 0:a906bb7c7831 413 ti.message_type = (char *) subscribers[i]->getMsgType();
garyservin 0:a906bb7c7831 414 ti.md5sum = (char *) subscribers[i]->getMsgMD5();
garyservin 0:a906bb7c7831 415 ti.buffer_size = INPUT_SIZE;
garyservin 0:a906bb7c7831 416 publish( subscribers[i]->getEndpointType(), &ti );
garyservin 0:a906bb7c7831 417 }
garyservin 0:a906bb7c7831 418 }
garyservin 0:a906bb7c7831 419 configured_ = true;
garyservin 0:a906bb7c7831 420 }
garyservin 0:a906bb7c7831 421
garyservin 0:a906bb7c7831 422 virtual int publish(int id, const Msg * msg)
garyservin 0:a906bb7c7831 423 {
garyservin 0:a906bb7c7831 424 if(id >= 100 && !configured_)
garyservin 0:a906bb7c7831 425 return 0;
garyservin 0:a906bb7c7831 426
garyservin 0:a906bb7c7831 427 /* serialize message */
garyservin 0:a906bb7c7831 428 uint16_t l = msg->serialize(message_out+7);
garyservin 0:a906bb7c7831 429
garyservin 0:a906bb7c7831 430 /* setup the header */
garyservin 0:a906bb7c7831 431 message_out[0] = 0xff;
garyservin 0:a906bb7c7831 432 message_out[1] = PROTOCOL_VER;
garyservin 0:a906bb7c7831 433 message_out[2] = (uint8_t) ((uint16_t)l&255);
garyservin 0:a906bb7c7831 434 message_out[3] = (uint8_t) ((uint16_t)l>>8);
garyservin 0:a906bb7c7831 435 message_out[4] = 255 - ((message_out[2] + message_out[3])%256);
garyservin 0:a906bb7c7831 436 message_out[5] = (uint8_t) ((int16_t)id&255);
garyservin 0:a906bb7c7831 437 message_out[6] = (uint8_t) ((int16_t)id>>8);
garyservin 0:a906bb7c7831 438
garyservin 0:a906bb7c7831 439 /* calculate checksum */
garyservin 0:a906bb7c7831 440 int chk = 0;
garyservin 0:a906bb7c7831 441 for(int i =5; i<l+7; i++)
garyservin 0:a906bb7c7831 442 chk += message_out[i];
garyservin 0:a906bb7c7831 443 l += 7;
garyservin 0:a906bb7c7831 444 message_out[l++] = 255 - (chk%256);
garyservin 0:a906bb7c7831 445
garyservin 0:a906bb7c7831 446 if( l <= OUTPUT_SIZE ){
garyservin 0:a906bb7c7831 447 hardware_.write(message_out, l);
garyservin 0:a906bb7c7831 448 return l;
garyservin 0:a906bb7c7831 449 }else{
garyservin 0:a906bb7c7831 450 logerror("Message from device dropped: message larger than buffer.");
garyservin 0:a906bb7c7831 451 return -1;
garyservin 0:a906bb7c7831 452 }
garyservin 0:a906bb7c7831 453 }
garyservin 0:a906bb7c7831 454
garyservin 0:a906bb7c7831 455 /********************************************************************
garyservin 0:a906bb7c7831 456 * Logging
garyservin 0:a906bb7c7831 457 */
garyservin 0:a906bb7c7831 458
garyservin 0:a906bb7c7831 459 private:
garyservin 0:a906bb7c7831 460 void log(char byte, const char * msg){
garyservin 0:a906bb7c7831 461 rosserial_msgs::Log l;
garyservin 0:a906bb7c7831 462 l.level= byte;
garyservin 0:a906bb7c7831 463 l.msg = (char*)msg;
garyservin 0:a906bb7c7831 464 publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
garyservin 0:a906bb7c7831 465 }
garyservin 0:a906bb7c7831 466
garyservin 0:a906bb7c7831 467 public:
garyservin 0:a906bb7c7831 468 void logdebug(const char* msg){
garyservin 0:a906bb7c7831 469 log(rosserial_msgs::Log::ROSDEBUG, msg);
garyservin 0:a906bb7c7831 470 }
garyservin 0:a906bb7c7831 471 void loginfo(const char * msg){
garyservin 0:a906bb7c7831 472 log(rosserial_msgs::Log::INFO, msg);
garyservin 0:a906bb7c7831 473 }
garyservin 0:a906bb7c7831 474 void logwarn(const char *msg){
garyservin 0:a906bb7c7831 475 log(rosserial_msgs::Log::WARN, msg);
garyservin 0:a906bb7c7831 476 }
garyservin 0:a906bb7c7831 477 void logerror(const char*msg){
garyservin 0:a906bb7c7831 478 log(rosserial_msgs::Log::ERROR, msg);
garyservin 0:a906bb7c7831 479 }
garyservin 0:a906bb7c7831 480 void logfatal(const char*msg){
garyservin 0:a906bb7c7831 481 log(rosserial_msgs::Log::FATAL, msg);
garyservin 0:a906bb7c7831 482 }
garyservin 0:a906bb7c7831 483
garyservin 0:a906bb7c7831 484 /********************************************************************
garyservin 0:a906bb7c7831 485 * Parameters
garyservin 0:a906bb7c7831 486 */
garyservin 0:a906bb7c7831 487
garyservin 0:a906bb7c7831 488 private:
garyservin 0:a906bb7c7831 489 bool param_recieved;
garyservin 0:a906bb7c7831 490 rosserial_msgs::RequestParamResponse req_param_resp;
garyservin 0:a906bb7c7831 491
garyservin 0:a906bb7c7831 492 bool requestParam(const char * name, int time_out = 1000){
garyservin 0:a906bb7c7831 493 param_recieved = false;
garyservin 0:a906bb7c7831 494 rosserial_msgs::RequestParamRequest req;
garyservin 0:a906bb7c7831 495 req.name = (char*)name;
garyservin 0:a906bb7c7831 496 publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
garyservin 0:a906bb7c7831 497 uint16_t end_time = hardware_.time() + time_out;
garyservin 0:a906bb7c7831 498 while(!param_recieved ){
garyservin 0:a906bb7c7831 499 spinOnce();
garyservin 0:a906bb7c7831 500 if (hardware_.time() > end_time) return false;
garyservin 0:a906bb7c7831 501 }
garyservin 0:a906bb7c7831 502 return true;
garyservin 0:a906bb7c7831 503 }
garyservin 0:a906bb7c7831 504
garyservin 0:a906bb7c7831 505 public:
garyservin 0:a906bb7c7831 506 bool getParam(const char* name, int* param, int length =1){
garyservin 0:a906bb7c7831 507 if (requestParam(name) ){
garyservin 0:a906bb7c7831 508 if (length == req_param_resp.ints_length){
garyservin 0:a906bb7c7831 509 //copy it over
garyservin 0:a906bb7c7831 510 for(int i=0; i<length; i++)
garyservin 0:a906bb7c7831 511 param[i] = req_param_resp.ints[i];
garyservin 0:a906bb7c7831 512 return true;
garyservin 0:a906bb7c7831 513 }
garyservin 0:a906bb7c7831 514 }
garyservin 0:a906bb7c7831 515 return false;
garyservin 0:a906bb7c7831 516 }
garyservin 0:a906bb7c7831 517 bool getParam(const char* name, float* param, int length=1){
garyservin 0:a906bb7c7831 518 if (requestParam(name) ){
garyservin 0:a906bb7c7831 519 if (length == req_param_resp.floats_length){
garyservin 0:a906bb7c7831 520 //copy it over
garyservin 0:a906bb7c7831 521 for(int i=0; i<length; i++)
garyservin 0:a906bb7c7831 522 param[i] = req_param_resp.floats[i];
garyservin 0:a906bb7c7831 523 return true;
garyservin 0:a906bb7c7831 524 }
garyservin 0:a906bb7c7831 525 }
garyservin 0:a906bb7c7831 526 return false;
garyservin 0:a906bb7c7831 527 }
garyservin 0:a906bb7c7831 528 bool getParam(const char* name, char** param, int length=1){
garyservin 0:a906bb7c7831 529 if (requestParam(name) ){
garyservin 0:a906bb7c7831 530 if (length == req_param_resp.strings_length){
garyservin 0:a906bb7c7831 531 //copy it over
garyservin 0:a906bb7c7831 532 for(int i=0; i<length; i++)
garyservin 0:a906bb7c7831 533 strcpy(param[i],req_param_resp.strings[i]);
garyservin 0:a906bb7c7831 534 return true;
garyservin 0:a906bb7c7831 535 }
garyservin 0:a906bb7c7831 536 }
garyservin 0:a906bb7c7831 537 return false;
garyservin 0:a906bb7c7831 538 }
garyservin 0:a906bb7c7831 539 };
garyservin 0:a906bb7c7831 540
garyservin 0:a906bb7c7831 541 }
garyservin 0:a906bb7c7831 542
garyservin 0:a906bb7c7831 543 #endif