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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

ROSSerial_mbed for Indigo 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

rosserial_mbed Hello World

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 14:22:59 2016 +0000
Revision:
0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full

Who changed what in which revision?

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