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_PUBLISHER_H_
garyservin 0:9e9b7db60fd5 36 #define _ROS_PUBLISHER_H_
garyservin 0:9e9b7db60fd5 37
garyservin 0:9e9b7db60fd5 38 #include "rosserial_msgs/TopicInfo.h"
garyservin 0:9e9b7db60fd5 39 #include "ros/node_handle.h"
garyservin 0:9e9b7db60fd5 40
garyservin 0:9e9b7db60fd5 41 namespace ros {
garyservin 0:9e9b7db60fd5 42
garyservin 0:9e9b7db60fd5 43 /* Generic Publisher */
garyservin 0:9e9b7db60fd5 44 class Publisher
garyservin 0:9e9b7db60fd5 45 {
garyservin 0:9e9b7db60fd5 46 public:
garyservin 0:9e9b7db60fd5 47 Publisher( const char * topic_name, Msg * msg, int endpoint=rosserial_msgs::TopicInfo::ID_PUBLISHER) :
garyservin 0:9e9b7db60fd5 48 topic_(topic_name),
garyservin 0:9e9b7db60fd5 49 msg_(msg),
garyservin 0:9e9b7db60fd5 50 endpoint_(endpoint) {};
garyservin 0:9e9b7db60fd5 51
garyservin 0:9e9b7db60fd5 52 int publish( const Msg * msg ) { return nh_->publish(id_, msg); };
garyservin 0:9e9b7db60fd5 53 int getEndpointType(){ return endpoint_; }
garyservin 0:9e9b7db60fd5 54
garyservin 0:9e9b7db60fd5 55 const char * topic_;
garyservin 0:9e9b7db60fd5 56 Msg *msg_;
garyservin 0:9e9b7db60fd5 57 // id_ and no_ are set by NodeHandle when we advertise
garyservin 0:9e9b7db60fd5 58 int id_;
garyservin 0:9e9b7db60fd5 59 NodeHandleBase_* nh_;
garyservin 0:9e9b7db60fd5 60
garyservin 0:9e9b7db60fd5 61 private:
garyservin 0:9e9b7db60fd5 62 int endpoint_;
garyservin 0:9e9b7db60fd5 63 };
garyservin 0:9e9b7db60fd5 64
garyservin 0:9e9b7db60fd5 65 }
garyservin 0:9e9b7db60fd5 66
garyservin 0:9e9b7db60fd5 67 #endif