Skip to content

Commit

Permalink
Merge pull request ros-drivers#2 in PHEN/rosserial from update_upstre…
Browse files Browse the repository at this point in the history
…am to jade-devel

* commit 'a707373c7e9f9ad40ad9440550840e29960c9290':
  Changed hardcoded pin 13 to LED_BUILTIN (ros-drivers#328)
  Re-attempting rosserial for VEX Cortex (ros-drivers#380)
  Added service to force an Arduino hard reset in serial_node.py (ros-drivers#349)
  Fix compiling on boost > 1.66 (ros-drivers#362)
  Use the ! prefix introduced in gcc4mbed for mbed examples (ros-drivers#304)
  Add support for boolean parameters (ros-drivers#355)
  Change Travis to use clang-5.0.0 (ros-drivers#363)
  [python] fix an unboundlocalerror (ros-drivers#346)
  Added ESP32 support (ros-drivers#345)
  Retry opening the serial port every 3 seconds (ros-drivers#342)
  In rosserial_arduino, changed embedded type size for ROS uint64 to 8 bytes from 4. (ros-drivers#312)
  0.7.7
  Changes
  Copy src/examples to install dir so make_libraries.py doesn't fail (ros-drivers#336)
  Add overall spin timeout to rosserial read. (ros-drivers#334)
  Fixing formatting on files. (ros-drivers#333)
  Fix catkin lint errors (ros-drivers#296)
  • Loading branch information
1r0b1n0 committed Sep 12, 2018
2 parents d924864 + a707373 commit f3572cc
Show file tree
Hide file tree
Showing 111 changed files with 2,412 additions and 998 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,6 @@
*.swp
rosserial_server/doc/
*.user*
*.out
*.geany

2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ language: generic

env:
- CI_ROS_DISTRO=indigo CC=gcc CXX=g++ PATH=/usr/sbin:/usr/bin:/sbin:/bin
- CI_ROS_DISTRO=indigo CC=clang CXX=clang++ PATH=/usr/local/clang-3.9.0/bin:/usr/sbin:/usr/bin:/sbin:/bin
- CI_ROS_DISTRO=indigo CC=clang CXX=clang++ PATH=/usr/local/clang-5.0.0/bin:/usr/sbin:/usr/bin:/sbin:/bin

before_install:
- sudo sh -c 'echo "deb http://packages.ros.org/ros-shadow-fixed/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list'
Expand Down
3 changes: 3 additions & 0 deletions rosserial/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package rosserial
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.7.7 (2017-11-29)
------------------

0.7.6 (2017-03-01)
------------------

Expand Down
2 changes: 1 addition & 1 deletion rosserial/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>rosserial</name>
<version>0.7.6</version>
<version>0.7.7</version>
<description>
Metapackage for core of rosserial.
</description>
Expand Down
12 changes: 12 additions & 0 deletions rosserial_arduino/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,18 @@
Changelog for package rosserial_arduino
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.7.7 (2017-11-29)
------------------
* Fix catkin lint errors (`#296 <https://github.com/ros-drivers/rosserial/issues/296>`_)
* Add ArduinoTcpHardware to use Arduino Ethernet shield. (`#324 <https://github.com/ros-drivers/rosserial/issues/324>`_)
* Add an example to use Subscriber and ServiceServer as class members. (`#321 <https://github.com/ros-drivers/rosserial/issues/321>`_)
* Added support for the Particle Photon (`#292 <https://github.com/ros-drivers/rosserial/issues/292>`_)
* Fix POLICY CMP0054 unknown (`#291 <https://github.com/ros-drivers/rosserial/issues/291>`_)
* Use ESP8266 header only if defined. (`#288 <https://github.com/ros-drivers/rosserial/issues/288>`_)
* Add Esp8266 support and an example (`#279 <https://github.com/ros-drivers/rosserial/issues/279>`_)
* Add support for STM32F1 with stm32duino. (`#281 <https://github.com/ros-drivers/rosserial/issues/281>`_)
* Contributors: Bei Chen Liu, David Portugal, Dmitry Kargin, Mike Purvis, Romain Reignier, Valentin VERGEZ, khancyr

0.7.6 (2017-03-01)
------------------
* Fixed issue with CMake CMP0054 (`#273 <https://github.com/ros-drivers/rosserial/issues/273>`_)
Expand Down
28 changes: 16 additions & 12 deletions rosserial_arduino/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,34 +1,38 @@
cmake_minimum_required(VERSION 2.8.3)
project(rosserial_arduino)

find_package(catkin REQUIRED COMPONENTS message_generation)
find_package(catkin REQUIRED COMPONENTS
message_generation
)

add_message_files(FILES
Adc.msg
)
Adc.msg
)

add_service_files(FILES
Test.srv
)
Test.srv
)

catkin_python_setup()

generate_messages()

catkin_package(
CATKIN_DEPENDS message_runtime
CFG_EXTRAS rosserial_arduino-extras.cmake
CFG_EXTRAS ${PROJECT_NAME}-extras.cmake
)

install(DIRECTORY src/ros_lib
install(
DIRECTORY src/ros_lib
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/src
)

install(DIRECTORY arduino-cmake
install(
DIRECTORY arduino-cmake
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

install(PROGRAMS src/rosserial_arduino/make_libraries.py
catkin_install_python(
PROGRAMS src/${PROJECT_NAME}/make_libraries.py nodes/serial_node.py
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)



76 changes: 76 additions & 0 deletions rosserial_arduino/nodes/serial_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
#!/usr/bin/env python

#####################################################################
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import rospy
from rosserial_arduino import SerialClient
from serial import SerialException
from time import sleep

import sys

if __name__=="__main__":

rospy.init_node("serial_node")
rospy.loginfo("ROS Serial Python Node")

port_name = rospy.get_param('~port','/dev/ttyUSB0')
baud = int(rospy.get_param('~baud','57600'))

# Number of seconds of sync failure after which Arduino is auto-reset.
# 0 = no timeout, auto-reset disabled
auto_reset_timeout = int(rospy.get_param('~auto_reset_timeout','0'))

# for systems where pyserial yields errors in the fcntl.ioctl(self.fd, TIOCMBIS, \
# TIOCM_DTR_str) line, which causes an IOError, when using simulated port
fix_pyserial_for_test = rospy.get_param('~fix_pyserial_for_test', False)

# TODO: do we really want command line params in addition to parameter server params?
sys.argv = rospy.myargv(argv=sys.argv)
if len(sys.argv) >= 2 :
port_name = sys.argv[1]

while not rospy.is_shutdown():
rospy.loginfo("Connecting to %s at %d baud" % (port_name, baud))
try:
client = SerialClient(port_name, baud, fix_pyserial_for_test=fix_pyserial_for_test, auto_reset_timeout=auto_reset_timeout)
client.run()
except KeyboardInterrupt:
break
except SerialException:
sleep(1.0)
continue
except OSError:
sleep(1.0)
continue
7 changes: 3 additions & 4 deletions rosserial_arduino/package.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<package>
<name>rosserial_arduino</name>
<version>0.7.6</version>
<version>0.7.7</version>
<description>
Libraries and examples for ROSserial usage on Arduino/AVR Platforms.
rosserial for Arduino/AVR platforms.
</description>
<author>Michael Ferguson</author>
<author>Adam Stambler</author>
Expand All @@ -20,6 +20,5 @@
<run_depend>rosserial_msgs</run_depend>
<run_depend>rosserial_client</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>rosserial_python</run_depend>
</package>


11 changes: 11 additions & 0 deletions rosserial_arduino/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
#!/usr/bin/env python

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup(
packages=['rosserial_arduino'],
package_dir={'': 'src'},
)

setup(**d)
6 changes: 4 additions & 2 deletions rosserial_arduino/src/ros_lib/ArduinoTcpHardware.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <Arduino.h>
#if defined(ESP8266)
#include <ESP8266WiFi.h>
#elif defined(ESP32)
#include <WiFi.h> // Using Espressif's WiFi.h
#else
#include <SPI.h>
#include <Ethernet.h>
Expand All @@ -57,7 +59,7 @@ class ArduinoHardware {

IPAddress getLocalIP()
{
#if defined(ESP8266)
#if defined(ESP8266) or defined(ESP32)
return tcp_.localIP();
#else
return Ethernet.localIP();
Expand Down Expand Up @@ -92,7 +94,7 @@ class ArduinoHardware {
}

protected:
#if defined(ESP8266)
#if defined(ESP8266) or defined(ESP32)
WiFiClient tcp_;
#else
EthernetClient tcp_;
Expand Down
4 changes: 2 additions & 2 deletions rosserial_arduino/src/ros_lib/examples/Blink/Blink.pde
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,14 @@
ros::NodeHandle nh;

void messageCb( const std_msgs::Empty& toggle_msg){
digitalWrite(13, HIGH-digitalRead(13)); // blink the led
digitalWrite(LED_BUILTIN, HIGH-digitalRead(LED_BUILTIN)); // blink the led
}

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

void setup()
{
pinMode(13, OUTPUT);
pinMode(LED_BUILTIN, OUTPUT);
nh.initNode();
nh.subscribe(sub);
}
Expand Down
Empty file modified rosserial_arduino/src/ros_lib/examples/ServiceClient/client.py
100755 → 100644
Empty file.
6 changes: 3 additions & 3 deletions rosserial_arduino/src/ros_lib/ros.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
Expand Down Expand Up @@ -37,7 +37,7 @@

#include "ros/node_handle.h"

#if defined(ESP8266) or defined(ROSSERIAL_ARDUINO_TCP)
#if defined(ESP8266) or defined(ESP32) or defined(ROSSERIAL_ARDUINO_TCP)
#include "ArduinoTcpHardware.h"
#else
#include "ArduinoHardware.h"
Expand All @@ -61,7 +61,7 @@ namespace ros

typedef NodeHandle_<ArduinoHardware> NodeHandle; // default 25, 25, 512, 512

#endif
#endif
}

#endif
85 changes: 85 additions & 0 deletions rosserial_arduino/src/rosserial_arduino/SerialClient.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
#!/usr/bin/env python

#####################################################################
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import time

import rospy
from std_srvs.srv import Empty, EmptyResponse

from serial import Serial

from rosserial_python import SerialClient as _SerialClient

MINIMUM_RESET_TIME = 30

class SerialClient(_SerialClient):

def __init__(self, *args, **kwargs):
# The number of seconds to wait after a sync failure for a sync success before automatically performing a reset.
# If 0, no reset is performed.
self.auto_reset_timeout = kwargs.pop('auto_reset_timeout', 0)
self.lastsync_reset = rospy.Time.now()
rospy.Service('~reset_arduino', Empty, self.resetArduino)
super(SerialClient, self).__init__(*args, **kwargs)

def resetArduino(self, *args, **kwargs):
"""
Forces the Arduino to perform a reset, as though its reset button was pressed.
"""
with self.read_lock, self.write_lock:
rospy.loginfo('Beginning Arduino reset on port %s. Closing serial port...' % self.port.portstr)
self.port.close()
with Serial(self.port.portstr) as arduino:
arduino.setDTR(False)
time.sleep(3)
arduino.flushInput()
arduino.setDTR(True)
time.sleep(5)
rospy.loginfo('Reopening serial port...')
self.port.open()
rospy.loginfo('Arduino reset complete.')
self.lastsync_reset = rospy.Time.now()
self.requestTopics()
return EmptyResponse()

def sendDiagnostics(self, level, msg_text):
super(SerialClient, self).sendDiagnostics(level, msg_text)
# Reset when we haven't received any data from the Arduino in over N seconds.
if self.auto_reset_timeout and (rospy.Time.now() - self.last_read).secs >= self.auto_reset_timeout:
if (rospy.Time.now() - self.lastsync_reset).secs < MINIMUM_RESET_TIME:
rospy.loginfo('Sync has failed, but waiting for last reset to complete.')
else:
rospy.loginfo('Sync has failed for over %s seconds. Initiating automatic reset.' % self.auto_reset_timeout)
self.resetArduino()
1 change: 1 addition & 0 deletions rosserial_arduino/src/rosserial_arduino/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
from SerialClient import *
2 changes: 1 addition & 1 deletion rosserial_arduino/src/rosserial_arduino/make_libraries.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@
'int32' : ('int32_t', 4, PrimitiveDataType, []),
'uint32' : ('uint32_t', 4, PrimitiveDataType, []),
'int64' : ('int64_t', 8, PrimitiveDataType, []),
'uint64' : ('uint64_t', 4, PrimitiveDataType, []),
'uint64' : ('uint64_t', 8, PrimitiveDataType, []),
'float32' : ('float', 4, PrimitiveDataType, []),
'float64' : ('float', 4, AVR_Float64DataType, []),
'time' : ('ros::Time', 8, TimeDataType, ['ros/time']),
Expand Down
14 changes: 14 additions & 0 deletions rosserial_client/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,20 @@
Changelog for package rosserial_client
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.7.7 (2017-11-29)
------------------
* Add overall spin timeout to rosserial read. (`#334 <https://github.com/ros-drivers/rosserial/issues/334>`_)
* Fixing formatting on files. (`#333 <https://github.com/ros-drivers/rosserial/issues/333>`_)
* Fix catkin lint errors (`#296 <https://github.com/ros-drivers/rosserial/issues/296>`_)
* fix spinOnce timeout : 5ms -> 5s (`#326 <https://github.com/ros-drivers/rosserial/issues/326>`_)
* [Client] Fix a warning in comparison. (`#323 <https://github.com/ros-drivers/rosserial/issues/323>`_)
* Use const in ros namespace instead of #define for constants. Fix `#283 <https://github.com/ros-drivers/rosserial/issues/283>`_ (`#318 <https://github.com/ros-drivers/rosserial/issues/318>`_)
* Fix CMP0046 warnings in catkin-built firmwares (`#320 <https://github.com/ros-drivers/rosserial/issues/320>`_)
* Prevent time variable overflow leading to parameter timeout error (`#293 <https://github.com/ros-drivers/rosserial/issues/293>`_)
* Add class member method callback support for Service Server. (`#282 <https://github.com/ros-drivers/rosserial/issues/282>`_)
* Added capability to specify timeout in getParam methods (`#278 <https://github.com/ros-drivers/rosserial/issues/278>`_)
* Contributors: 1r0b1n0, Alessandro Francescon, Bei Chen Liu, David Portugal, Dmitry Kargin, Mike O'Driscoll, Mike Purvis, Romain Reignier

0.7.6 (2017-03-01)
------------------
* Fixing message has no attribute _md5sum (`#257 <https://github.com/ros-drivers/rosserial/issues/257>`_)
Expand Down
Loading

0 comments on commit f3572cc

Please sign in to comment.