This is a fork from the original, including a small change in the buffer size of the hardware interface (increased to 2048) and decreasing the number of publishers and subscribers to 5. Besides, the library about the message Adc.h was modified so as to increase the number of available Adc channels to be read ( from 6 to 7 ) For this modification, a change in checksum was required

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
jacobepfl1692
Date:
Tue Oct 17 18:49:03 2017 +0000
Revision:
2:9114cc24ddcf
Parent:
0:9e9b7db60fd5
I increased the channels of the ADC to 6 (hence change in checksum) because my application needed it (STM32f407V6)

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 /*
garyservin 0:9e9b7db60fd5 2 * Software License Agreement (BSD License)
garyservin 0:9e9b7db60fd5 3 *
garyservin 0:9e9b7db60fd5 4 * Copyright (c) 2011, Willow Garage, Inc.
garyservin 0:9e9b7db60fd5 5 * All rights reserved.
garyservin 0:9e9b7db60fd5 6 *
garyservin 0:9e9b7db60fd5 7 * Redistribution and use in source and binary forms, with or without
garyservin 0:9e9b7db60fd5 8 * modification, are permitted provided that the following conditions
garyservin 0:9e9b7db60fd5 9 * are met:
garyservin 0:9e9b7db60fd5 10 *
garyservin 0:9e9b7db60fd5 11 * * Redistributions of source code must retain the above copyright
garyservin 0:9e9b7db60fd5 12 * notice, this list of conditions and the following disclaimer.
garyservin 0:9e9b7db60fd5 13 * * Redistributions in binary form must reproduce the above
garyservin 0:9e9b7db60fd5 14 * copyright notice, this list of conditions and the following
garyservin 0:9e9b7db60fd5 15 * disclaimer in the documentation and/or other materials provided
garyservin 0:9e9b7db60fd5 16 * with the distribution.
garyservin 0:9e9b7db60fd5 17 * * Neither the name of Willow Garage, Inc. nor the names of its
garyservin 0:9e9b7db60fd5 18 * contributors may be used to endorse or promote prducts derived
garyservin 0:9e9b7db60fd5 19 * from this software without specific prior written permission.
garyservin 0:9e9b7db60fd5 20 *
garyservin 0:9e9b7db60fd5 21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
garyservin 0:9e9b7db60fd5 22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
garyservin 0:9e9b7db60fd5 23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
garyservin 0:9e9b7db60fd5 24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
garyservin 0:9e9b7db60fd5 25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
garyservin 0:9e9b7db60fd5 26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
garyservin 0:9e9b7db60fd5 27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
garyservin 0:9e9b7db60fd5 28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
garyservin 0:9e9b7db60fd5 29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
garyservin 0:9e9b7db60fd5 30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
garyservin 0:9e9b7db60fd5 31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
garyservin 0:9e9b7db60fd5 32 * POSSIBILITY OF SUCH DAMAGE.
garyservin 0:9e9b7db60fd5 33 */
garyservin 0:9e9b7db60fd5 34
garyservin 0:9e9b7db60fd5 35 #ifndef ROS_SUBSCRIBER_H_
garyservin 0:9e9b7db60fd5 36 #define ROS_SUBSCRIBER_H_
garyservin 0:9e9b7db60fd5 37
garyservin 0:9e9b7db60fd5 38 #include "rosserial_msgs/TopicInfo.h"
garyservin 0:9e9b7db60fd5 39
garyservin 0:9e9b7db60fd5 40 namespace ros {
garyservin 0:9e9b7db60fd5 41
garyservin 0:9e9b7db60fd5 42 /* Base class for objects subscribers. */
garyservin 0:9e9b7db60fd5 43 class Subscriber_
garyservin 0:9e9b7db60fd5 44 {
garyservin 0:9e9b7db60fd5 45 public:
garyservin 0:9e9b7db60fd5 46 virtual void callback(unsigned char *data)=0;
garyservin 0:9e9b7db60fd5 47 virtual int getEndpointType()=0;
garyservin 0:9e9b7db60fd5 48
garyservin 0:9e9b7db60fd5 49 // id_ is set by NodeHandle when we advertise
garyservin 0:9e9b7db60fd5 50 int id_;
garyservin 0:9e9b7db60fd5 51
garyservin 0:9e9b7db60fd5 52 virtual const char * getMsgType()=0;
garyservin 0:9e9b7db60fd5 53 virtual const char * getMsgMD5()=0;
garyservin 0:9e9b7db60fd5 54 const char * topic_;
garyservin 0:9e9b7db60fd5 55 };
garyservin 0:9e9b7db60fd5 56
garyservin 0:9e9b7db60fd5 57 /* Bound function subscriber. */
garyservin 0:9e9b7db60fd5 58 template<typename MsgT, typename ObjT=void>
garyservin 0:9e9b7db60fd5 59 class Subscriber: public Subscriber_
garyservin 0:9e9b7db60fd5 60 {
garyservin 0:9e9b7db60fd5 61 public:
garyservin 0:9e9b7db60fd5 62 typedef void(ObjT::*CallbackT)(const MsgT&);
garyservin 0:9e9b7db60fd5 63 MsgT msg;
garyservin 0:9e9b7db60fd5 64
garyservin 0:9e9b7db60fd5 65 Subscriber(const char * topic_name, CallbackT cb, ObjT* obj, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) :
garyservin 0:9e9b7db60fd5 66 cb_(cb),
garyservin 0:9e9b7db60fd5 67 obj_(obj),
garyservin 0:9e9b7db60fd5 68 endpoint_(endpoint)
garyservin 0:9e9b7db60fd5 69 {
garyservin 0:9e9b7db60fd5 70 topic_ = topic_name;
garyservin 0:9e9b7db60fd5 71 };
garyservin 0:9e9b7db60fd5 72
garyservin 0:9e9b7db60fd5 73 virtual void callback(unsigned char* data)
garyservin 0:9e9b7db60fd5 74 {
garyservin 0:9e9b7db60fd5 75 msg.deserialize(data);
garyservin 0:9e9b7db60fd5 76 (obj_->*cb_)(msg);
garyservin 0:9e9b7db60fd5 77 }
garyservin 0:9e9b7db60fd5 78
garyservin 0:9e9b7db60fd5 79 virtual const char * getMsgType() { return this->msg.getType(); }
garyservin 0:9e9b7db60fd5 80 virtual const char * getMsgMD5() { return this->msg.getMD5(); }
garyservin 0:9e9b7db60fd5 81 virtual int getEndpointType() { return endpoint_; }
garyservin 0:9e9b7db60fd5 82
garyservin 0:9e9b7db60fd5 83 private:
garyservin 0:9e9b7db60fd5 84 CallbackT cb_;
garyservin 0:9e9b7db60fd5 85 ObjT* obj_;
garyservin 0:9e9b7db60fd5 86 int endpoint_;
garyservin 0:9e9b7db60fd5 87 };
garyservin 0:9e9b7db60fd5 88
garyservin 0:9e9b7db60fd5 89 /* Standalone function subscriber. */
garyservin 0:9e9b7db60fd5 90 template<typename MsgT>
garyservin 0:9e9b7db60fd5 91 class Subscriber<MsgT, void>: public Subscriber_
garyservin 0:9e9b7db60fd5 92 {
garyservin 0:9e9b7db60fd5 93 public:
garyservin 0:9e9b7db60fd5 94 typedef void(*CallbackT)(const MsgT&);
garyservin 0:9e9b7db60fd5 95 MsgT msg;
garyservin 0:9e9b7db60fd5 96
garyservin 0:9e9b7db60fd5 97 Subscriber(const char * topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) :
garyservin 0:9e9b7db60fd5 98 cb_(cb),
garyservin 0:9e9b7db60fd5 99 endpoint_(endpoint)
garyservin 0:9e9b7db60fd5 100 {
garyservin 0:9e9b7db60fd5 101 topic_ = topic_name;
garyservin 0:9e9b7db60fd5 102 };
garyservin 0:9e9b7db60fd5 103
garyservin 0:9e9b7db60fd5 104 virtual void callback(unsigned char* data)
garyservin 0:9e9b7db60fd5 105 {
garyservin 0:9e9b7db60fd5 106 msg.deserialize(data);
garyservin 0:9e9b7db60fd5 107 this->cb_(msg);
garyservin 0:9e9b7db60fd5 108 }
garyservin 0:9e9b7db60fd5 109
garyservin 0:9e9b7db60fd5 110 virtual const char * getMsgType() { return this->msg.getType(); }
garyservin 0:9e9b7db60fd5 111 virtual const char * getMsgMD5() { return this->msg.getMD5(); }
garyservin 0:9e9b7db60fd5 112 virtual int getEndpointType() { return endpoint_; }
garyservin 0:9e9b7db60fd5 113
garyservin 0:9e9b7db60fd5 114 private:
garyservin 0:9e9b7db60fd5 115 CallbackT cb_;
garyservin 0:9e9b7db60fd5 116 int endpoint_;
garyservin 0:9e9b7db60fd5 117 };
garyservin 0:9e9b7db60fd5 118
garyservin 0:9e9b7db60fd5 119 }
garyservin 0:9e9b7db60fd5 120
garyservin 0:9e9b7db60fd5 121 #endif