Coder Social home page Coder Social logo

phidgets_drivers's Introduction

Phidgets drivers for ROS

Overview

Drivers for various Phidgets devices. This Catkin metapackage includes:

Migrating from earlier versions

Prior to ROS Noetic, this library was based on the older libphidget21 library. While it is still supported by Phidgets, they no longer add new features to it and VINT hub style devices cannot be used with it. In ROS Noetic, this library was rewritten to use the libphidget22 library, which is the latest supported and contains all of the newest features. However, the new libphidget22 library is very different from the old libphidget21 library, and some of those differences leak through to the drivers themselves. The following is a list of things that may help in migrating to the new drivers.

General

  • All drivers now have nodelets.
  • No drivers have nodes anymore. While this makes debugging somewhat harder, nodelets are the only way to support devices on a VINT hub.
  • The "serial_number" parameter has been renamed to "serial".

Specific nodes

IMU

  • The "imu" node was renamed to the "spatial" node.
  • Diagnostics have been removed from the spatial driver. They will be reinstated later.
  • The "period" parameter has been renamed to "data_interval_ms".
  • The default "frame_id" has been changed from "imu" to "imu_link" to comply with REP-0145.

IK

  • The "ik" node is now just a launch file which composes an Analog Input, Digital Input, and Digital Output nodelet together.

Installing

From source

Make sure you have a working catkin workspace, as described at: http://www.ros.org/wiki/catkin/Tutorials/create_a_workspace

Also make sure you have git installed:

sudo apt-get install git-core

Change directory to the source folder of your catkin workspace. If, for instance, your workspace is ~/catkin_ws, make sure there is a src/ folder within it, then execute:

cd ~/catkin_ws/src

Download the metapackage from the github repository (<ros_distro> may be groovy, hydro, indigo...):

git clone -b <ros_distro> https://github.com/ros-drivers/phidgets_drivers.git

Install dependencies using rosdep:

rosdep install phidgets_drivers

Alternatively, if rosdep does not work, install the following packages:

sudo apt-get install libusb-1.0-0 libusb-1.0-0-dev

Compile your catkin workspace:

cd ~/catkin_ws
catkin_make

Udev rules setup

Note: The following steps are only required when installing the package from source. When installing a binary debian package of phidgets_api >= 0.7.8, the udev rules are set up automatically.

Make sure your catkin workspace has been successfully compiled. To set up the udev rules for the Phidgets USB devices, run the following commands:

roscd phidgets_api
sudo cp debian/udev /etc/udev/rules.d/99-phidgets.rules
sudo udevadm control --reload-rules

Afterwards, disconnect the USB cable and plug it in again (or run sudo udevadm trigger).

For documentation regarding nodes, topics, etc:

http://ros.org/wiki/phidgets_drivers

pre-commit Formatting Checks

This repo has a pre-commit check that runs in CI. You can use this locally and set it up to run automatically before you commit something. To install, use pip:

pip3 install --user pre-commit

To run over all the files in the repo manually:

pre-commit run -a

To run pre-commit automatically before committing in the local repo, install the git hooks:

pre-commit install

phidgets_drivers's People

Contributors

caplasberg avatar ccny-ros-pkg avatar clalancette avatar dogoepp avatar garyedwards avatar hikinggrass avatar idryanov avatar jlblancoc avatar jovobe avatar jspricke avatar keshaviyengar avatar lights0123 avatar mani-monaj avatar michaelgrupp avatar mikaelarguedas avatar mintar avatar mklpiening avatar muhrix avatar russelhowe avatar seebq avatar tim-fan avatar zabot avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

phidgets_drivers's Issues

Connect two spatial

Hi,

I am trying to use phidgets_imu. I have two spatial with different serial numbers but when I try to run the launch file provided it always connect to the same one. I am not able to create two launch files that launch two different sensors, I have changed the name of topic s but still does not work!

<!-- Phidgets IMU launch file -->

<launch>

  #### Nodelet manager ######################################################

  <node pkg="nodelet" type="nodelet" name="imu_manager" args="manager" output="screen">

  </node>

  #### IMU Driver ###########################################################

  <node pkg="nodelet" type="nodelet" name="PhidgetsImuNodelet" args="load phidgets_imu/PhidgetsImuNodelet imu_manager" output="screen">

    <remap from="/imu/data_raw" to="/imu_top/data_raw"/>
    <remap from="/imu/mag" to="/imu_top/mag"/>
    <remap from="/imu/is_calibrated" to="/imu_top/is_calibrated"/>

    # supported data rates: 4 8 16 24 32 40 ... 1000 (in ms)
    <param name="period" value="4"/>
    <param name="frame_id" value="imu_link_top"/>

    # optional param serial_number, default is -1
    <param name="serial_number" value="301940"/>

    # compass correction params (see http://www.phidgets.com/docs/1044_User_Guide)
    <param name="cc_mag_field" value="1.04193"/>
    <param name="cc_offset0" value="0.01966"/>
    <param name="cc_offset1" value="0.12772"/>
    <param name="cc_offset2" value="0.00000"/>
    <param name="cc_gain0" value="0.98090"/>
    <param name="cc_gain1" value="0.93862"/>
    <param name="cc_gain2" value="0.95976"/>
    <param name="cc_t0" value="0.00346"/>
    <param name="cc_t1" value="0.00000"/>
    <param name="cc_t2" value="0.00361"/>
    <param name="cc_t3" value="0.00000"/>
    <param name="cc_t4" value="0.00000"/>
    <param name="cc_t5" value="0.00000"/>
  </node>

  #### IMU Orientation Filter ###############################################

  <node pkg="nodelet" type="nodelet" name="ImuFilterNodelet" args="load imu_filter_madgwick/ImuFilterNodelet imu_manager" output="screen">

    <remap from="/imu/data_raw" to="/imu_top/data_raw"/>
    <remap from="/imu/mag" to="/imu_top/mag"/>
    <remap from="/imu/data" to="/imu_top/data"/>

    <param name="use_mag" value="false"/>
    <param name="use_magnetic_field_msg" value="true"/>
    <param name="world_frame" value="enu"/>
    <param name="publish_tf" value="false"/>
  </node>

</launch>

This is the example of my launch file, I tried to insert the param serial_number but no results.

Failed to load node 'phidgets_spatial' of type 'phidgets::SpatialRosI' in container

Hello All,

Recently, I switch my project from ROS1 to ROS2.
After I ran
ros2 launch phidgets_spatial spatial-launch.py.

I got the following error messages. Then the process is stuck there.
Any help to solve this issue, I will greatly appreciate.

OS: Ubuntu 18.04 in docker container
branch: dashing

  • [ERROR] [launch_ros.actions.load_composable_nodes]: Failed to load node 'phidgets_spatial' of type 'phidgets::SpatialRosI' in container '/phidget_container': Component constructor threw an exception
  • [INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '' in container '/phidget_container'
  • [component_container-1] [INFO] [phidget_container]: Load Library: /module/install/phidgets_spatial/lib/libphidgets_spatial.so
  • [component_container-1] [INFO] [phidget_container]: Found class: rclcpp_components::NodeFactoryTemplatephidgets::SpatialRosI
  • [component_container-1] [INFO] [phidget_container]: Instantiate class: rclcpp_components::NodeFactoryTemplatephidgets::SpatialRosI
  • [component_container-1] [INFO] [phidgets_spatial]: Starting Phidgets Spatial
  • [component_container-1] [ERROR] [phidget_container]: Component constructor threw an exception
    ^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
  • [component_container-1] [INFO] [rclcpp]: signal_handler(signal_value=2)
  • [INFO] [component_container-1]: process has finished cleanly [pid 10351]

Support for Analog Outputs

I've noticed Analog Outpts as e.g. Board 1002_0B aren't supported right now. It might be usefull to also support them. Have a look here for a solution similar to Digital Outputs.

Add diagnostics support back to noetic branch

In PR #39, we are rewriting the phidgets_drivers to use libphidget22 (and get us access to phidgets on VINT hubs). To keep the size of that PR down, and to keep the code consistent, we removed diagnostics from the one node that already had it (the IMU node).

This is an issue to track adding diagnostics back to the entire library so all of the nodes have it.

Spatial precision - underreported velocity

Hi!

I think I'm running into an issue with PhidgetSpatial Precision 3/3/3 High Resolution and thought maybe someone here would be able to offer some advice on the problem.

What I have noticed while testing my robot is that the odometry coming out from the EKF would be worse than the wheel odometry of the robot:

image

In the above image the green odometry is from wheel encoders and the red one is wheel_encoders odometry fused with the phidgets IMU.

In the IMU part of the EKF I'm only fusing angular rates. On the robot I've mounted an Realsense T265 tracking camera that also contains the IMU. Comparing the angular rates of the relevant axes you can see that there is slight difference in measurements:

image

Another thing to note is that I see this bot with the /imu/data_raw and /imu/data coming out from the madgwick filter.

If you have any advice I'd appreciate it. I think this setup should be correct but maybe I missed something.

Phidgets Imu driver splits my tf tree

Hey, I am using phidgets imu 3/3/3 on google cartographer, and when i launch the imu driver it splits my tf tree which avoid cartographer node to provide a map because he don't have a complete tf tree.
The launch: roslaunch phidgets_imu imu.launch

Before Launching imu driver (Only cartographer node executed):
Screenshot from 2021-03-25 08-01-55

And after:
Screenshot from 2021-03-25 08-01-35

Thanks!

Switch to libphidget22

I'm interested in adding support for some additional Phidgets devices, namely the VINT hub (and some sensors behind it). Unfortunately, the VINT hub is not supported by libphidget21, but it is supported by libphidget22.

I've done some preliminary work to see how hard it would be to switch the current code to libphidget22. The major issue as I see it is that libphidget22 has a very different idea of how to connect to devices. For instance, instead of having an InterfaceKit structure, and having the Digital Inputs and Outputs attached to that, there seems to instead be a separate DigitalInput and DigitalOutput structure. This is more flexible, but also means that the current class structure in phidgets_api doesn't really match.

Assuming we want to move to libphidget22, I can see two different ways we can make this work:

  1. Keep the current class structure, "emulating" the old ways of doing things by creating multiple device handles inside the IK class, for instance. This has the advantage of looking like the current structure, but trades off a bunch of flexibility.
  2. Change the class structure to more closely match how libphidget22 works. This has the advantage of flexibility, but it means that all of the old APIs, nodes, launch files, etc. would change.

Ultimately I want to port this entire thing to ROS 2, so backwards compatibility isn't a huge concern to me. Thus I'd personally choose option 2, as it gives us access to larger numbers of devices. However, I'd like to get some input/advice before moving forward, since I'd like to submit whatever I do to this repository. Thanks in advance for your thoughts.

MOT0109_0: Spatial: Failed to open device: Timed Out

did anyone encounter this before?
on branch noetic.
i have the phidgets spatial 3/3/3 MOT0109_0, i'm trying to launch the spatial.launch and i get these errors:

[ INFO] [1634714179.485430556]: Loading nodelet /PhidgetsSpatialNodelet of type phidgets_spatial/PhidgetsSpatialNodelet to manager imu_manager with the following remappings:
[ INFO] [1634714179.487040471]: waitForService: Service [/imu_manager/load_nodelet] has not been advertised, waiting...
[ INFO] [1634714179.492581832]: Loading nodelet /ImuFilterNodelet of type imu_filter_madgwick/ImuFilterNodelet to manager imu_manager with the following remappings:
[ INFO] [1634714179.494079519]: waitForService: Service [/imu_manager/load_nodelet] has not been advertised, waiting...
[ INFO] [1634714179.504203262]: Initializing nodelet with 8 worker threads.
[ INFO] [1634714179.508148068]: waitForService: Service [/imu_manager/load_nodelet] is now available.
[ INFO] [1634714179.510623053]: Initializing Phidgets SPATIAL Nodelet
[ INFO] [1634714179.510687100]: Starting Phidgets SPATIAL
[ INFO] [1634714179.510703508]: Opening spatial
[ INFO] [1634714179.513058698]: Connecting to Phidgets Spatial serial 373265, hub port 0 ...
[ INFO] [1634714179.515118447]: waitForService: Service [/imu_manager/load_nodelet] is now available.
[ERROR] [1634714180.514098019]: Spatial: Failed to open device: Timed Out
[FATAL] [1634714180.515002304]: Failed to load nodelet '/PhidgetsSpatialNodeletof typephidgets_spatial/PhidgetsSpatialNodeletto managerimu_manager'
[ INFO] [1634714180.525610450]: Initializing IMU Filter Nodelet
[ INFO] [1634714180.528075648]: Starting ImuFilter
[ INFO] [1634714180.539780216]: Using dt computed from message headers
[ INFO] [1634714180.539883555]: The gravity vector is kept in the IMU message.
[ INFO] [1634714180.560925486]: Imu filter gain set to 0.100000
[ INFO] [1634714180.560996819]: Gyro drift bias set to 0.000000
[ INFO] [1634714180.561031830]: Magnetometer bias values: 0.000000 0.000000 0.000000
[PhidgetsSpatialNodelet-3] process has died [pid 6039, exit code 255, cmd /opt/ros/melodic/lib/nodelet/nodelet load phidgets_spatial/PhidgetsSpatialNodelet imu_manager __name:=PhidgetsSpatialNodelet __log:=/home/user/.ros/log/9edd08f0-3175-11ec-92fd-b05cdaa8ff51/PhidgetsSpatialNodelet-3.log].
log file: /home/user/.ros/log/9edd08f0-3175-11ec-92fd-b05cdaa8ff51/PhidgetsSpatialNodelet-3*.log
[ WARN] [1634714190.572501364]: Still waiting for data on topics /imu/data_raw and /imu/mag...

can anyone help please?

Motor driver with odometry

I've implemented a driver which provides basic move_base support using phidgets encoders to produce odometry and uses the phidgets HC motor controller for motion control. This probably needs some work but if you would like to borrow some of this code or think a PR to this repo is the right place for this I'm happy to help get this brought over.

https://github.com/CumulonimbusLtd/phidgets_motion_control

libphidget22: Release into ROS2 rolling broken

TL;DR: @nuclearsandwich has to remove core.autocrlf from his .gitconfig and re-run bloom-release.

Problem

The project fails to build on the build farm on ROS2 rolling, caused by a bad bloom-release, probably by @nuclearsandwich:

https://build.ros2.org/job/Rbin_uJ64__libphidget22__ubuntu_jammy_amd64__binary/3/consoleFull

Relevant part:

08:42:27 cd /tmp/binarydeb/ros-rolling-libphidget22-2.2.1/obj-x86_64-linux-gnu/libphidget22-src && patch -p1 < /tmp/binarydeb/ros-rolling-libphidget22-2.2.1/patch/libphidgets22-1.6.20210312-fix-warnings.patch
08:42:27 patching file configure
08:42:27 patching file src/class/dataadapter.c
08:42:27 patching file src/util/dataadaptersupport.c
08:42:27 Reversed (or previously applied) patch detected!  Assume -R? [n] 
08:42:27 Apply anyway? [n] 
08:42:27 Skipping patch.
08:42:27 1 out of 1 hunk ignored -- saving rejects to file src/util/dataadaptersupport.c.rej
08:42:27 make[4]: Leaving directory '/tmp/binarydeb/ros-rolling-libphidget22-2.2.1/obj-x86_64-linux-gnu'
08:42:27 make[4]: *** [CMakeFiles/EP_libphidget22.dir/build.make:124: EP_libphidget22-prefix/src/EP_libphidget22-stamp/EP_libphidget22-patch] Error 1
08:42:27 make[3]: *** [CMakeFiles/Makefile2:140: CMakeFiles/EP_libphidget22.dir/all] Error 2
08:42:27 make[3]: Leaving directory '/tmp/binarydeb/ros-rolling-libphidget22-2.2.1/obj-x86_64-linux-gnu'
08:42:27 make[2]: Leaving directory '/tmp/binarydeb/ros-rolling-libphidget22-2.2.1/obj-x86_64-linux-gnu'
08:42:27 make[2]: *** [Makefile:149: all] Error 2
08:42:27 dh_auto_build: error: cd obj-x86_64-linux-gnu && make -j1 VERBOSE=1 returned exit code 2
08:42:28 make[1]: Leaving directory '/tmp/binarydeb/ros-rolling-libphidget22-2.2.1'
08:42:28 make[1]: *** [debian/rules:38: override_dh_auto_build] Error 25
08:42:28 make: *** [debian/rules:22: build] Error 2
08:42:28 dpkg-buildpackage: error: debian/rules build subprocess returned exit status 2

I had this problem before, so I know what caused it. The patch file in the release repository is different from the one in the source repo.

The source file has some ^M line endings, which are required:

https://github.com/ros-drivers/phidgets_drivers/blob/2.2.1/libphidget22/patch/libphidgets22-1.6.20210312-fix-warnings.patch

$ cat -v patch/libphidgets22-1.6.20210312-fix-warnings.patch                                                                                  
diff -urp libphidget22-1.6.20210312.orig/configure libphidget22-1.6.20210312/configure
--- libphidget22-1.6.20210312.orig/configure	2021-03-12 17:23:02.000000000 +0000
+++ libphidget22-1.6.20210312/configure	2021-03-22 13:55:52.553323821 +0000
@@ -5681,7 +5681,7 @@ esac
 fi
 
 : ${AR=ar}
-: ${AR_FLAGS=cru}
+: ${AR_FLAGS=cr}
 
 
 
diff -urp libphidget22-1.6.20210312.orig/src/class/dataadapter.c libphidget22-1.6.20210312/src/class/dataadapter.c
--- libphidget22-1.6.20210312.orig/src/class/dataadapter.c	2021-03-12 17:22:46.000000000 +0000
+++ libphidget22-1.6.20210312/src/class/dataadapter.c	2021-03-22 13:52:16.752083410 +0000
@@ -90,7 +90,7 @@ PhidgetDataAdapter_bridgeInput(PhidgetCh
 	uint32_t dataLen;
 	Phidget_DeviceID deviceID;
 	Phidget_DeviceClass deviceClass;
-	PhidgetDataAdapter_PacketErrorCode err;
+	uint32_t err;
 
 	ch = (PhidgetDataAdapterHandle)phid;
 
diff -urp libphidget22-1.6.20210312.orig/src/util/dataadaptersupport.c libphidget22-1.6.20210312/src/util/dataadaptersupport.c
--- libphidget22-1.6.20210312.orig/src/util/dataadaptersupport.c	2021-03-12 17:22:45.000000000 +0000
+++ libphidget22-1.6.20210312/src/util/dataadaptersupport.c	2021-03-22 13:53:10.348894764 +0000
@@ -859,49 +859,6 @@ PhidgetReturnCode sendI2CData(PhidgetCha
 	return sendDataBuffer(ch, totalCount, (const uint8_t *)buffer, bp, waitResposne);
 }^M
 ^M
-static PhidgetReturnCode^M
-waitForNAKClear(mosiop_t iop, PhidgetChannelHandle ch, uint32_t milliseconds) {^M
-	PhidgetDataAdapterSupportHandle dataAdapterSupport;^M
-	mostime_t duration;^M
-	mostime_t start;^M
-^M
-	assert(ch);^M
-	TESTATTACHED(ch);^M
-^M
-	dataAdapterSupport = DATAADAPTER_SUPPORT(ch);^M
-	assert(dataAdapterSupport);^M
-^M
-	start = 0; // make compiler happy^M
-^M
-	if (milliseconds)^M
-		start = mos_gettime_usec();^M
-^M
-	PhidgetLock(ch);^M
-	for (;;) {^M
-		if (dataAdapterSupport->nakFlag == 0) {^M
-			PhidgetUnlock(ch);^M
-			return (EPHIDGET_OK);^M
-		}^M
-^M
-		if (!_ISOPEN(ch)) {^M
-			PhidgetUnlock(ch);^M
-			return (MOS_ERROR(iop, EPHIDGET_CLOSED, "Channel was closed while waiting for clear to send."));^M
-		}^M
-^M
-		if (milliseconds) {^M
-			duration = (mos_gettime_usec() - start) / 1000;^M
-			if (duration >= milliseconds) {^M
-^M
-				PhidgetUnlock(ch);^M
-				return (EPHIDGET_TIMEOUT);^M
-			}^M
-			PhidgetTimedWait(ch, milliseconds - (uint32_t)duration);^M
-		} else {^M
-			PhidgetWait(ch);^M
-		}^M
-	}^M
-}
-
 static PhidgetReturnCode sendTXDataVINT(mosiop_t iop, PhidgetChannelHandle ch, uint8_t *buf, size_t packetLen, PhidgetTransaction *trans){
 	PhidgetReturnCode ret;
 	SetNAK(ch);

The release repo file is missing the line endings:

https://github.com/ros2-gbp/phidgets_drivers-release/blob/debian/ros-rolling-libphidget22_2.2.1-2_jammy/patch/libphidgets22-1.6.20210312-fix-warnings.patch

$ cat -v /tmp/phidgets_drivers-release/patch/libphidgets22-1.6.20210312-fix-warnings.patch              
diff -urp libphidget22-1.6.20210312.orig/configure libphidget22-1.6.20210312/configure
--- libphidget22-1.6.20210312.orig/configure	2021-03-12 17:23:02.000000000 +0000
+++ libphidget22-1.6.20210312/configure	2021-03-22 13:55:52.553323821 +0000
@@ -5681,7 +5681,7 @@ esac
 fi
 
 : ${AR=ar}
-: ${AR_FLAGS=cru}
+: ${AR_FLAGS=cr}
 
 
 
diff -urp libphidget22-1.6.20210312.orig/src/class/dataadapter.c libphidget22-1.6.20210312/src/class/dataadapter.c
--- libphidget22-1.6.20210312.orig/src/class/dataadapter.c	2021-03-12 17:22:46.000000000 +0000
+++ libphidget22-1.6.20210312/src/class/dataadapter.c	2021-03-22 13:52:16.752083410 +0000
@@ -90,7 +90,7 @@ PhidgetDataAdapter_bridgeInput(PhidgetCh
 	uint32_t dataLen;
 	Phidget_DeviceID deviceID;
 	Phidget_DeviceClass deviceClass;
-	PhidgetDataAdapter_PacketErrorCode err;
+	uint32_t err;
 
 	ch = (PhidgetDataAdapterHandle)phid;
 
diff -urp libphidget22-1.6.20210312.orig/src/util/dataadaptersupport.c libphidget22-1.6.20210312/src/util/dataadaptersupport.c
--- libphidget22-1.6.20210312.orig/src/util/dataadaptersupport.c	2021-03-12 17:22:45.000000000 +0000
+++ libphidget22-1.6.20210312/src/util/dataadaptersupport.c	2021-03-22 13:53:10.348894764 +0000
@@ -859,49 +859,6 @@ PhidgetReturnCode sendI2CData(PhidgetCha
 	return sendDataBuffer(ch, totalCount, (const uint8_t *)buffer, bp, waitResposne);
 }
 
-static PhidgetReturnCode
-waitForNAKClear(mosiop_t iop, PhidgetChannelHandle ch, uint32_t milliseconds) {
-	PhidgetDataAdapterSupportHandle dataAdapterSupport;
-	mostime_t duration;
-	mostime_t start;
-
-	assert(ch);
-	TESTATTACHED(ch);
-
-	dataAdapterSupport = DATAADAPTER_SUPPORT(ch);
-	assert(dataAdapterSupport);
-
-	start = 0; // make compiler happy
-
-	if (milliseconds)
-		start = mos_gettime_usec();
-
-	PhidgetLock(ch);
-	for (;;) {
-		if (dataAdapterSupport->nakFlag == 0) {
-			PhidgetUnlock(ch);
-			return (EPHIDGET_OK);
-		}
-
-		if (!_ISOPEN(ch)) {
-			PhidgetUnlock(ch);
-			return (MOS_ERROR(iop, EPHIDGET_CLOSED, "Channel was closed while waiting for clear to send."));
-		}
-
-		if (milliseconds) {
-			duration = (mos_gettime_usec() - start) / 1000;
-			if (duration >= milliseconds) {
-
-				PhidgetUnlock(ch);
-				return (EPHIDGET_TIMEOUT);
-			}
-			PhidgetTimedWait(ch, milliseconds - (uint32_t)duration);
-		} else {
-			PhidgetWait(ch);
-		}
-	}
-}
-
 static PhidgetReturnCode sendTXDataVINT(mosiop_t iop, PhidgetChannelHandle ch, uint8_t *buf, size_t packetLen, PhidgetTransaction *trans){
 	PhidgetReturnCode ret;
 	SetNAK(ch);

So how did these line endings disappear? Probably because whoever did the release (according to the git history I guess it's @nuclearsandwich) had the following in their .gitconfig:

[core]
	autocrlf = input

See #77 (comment) .

Solution

@nuclearsandwich has to remove core.autocrlf from his .gitconfig and re-run bloom-release. It is probably not safe to have this setting enabled on any PC that runs bloom-release.

libphidget22 noetic build fails on the build farm

Full log is here: http://build.ros.org/job/Nbin_uF64__libphidget22__ubuntu_focal_amd64__binary/2/consoleFull#console-section-15

The relevant part of the log is at the end (of course):

23:18:32 [ 37%] Performing patch step for 'EP_libphidget22'
23:18:32 cd /tmp/binarydeb/ros-noetic-libphidget22-1.0.0/obj-x86_64-linux-gnu/libphidget22-src && patch -p1 < /tmp/binarydeb/ros-noetic-libphidget22-1.0.0/patch/libphidgets22-1.6.20200417-fix-warnings.patch
23:18:32 patching file configure
23:18:32 patching file src/class/dataadapter.gen.c
23:18:32 patching file src/class/distancesensor.gen.c
23:18:32 patching file src/device/dataadapterdevice.c
23:18:32 Reversed (or previously applied) patch detected!  Assume -R? [n] 
23:18:32 Apply anyway? [n] 
23:18:32 Skipping patch.
23:18:32 1 out of 1 hunk ignored -- saving rejects to file src/device/dataadapterdevice.c.rej
23:18:32 patching file src/device/genericdevice.c
23:18:32 patching file src/phidget.c
23:18:32 make[4]: *** [CMakeFiles/EP_libphidget22.dir/build.make:106: EP_libphidget22-prefix/src/EP_libphidget22-stamp/EP_libphidget22-patch] Error 1
23:18:32 make[4]: Leaving directory '/tmp/binarydeb/ros-noetic-libphidget22-1.0.0/obj-x86_64-linux-gnu'
23:18:32 make[3]: Leaving directory '/tmp/binarydeb/ros-noetic-libphidget22-1.0.0/obj-x86_64-linux-gnu'
23:18:32 make[3]: *** [CMakeFiles/Makefile2:225: CMakeFiles/EP_libphidget22.dir/all] Error 2
23:18:32 make[2]: *** [Makefile:133: all] Error 2
23:18:32 make[2]: Leaving directory '/tmp/binarydeb/ros-noetic-libphidget22-1.0.0/obj-x86_64-linux-gnu'
23:18:32 dh_auto_build: error: cd obj-x86_64-linux-gnu && make -j1 returned exit code 2
23:18:32 make[1]: Leaving directory '/tmp/binarydeb/ros-noetic-libphidget22-1.0.0'
23:18:32 make[1]: *** [debian/rules:38: override_dh_auto_build] Error 25
23:18:32 make: *** [debian/rules:22: build] Error 2
23:18:32 dpkg-buildpackage: error: debian/rules build subprocess returned exit status 2
23:18:32 E: Building failed
23:18:32 Traceback (most recent call last):
23:18:32   File "/tmp/ros_buildfarm/ros_buildfarm/binarydeb_job.py", line 138, in build_binarydeb
23:18:32     subprocess.check_call(cmd, cwd=source_dir)
23:18:32   File "/usr/lib/python3.8/subprocess.py", line 364, in check_call
23:18:32     raise CalledProcessError(retcode, cmd)
23:18:32 subprocess.CalledProcessError: Command '['apt-src', 'build', 'ros-noetic-libphidget22']' returned non-zero exit status 1.

The prerelease test does not fail, and it completes the Performing patch step for 'EP_libphidget22' without problems:

corresponding part of the local prerelease log (click to expand)
# BEGIN SECTION: Run Dockerfile - build and install
# BEGIN SUBSECTION: build workspace in isolation and install
Invoking '_CATKIN_SETUP_DIR=/opt/ros/noetic . /opt/ros/noetic/setup.sh && PYTHONIOENCODING=utf_8 PYTHONUNBUFFERED=1 catkin_make_isolated --install --cmake-args -DBUILD_TESTING=0 -DCATKIN_SKIP_TESTING=1' in '/tmp/ws'
Base path: /tmp/ws
Source space: /tmp/ws/src
Build space: /tmp/ws/build_isolated
Devel space: /tmp/ws/devel_isolated
Install space: /tmp/ws/install_isolated
Additional CMake Arguments: -DBUILD_TESTING=0 -DCATKIN_SKIP_TESTING=1
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
~~  traversing 15 packages in topological order:
~~  - libphidget22
~~  - phidgets_api
~~  - phidgets_accelerometer
~~  - phidgets_analog_inputs
~~  - phidgets_digital_inputs
~~  - phidgets_drivers
~~  - phidgets_gyroscope
~~  - phidgets_ik
~~  - phidgets_magnetometer
~~  - phidgets_msgs
~~  - phidgets_digital_outputs
~~  - phidgets_high_speed_encoder
~~  - phidgets_motors
~~  - phidgets_spatial
~~  - phidgets_temperature
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
The packages or cmake arguments have changed, forcing cmake invocation

==> Processing catkin package: 'libphidget22'
==> Creating build directory: 'build_isolated/libphidget22'
==> cmake /tmp/ws/src/phidgets_drivers/libphidget22 -DCATKIN_DEVEL_PREFIX=/tmp/ws/devel_isolated/libphidget22 -DCMAKE_INSTALL_PREFIX=/tmp/ws/install_isolated -DBUILD_TESTING=0 -DCATKIN_SKIP_TESTING=1 -G Unix Makefiles in '/tmp/ws/build_isolated/libphidget22'
-- The C compiler identification is GNU 9.3.0
-- The CXX compiler identification is GNU 9.3.0
-- Check for working C compiler: /usr/lib/ccache/cc
-- Check for working C compiler: /usr/lib/ccache/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler: /usr/lib/ccache/c++
-- Check for working CXX compiler: /usr/lib/ccache/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Using CATKIN_DEVEL_PREFIX: /tmp/ws/devel_isolated/libphidget22
-- Using CMAKE_PREFIX_PATH: /opt/ros/noetic
-- This workspace overlays: /opt/ros/noetic
-- Found PythonInterp: /usr/bin/python3 (found suitable version "3.8.2", minimum required is "3") 
-- Using PYTHON_EXECUTABLE: /usr/bin/python3
-- Using Debian Python package layout
-- Found PY_em: /usr/lib/python3/dist-packages/em.py  
-- Using empy: /usr/lib/python3/dist-packages/em.py
-- Using CATKIN_SKIP_TESTING: 1 (implying CATKIN_ENABLE_TESTING=OFF)
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /tmp/ws/build_isolated/libphidget22/test_results
-- Forcing gtest/gmock from source, though one was otherwise available.
-- Found gtest sources under '/usr/src/googletest': gtests will be built
-- Found gmock sources under '/usr/src/googletest': gmock will be built
-- Found PythonInterp: /usr/bin/python3 (found version "3.8.2") 
-- Found Threads: TRUE  
-- Using Python nosetests: /usr/bin/nosetests3
-- catkin 0.8.6
-- BUILD_SHARED_LIBS is on
-- Configuring done
-- Generating done
CMake Warning:
  Manually-specified variables were not used by the project:

    BUILD_TESTING


-- Build files have been written to: /tmp/ws/build_isolated/libphidget22
==> make in '/tmp/ws/build_isolated/libphidget22'
Scanning dependencies of target EP_libphidget22
[ 12%] Creating directories for 'EP_libphidget22'
[ 25%] Performing download step (download, verify and extract) for 'EP_libphidget22'
-- Downloading...
   dst='/tmp/ws/build_isolated/libphidget22/EP_libphidget22-prefix/src/libphidget22-1.6.20200417.tar.gz'
   timeout='none'
-- Using src='https://www.phidgets.com/downloads/phidget22/libraries/linux/libphidget22/libphidget22-1.6.20200417.tar.gz'
-- [download 1% complete]
-- [download 3% complete]
-- [download 4% complete]
-- [download 6% complete]
-- [download 7% complete]
-- [download 9% complete]
-- [download 10% complete]
-- [download 12% complete]
-- [download 13% complete]
-- [download 15% complete]
-- [download 16% complete]
-- [download 18% complete]
-- [download 19% complete]
-- [download 21% complete]
-- [download 22% complete]
-- [download 24% complete]
-- [download 25% complete]
-- [download 27% complete]
-- [download 28% complete]
-- [download 30% complete]
-- [download 31% complete]
-- [download 33% complete]
-- [download 34% complete]
-- [download 36% complete]
-- [download 37% complete]
-- [download 39% complete]
-- [download 40% complete]
-- [download 42% complete]
-- [download 43% complete]
-- [download 45% complete]
-- [download 46% complete]
-- [download 48% complete]
-- [download 49% complete]
-- [download 51% complete]
-- [download 52% complete]
-- [download 54% complete]
-- [download 55% complete]
-- [download 57% complete]
-- [download 58% complete]
-- [download 60% complete]
-- [download 61% complete]
-- [download 63% complete]
-- [download 64% complete]
-- [download 66% complete]
-- [download 67% complete]
-- [download 69% complete]
-- [download 70% complete]
-- [download 72% complete]
-- [download 73% complete]
-- [download 75% complete]
-- [download 76% complete]
-- [download 78% complete]
-- [download 79% complete]
-- [download 81% complete]
-- [download 82% complete]
-- [download 84% complete]
-- [download 85% complete]
-- [download 86% complete]
-- [download 88% complete]
-- [download 89% complete]
-- [download 91% complete]
-- [download 92% complete]
-- [download 94% complete]
-- [download 95% complete]
-- [download 97% complete]
-- [download 98% complete]
-- [download 100% complete]
-- verifying file...
       file='/tmp/ws/build_isolated/libphidget22/EP_libphidget22-prefix/src/libphidget22-1.6.20200417.tar.gz'
-- Downloading... done
-- extracting...
     src='/tmp/ws/build_isolated/libphidget22/EP_libphidget22-prefix/src/libphidget22-1.6.20200417.tar.gz'
     dst='/tmp/ws/build_isolated/libphidget22/libphidget22-src'
-- extracting... [tar xfz]
-- extracting... [analysis]
-- extracting... [rename]
-- extracting... [clean up]
-- extracting... done
[ 37%] Performing patch step for 'EP_libphidget22'
patching file configure
patching file src/class/dataadapter.gen.c
patching file src/class/distancesensor.gen.c
patching file src/device/dataadapterdevice.c
patching file src/device/genericdevice.c
patching file src/phidget.c
[ 50%] No update step for 'EP_libphidget22'
[ 62%] Performing configure step for 'EP_libphidget22'
checking for a BSD-compatible install... /usr/bin/install -c
checking whether build environment is sane... yes
checking for a thread-safe mkdir -p... /usr/bin/mkdir -p
checking for gawk... no
checking for mawk... mawk
checking whether make sets $(MAKE)... yes
checking whether make supports nested variables... yes
checking for style of include used by make... GNU
checking for gcc... gcc
checking whether the C compiler works... yes
checking for C compiler default output file name... a.out
checking for suffix of executables... 
checking whether we are cross compiling... no
checking for suffix of object files... o
checking whether we are using the GNU C compiler... yes
checking whether gcc accepts -g... yes
checking for gcc option to accept ISO C89... none needed
checking whether gcc understands -c and -o together... yes
checking dependency style of gcc... gcc3
checking for ar... ar
checking the archiver (ar) interface... ar
checking build system type... x86_64-unknown-linux-gnu
checking host system type... x86_64-unknown-linux-gnu
checking how to print strings... printf
checking for a sed that does not truncate output... /usr/bin/sed
checking for grep that handles long lines and -e... /usr/bin/grep
checking for egrep... /usr/bin/grep -E
checking for fgrep... /usr/bin/grep -F
checking for ld used by gcc... /usr/bin/ld
checking if the linker (/usr/bin/ld) is GNU ld... yes
checking for BSD- or MS-compatible name lister (nm)... /usr/bin/nm -B
checking the name lister (/usr/bin/nm -B) interface... BSD nm
checking whether ln -s works... yes
checking the maximum length of command line arguments... 1572864
checking whether the shell understands some XSI constructs... yes
checking whether the shell understands "+="... yes
checking how to convert x86_64-unknown-linux-gnu file names to x86_64-unknown-linux-gnu format... func_convert_file_noop
checking how to convert x86_64-unknown-linux-gnu file names to toolchain format... func_convert_file_noop
checking for /usr/bin/ld option to reload object files... -r
checking for objdump... objdump
checking how to recognize dependent libraries... pass_all
checking for dlltool... no
checking how to associate runtime and link libraries... printf %s\n
checking for archiver @FILE support... @
checking for strip... strip
checking for ranlib... ranlib
checking command to parse /usr/bin/nm -B output from gcc object... ok
checking for sysroot... no
checking for mt... no
checking if : is a manifest tool... no
checking how to run the C preprocessor... gcc -E
checking for ANSI C header files... yes
checking for sys/types.h... yes
checking for sys/stat.h... yes
checking for stdlib.h... yes
checking for string.h... yes
checking for memory.h... yes
checking for strings.h... yes
checking for inttypes.h... yes
checking for stdint.h... yes
checking for unistd.h... yes
checking for dlfcn.h... yes
checking for objdir... .libs
checking if gcc supports -fno-rtti -fno-exceptions... no
checking for gcc option to produce PIC... -fPIC -DPIC
checking if gcc PIC flag -fPIC -DPIC works... yes
checking if gcc static flag -static works... yes
checking if gcc supports -c -o file.o... yes
checking if gcc supports -c -o file.o... (cached) yes
checking whether the gcc linker (/usr/bin/ld -m elf_x86_64) supports shared libraries... yes
checking whether -lc should be explicitly linked in... no
checking dynamic linker characteristics... GNU/Linux ld.so
checking how to hardcode library paths into programs... immediate
checking whether stripping libraries is possible... yes
checking if libtool supports shared libraries... yes
checking whether to build shared libraries... yes
checking whether to build static libraries... yes
checking whether make supports nested variables... (cached) yes
checking for gcc option to accept ISO C99... none needed
checking whether byte ordering is bigendian... no
checking for ldconfig... /sbin/ldconfig
checking for library containing dlopen... -ldl
checking for library containing sqrt... -lm
checking for library containing pthread_create... -lpthread
checking for library containing libusb_init... -lusb-1.0
checking for newlocale in xlocale.h... no
checking for newlocale in locale.h... yes
checking that generated files are newer than configure... done
configure: creating ./config.status
config.status: creating Makefile
config.status: creating libphidget22.pc
config.status: executing depfiles commands
config.status: executing libtool commands
[ 75%] Performing build step for 'EP_libphidget22'
  CC       src/analogsensor.lo
  CC       src/bridge.lo
  CC       src/bridgepackets.gen.lo
  CC       src/class/accelerometer.lo
  CC       src/class/bldcmotor.lo
  CC       src/class/capacitivetouch.lo
  CC       src/class/currentinput.lo
  CC       src/class/currentoutput.lo
  CC       src/class/dataadapter.lo
  CC       src/class/dcmotor.lo
  CC       src/class/dictionary.lo
  CC       src/class/digitalinput.lo
  CC       src/class/digitaloutput.lo
  CC       src/class/distancesensor.lo
  CC       src/class/encoder.lo
  CC       src/class/firmwareupgrade.lo
  CC       src/class/frequencycounter.lo
  CC       src/class/generic.lo
  CC       src/class/gps.lo
  CC       src/class/gyroscope.lo
  CC       src/class/hub.lo
  CC       src/class/humiditysensor.lo
  CC       src/class/ir.lo
  CC       src/class/lcd.lo
  CC       src/class/lightsensor.lo
  CC       src/class/magnetometer.lo
  CC       src/class/meshdongle.lo
  CC       src/class/motorpositioncontroller.lo
  CC       src/class/phsensor.lo
  CC       src/class/powerguard.lo
  CC       src/class/pressuresensor.lo
  CC       src/class/rcservo.lo
  CC       src/class/resistanceinput.lo
  CC       src/class/rfid.lo
  CC       src/class/soundsensor.lo
  CC       src/class/spatial.lo
  CC       src/class/stepper.lo
  CC       src/class/temperaturesensor.lo
  CC       src/class/voltageinput.lo
  CC       src/class/voltageoutput.lo
  CC       src/class/voltageratioinput.lo
  CC       src/constants.lo
  CC       src/datainterval.gen.lo
  CC       src/debug.lo
  CC       src/device/accelerometerdevice.lo
  CC       src/device/advancedservodevice.lo
  CC       src/device/analogdevice.lo
  CC       src/device/bridgedevice.lo
  CC       src/device/dataadapterdevice.lo
  CC       src/device/dictionarydevice.lo
  CC       src/device/encoderdevice.lo
  CC       src/device/firmwareupgradedevice.lo
  CC       src/device/frequencycounterdevice.lo
  CC       src/device/genericdevice.lo
  CC       src/device/gpsdevice.lo
  CC       src/device/hubdevice.lo
  CC       src/device/interfacekitdevice.lo
  CC       src/device/irdevice.lo
  CC       src/device/leddevice.lo
  CC       src/device/meshdongledevice.lo
  CC       src/device/motorcontroldevice.lo
  CC       src/device/phsensordevice.lo
  CC       src/device/rfiddevice.lo
  CC       src/device/servodevice.lo
  CC       src/device/spatialdevice.lo
  CC       src/device/stepperdevice.lo
  CC       src/device/temperaturesensordevice.lo
  CC       src/device/textlcddevice.lo
  CC       src/device/vintdevice.lo
  CC       src/devices.lo
  CC       src/dispatch.lo
  CC       src/enumutil.gen.lo
  CC       src/errorstrings.gen.lo
  CC       src/ext/cvtutf.lo
  CC       src/ext/md5.lo
  CC       src/ext/mos/base64.lo
  CC       src/ext/mos/base.lo
  CC       src/ext/mos/crc32.lo
  CC       src/ext/mos/ctype.lo
  CC       src/ext/mos/endswith.lo
  CC       src/ext/mos/getcwd.lo
  CC       src/ext/mos/getenv.lo
  CC       src/ext/mos/getopt.lo
  CC       src/ext/mos/getpasswd-unix.lo
  CC       src/ext/mos/glob.lo
  CC       src/ext/mos/glock.lo
  CC       src/ext/mos/hexdump.lo
  CC       src/ext/mos/init_daemon.lo
  CC       src/ext/mos/iop.lo
  CC       src/ext/mos/kv/kv.lo
  CC       src/ext/mos/kv/kvent.lo
  CC       src/ext/mos/kv/parse.lo
  CC       src/ext/mos/kv/scan.lo
  CC       src/ext/mos/malloc.lo
  CC       src/ext/mos/malloc-user.lo
  CC       src/ext/mos/md5c.lo
  CC       src/ext/mos/memchr.lo
  CC       src/ext/mos/memcmp.lo
  CC       src/ext/mos/memmem.lo
  CC       src/ext/mos/mkdirp.lo
  CC       src/ext/mos/mos_atomic-pthread.lo
  CC       src/ext/mos/mos_dl-unix.lo
  CC       src/ext/mos/mos_error-errno.lo
  CC       src/ext/mos/mos_fileio-unix-user.lo
  CC       src/ext/mos/mos_lock-pthread.lo
  CC       src/ext/mos/mos_net.lo
  CC       src/ext/mos/mos_netops-unix.lo
  CC       src/ext/mos/mos_os.lo
  CC       src/ext/mos/mos_random-unix.lo
  CC       src/ext/mos/mos_setenv-native.lo
  CC       src/ext/mos/mos_stacktrace-gnu.lo
  CC       src/ext/mos/mos_task-pthread.lo
  CC       src/ext/mos/mos_time-unix.lo
  CC       src/ext/mos/mos_tlock.lo
  CC       src/ext/mos/path.lo
  CC       src/ext/mos/pkcs5_pbkdf2.lo
  CC       src/ext/mos/printf-smart.lo
  CC       src/ext/mos/process-unix.lo
  CC       src/ext/mos/rand48.lo
  CC       src/ext/mos/random.lo
  CC       src/ext/mos/readdir-unix.lo
  CC       src/ext/mos/readline.lo
  CC       src/ext/mos/rwrlock.lo
  CC       src/ext/mos/scanf.lo
  CC       src/ext/mos/sha1.lo
  CC       src/ext/mos/sha2.lo
  CC       src/ext/mos/snprintf.lo
  CC       src/ext/mos/strcasecmp.lo
  CC       src/ext/mos/strchr.lo
  CC       src/ext/mos/strcmp.lo
  CC       src/ext/mos/strdup.lo
  CC       src/ext/mos/strlcat.lo
  CC       src/ext/mos/strlcpy.lo
  CC       src/ext/mos/strlen.lo
  CC       src/ext/mos/strncmp.lo
  CC       src/ext/mos/strncpy.lo
  CC       src/ext/mos/strnsep.lo
  CC       src/ext/mos/strnstr.lo
  CC       src/ext/mos/strrchr.lo
  CC       src/ext/mos/strrev.lo
  CC       src/ext/mos/strstr.lo
  CC       src/ext/mos/strton.lo
  CC       src/ext/mos/strtrim.lo
  CC       src/ext/mos/time.lo
  CC       src/ext/mos/urldecode.lo
  CC       src/ext/mos/urlencode.lo
  CC       src/ext/mos/vasprintf.lo
  CC       src/formatters.lo
  CC       src/gpp.lo
  CC       src/lightning.lo
  CC       src/manager.lo
  CC       src/mesh.lo
  CC       src/network/channel.lo
  CC       src/network/client.lo
  CC       src/network/network.lo
  CC       src/network/networkcontrol.lo
  CC       src/network/server.lo
  CC       src/network/servers.lo
  CC       src/network/zeroconf-avahi.lo
  CC       src/object.lo
  CC       src/phidget.lo
  CC       src/phidget22.lo
  CC       src/plat/linux/usblinux.lo
  CC       src/spi.lo
  CC       src/stats.lo
  CC       src/supportedpacket.gen.lo
  CC       src/usb.lo
  CC       src/util/config.lo
  CC       src/util/jsmn.lo
  CC       src/util/json.lo
  CC       src/util/log.lo
  CC       src/util/packettracker.lo
  CC       src/util/packing.lo
  CC       src/util/utils.lo
  CC       src/vint.lo
  CC       src/vintpackets.lo
  CC       src/virtual.lo
  CCLD     libphidget22.la
Making phidget22.h
[ 87%] No install step for 'EP_libphidget22'
[100%] Completed 'EP_libphidget22'
[100%] Built target EP_libphidget22
==> make install in '/tmp/ws/build_isolated/libphidget22'
[100%] Built target EP_libphidget22
Install the project...
-- Install configuration: ""
-- Installing: /tmp/ws/install_isolated/_setup_util.py
-- Installing: /tmp/ws/install_isolated/env.sh
-- Installing: /tmp/ws/install_isolated/setup.bash
-- Installing: /tmp/ws/install_isolated/local_setup.bash
-- Installing: /tmp/ws/install_isolated/setup.sh
-- Installing: /tmp/ws/install_isolated/local_setup.sh
-- Installing: /tmp/ws/install_isolated/setup.zsh
-- Installing: /tmp/ws/install_isolated/local_setup.zsh
-- Installing: /tmp/ws/install_isolated/.rosinstall
-- Installing: /tmp/ws/install_isolated/lib/pkgconfig/libphidget22.pc
-- Installing: /tmp/ws/install_isolated/share/libphidget22/cmake/libphidget22-extras.cmake
-- Installing: /tmp/ws/install_isolated/share/libphidget22/cmake/libphidget22Config.cmake
-- Installing: /tmp/ws/install_isolated/share/libphidget22/cmake/libphidget22Config-version.cmake
-- Installing: /tmp/ws/install_isolated/share/libphidget22/package.xml
-- Installing: /tmp/ws/install_isolated/include/libphidget22
-- Installing: /tmp/ws/install_isolated/include/libphidget22/phidget22.h
-- Installing: /tmp/ws/install_isolated/lib/libphidget22.so
-- Installing: /tmp/ws/install_isolated/lib/libphidget22.so.0
-- Installing: /tmp/ws/install_isolated/lib/libphidget22.so.0.0.0
<== Finished processing package [1 of 15]: 'libphidget22'

The failure on the build farm occurs during the build_binarydeb phase. It can be reproduced locally using the following steps:

docker run -it ros:noetic-ros-core

# in docker:

echo deb http://repositories.ros.org/ubuntu/building focal main | tee -a /etc/apt/sources.list.d/buildfarm.list
echo deb-src http://repositories.ros.org/ubuntu/building focal main | tee -a /etc/apt/sources.list.d/buildfarm.list
apt update
apt install -y apt-src
apt-src update
apt-src install ros-noetic-libphidget22=1.0.0-1focal
apt-src build ros-noetic-libphidget22=1.0.0-1focal

@jspricke @clalancette Any idea what's going on? Maybe the patch is being applied twice?

Out-of-order packets

Here's another one I hope to characterize better tomorrow, but I want to get it written in case anyone's seen this behavior before: it appears sometimes that the driver publishes IMU messages to the topic out-of-order in time. That is, a message will hit the topic with an earlier capture time than the most recent, as if there's a race condition somewhere in the pipeline ahead of publishing. In most applications, this probably doesn't matter much, but for whatever reason, Cartographer chooses to handle it with an instant choke-and-die.

Bloom-Release to ROS2 Dashing / Eloquent

Thank you for all the re-working done in this repo for ROS2 @clalancette & @mintar! I've been building this repo from source and using it with several sensors for a few weeks now. So far in my testing, things seem to be working well, though I admittedly am not using every phidget sensor.

This is just a friendly request to push these packages up into the ros buildfarm for ease of use/deployment:

  • bloom-release into ros-dashing
  • bloom-release into ros-eloquent

Thanks!

Allow configuring encoder IOMode

The new encoder module ENC1000_0 has several IOMode options:

typedef enum {
 ENCODER_IO_MODE_PUSH_PULL = 0x1,
 ENCODER_IO_MODE_LINE_DRIVER_2K2 = 0x2,
 ENCODER_IO_MODE_LINE_DRIVER_10K = 0x3,
 ENCODER_IO_MODE_OPEN_COLLECTOR_2K2 = 0x4,
 ENCODER_IO_MODE_OPEN_COLLECTOR_10K = 0x5,
} Phidget_EncoderIOMode;

This should be configurable from the node. I'd like to add it as a node parameter (and I'll send a PR), but I'd like to know if this should be configured as a string (and match it to the enum) or an integer and just pass it directly?

libphidget21 download URL incorrect

In libphidget21/CMakeLists.txt, I had to update the URL in line 11 to the following, lest the download would 404

ExternalProject_Add(EP_${PROJECT_NAME}                                                                           
    URL https://www.phidgets.com/downloads/phidget21/libraries/linux/libphidget/libphidget_2.1.8.20151217.tar.gz 
   URL_MD5 818ab2ff1de92ed9568a206e0e89657f 
...

Enhancement: Questions about adding support for Stepper Phidgets

@clalancette I am working on adding the interface to stepper phidgets. I have a few questions about the implementation choices you prefer.

I created a Stepper class in the phidgets_api and I am modeling it after your Motor class. You added a Motors class since there are some phidgets that control multiple dc motors from one VINT port. There do not seem to be any stepper phidgets that control multiple motors from one port. Should I go ahead and create a Steppers class as well even though it is not really necessary just so it better matches the way dc motors are handled? Is the idea with these drivers that there will be one node per VINT port? An alternative might be to use a vector of serial numbers and hub ports when creating the Steppers class so that multiple steppers are controlled by one node, but perhaps just creating separate nodes, one for each stepper, is cleaner.

I want to expose almost all of the stepper phidget functions so I have them available for my future projects. The stepper phidget API has like 30-40 functions. Should I create one topic per function or does that make a mess of the topic namespace? I could group some together so we can set things like acceleration, control mode, and current limits in one setup topic and leave setting and publishing the target position or velocity in separate topics since those will be called regularly. Do you have a preference on how such things are grouped?

Thanks!

Cannot specify remote vint hubs

The drivers do not discover a vint hub without specifying server details, i.e.:

PhidgetNet_addServer("myServerVintHub","100.100.0.1", 5661, "", 0);

Inserting that line and adding rosparams for server_name and server_ip, I have it working on the phidgets_temperature package. If it's agreeable to the devs, I can add similar launch file parameters to all the packages and submit a PR?

In addition, a similar change I could include would be to specify a server_password parameter from the launch file and the 'setServerPassword' method.

Please let me know if this is useful and I'll push, thank you!

Failed to load library (ros foxy installation)

After installing phidgets_drivers from source I tried to launch the spatial executable using:
ros2 launch phidgets_spatial spatial-launch.py
And I got:

[INFO] [launch]: All log files can be found below /home/rover/.ros/log/2021-08-04-15-35-36-796098-rover-ThinkCentre-M73-39388
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container-1]: process started with pid [39401]
[component_container-1] [INFO] [1628105737.177545698] [phidget_container]: Load Library: /home/rover/rover_ws/install/phidgets_spatial/lib/libphidgets_spatial.so
[component_container-1] [ERROR] [1628105737.180257760] [phidget_container]: Failed to load library: Could not load library LoadLibrary error: libphidget22.so.0: cannot open shared object file: No such file or directory, at /home/rover/ros2_foxy/src/ros2/rcutils/src/shared_library.c:84
[ERROR] [launch_ros.actions.load_composable_nodes]: Failed to load node 'phidgets_spatial' of type 'phidgets::SpatialRosI' in container '/phidget_container': Failed to load library: Could not load library LoadLibrary error: libphidget22.so.0: cannot open shared object file: No such file or directory, at /home/rover/ros2_foxy/src/ros2/rcutils/src/shared_library.c:84

I checked and there is a 'shared_library.c' at path '/home/rover/ros2_foxy/src/ros2/rcutils/src/'
Any clue what is going wrong ?

Bridge 4 Input Support

Hi
this is a copy of my post on ROS answers, but i think here might be a better place to ask:

im trying to get the data from the PhidgetBridge 4-Input into ros noetic (e.g. publishing the sensor values on a topic). As far as i've understood this device is not supported yet. Is that correct or could i reuse one of the existing packes in phidgets_drivers? Maybe with minor modification?

So far i've tried using the analog input nodelet roslaunch phidgets_analog_inputs analog_inputs.launch(pulled and built the noetic branch) however i got the connection problem: [ERROR] [1614854548.863487183]: AnalogInputs: Failed to open device: Timed Out(device is pluged in usb port an visible in /dev)

If unsupported, i'm willing to try to contribute, however as i've never done anything alike i would appriciate any reccomendation or help on what steps to take?

Garbage diagnostics data when the IMU is not connected

We fill hardware IDs if the IMU is not connected here:

https://github.com/ros-drivers/phidgets_drivers/blob/kinetic/phidgets_imu/src/imu_ros_i.cpp#L174

This leads to broken strings (we added a ROS_FATAL below to print the data):

[/broken/imu_manager  INFO 1541437152.313089147]: Starting Phidgets IMU
[/broken/imu_manager  INFO 1541437152.349699310]: Opening device
[/broken/imu_manager  INFO 1541437152.349842384]: Waiting for IMU to be attached...
[/broken/imu_manager FATAL 1541437162.359115469]: Problem waiting for IMU attachment: Given timeout has been exceeded. Make sure the USB cable is connected and you have executed the
phidgets_api/share/setup-udev.sh script.
[/broken/imu_manager  INFO 1541437162.359166272]: Calibrating IMU...
[/broken/imu_manager  INFO 1541437162.359194949]: Calibrating IMU done.
[/broken/imu_manager FATAL 1541437162.359280129]: h?W?_ -32767
[/broken/imu_manager  INFO 1541437162.359303531]: No compass correction params found.

Also the calibrate() in the function probably only makes sense if the IMU is connected. So maybe adding both to an else case is enough?

IMU gyro calibration time is not taken into account in the ROS service.

The CPhidgetSpatial_zeroGyro function from the Phidgets API returns directly, however the actual process takes around 2 seconds as written in the documentation:

Zeroes the gyroscope. This takes about two seconds and the gyro zxes will report 0 during the process. This should only be called when the board is not moving.

The imu/calibrate service logs success and returns immediately after calling this gyro calibration. This is bad because to a client it looks like the calibration is done, although moving the IMU in the 2 seconds period right after the calibration call will lead to a constant drift.

ROS_INFO("Calibrating IMU...");
zero();
ROS_INFO("Calibrating IMU done.");


I propose the following:

  1. change the log messages of the ROS service (#41)

  2. change the behavior of the service handler?
    Block 2 seconds or introduce an API change and use an action that takes 2 seconds?

Side note: Currently the service returns an empty response but there's an extra, unlatched /imu/is_calibrated topic that kind of takes over the job of a service response field. If we change the service API, we could also get rid of that topic by introducing a proper response field. Or, make it latched so one can check when it was calibrated the last time?

Add usage instructions to README

Hi there, I'm just trying this out in ROS2 for the first time with an IMU. All is working well, thank you to all the developers!

Just thought I'd note I had a bit of difficulty figuring out how to get the driver running, and maybe an addition to the readme would help others.

Basically I expected to be able to run a phidgets_spatial node, and I was a bit confused when I found the package does not build any nodes (only components). Later I found that there are launch files which handle the launching of the component.

My suggestion would be to add to the phidgets_spatial README.md:

## Usage
To launch the phidgets_spatial node:
ros2 launch phidgets_spatial spatial-launch.py

I assume a similar addition could be made to the rest of the driver packages as well.


Extra detail: The sequence of steps I took to get it going:

  1. Look at the phidget spatial readme, which documents the node API, but not how to start the node
  2. try to ros2 run phidget_spatial phidget_spatial, but that executable does not exist
  3. try to figure out which executables exist in the phidget spatial package, but there are none: ros2 pkg executables phidgets_spatial
  4. Have a look into the CMakeLists.txt, notice that no nodes are built, but a component is registered
  5. Google ros2 components, found this https://ubuntu.com/blog/components-vs-plugins-in-ros-2
  6. Based on the above, started a component container and load the phidgets_spatial component
  7. success!
  8. notice from reading issue logs that phidgets_spatial that launch files exist for starting the node
  9. more convenient success!

fatal error: libphidgets/phidget21.h: No such file or directory compilation terminated

I have installed the Phidgets libraries following the following link and the "Hello World" example was working.
http://www.phidgets.com/docs/OS_-_Linux#Quick_Downloads

But when I install Phidgets ROS driver
https://github.com/ccny-ros-pkg/phidgets_drivers
I got the error
fatal error: libphidgets/phidget21.h: No such file or directory compilation terminated.

How does it happy? The libraries have been installed by the Linux driver, right?

Left handed coordinates?

Right handed coordinates are the standard in ROS, but this package seems to report back left handed coordinates. Is there a reason?

Servo question

So this is more of a question than an issue.
I bought the PhidgetAdvancedServo 8-Motor controller hoping to use it from ROS as described here:

http://wiki.ros.org/phidgets

From there was then directed here to use this latest phidgets_driver repo.
I cannot an example launch file or an example rosrun command to use this controller.
Can someone direct me to one of these examples?
BTW I am using ROS Kinetic.

Thanks
Joshua

Enable travis

Hi @jack-oquin , first off: thanks a bunch for adding us to ros-drivers! :)

To celebrate, here is another request: could you enable Travis for this repo? It requires "owner" access, and I only have "write". Once you click that checkbox on travis-ci.org, we can add and maintain a .travis.yaml ourselves without any more intervention from you I guess.

PhidgetDCMotor_getBackEMF Operation Not Supported Error in dashing branch

@clalancette nice work on the upgrade to Phidget22 in the dashing branch, thank you!

I was playing with a DC Motor Phidget and I noticed that although the DCMotor class API lists getBackEMF, none of the DC Motor Phidget APIs actually seem to support that function. So when I run your code I get a "[component_container-1] [ERROR] [phidgets_motors]: Motors: Failed to get back EMF for Motor channel 0: Operation Not Supported" error.

I am happy to help you fix this or to do more testing if you do not have time. In ROS, is it better practice to not even create a publisher on an unsupported topic or is it better to publish some dummy value?

Interface Kit Support

I supported the Phidgets Interface Kit a while ago but due to the long awaited release of this repo for jade/kinetic have not released it as a seperate package. If you would like I'd happily submit a PR here for to support the interface kit directly to this repo as I think this probably a better place for it.

https://github.com/CumulonimbusLtd/phidgets_interface_kit

PhidgetSpatial 3/3/3 Basic 1042_0B Connection Issues - Melodic

Hello,

I am having trouble using your phidget_imu imu.launch script.
Issue:
roslaunch phidget_imu imu.launch
Outputs the following

SUMMARY

PARAMETERS

  • /ImuFilterNodelet/use_mag: True
  • /ImuFilterNodelet/use_magnetic_field_msg: True
  • /PhidgetsImuNodelet/period: 4
  • /rosdistro: melodic
  • /rosversion: 1.14.12

NODES
/
ImuFilterNodelet (nodelet/nodelet)
PhidgetsImuNodelet (nodelet/nodelet)
imu_manager (nodelet/nodelet)

ROS_MASTER_URI=http://localhost:11311

process[imu_manager-1]: started with pid [9468]
process[PhidgetsImuNodelet-2]: started with pid [9469]
process[ImuFilterNodelet-3]: started with pid [9470]
[ INFO] [1642688272.830204431]: Loading nodelet /PhidgetsImuNodelet of type phidgets_imu/PhidgetsImuNodelet to manager imu_manager with the following remappings:
[ INFO] [1642688272.865155316]: Loading nodelet /ImuFilterNodelet of type imu_filter_madgwick/ImuFilterNodelet to manager imu_manager with the following remappings:
[ INFO] [1642688272.881463024]: Initializing nodelet with 4 worker threads.
}
[ INFO] [1642688272.886425733]: waitForService: Service [/imu_manager/load_nodelet] has not been advertised, waiting...
[ INFO] [1642688272.913038285]: waitForService: Service [/imu_manager/load_nodelet] is now available.
[ INFO] [1642688272.963427972]: Initializing Phidgets IMU Nodelet
[ INFO] [1642688272.994070524]: Starting Phidgets IMU
[ INFO] [1642688273.089416149]: Opening device
[ INFO] [1642688273.089530837]: Waiting for IMU to be attached...
[FATAL] [1642688283.093874271]: Problem waiting for IMU attachment: Given timeout has been exceeded. Make sure the USB cable is connected and you have executed the phidgets_api/share/setup-udev.sh script.
[ INFO] [1642688283.094001406]: Calibrating IMU, this takes around 2 seconds to finish. Make sure that the device is not moved during this time.
[ INFO] [1642688285.094174895]: Calibrating IMU done.

Additional Info:

  • I can interact with the device using the Phidget Python library, so I know the device is connected and working.
  • I've installed the libphidget22 and libphidget21 libraries separately as well to ensure that when the system is compiled it would have everything it needs. However, i've noticed the ros package comes with it's own libphidget21 folder (so I assume the system libraries aren't used)
    Device:
  • Jetson Nano
    OS:
  • Ubuntu 18.04

Any help would be greatly appricated.
Thanks,

Services' type

Hello,

I realise now that my approach to services for IL, in #22 might not be the best.
Wouldn't it be better to define a single service with two parameters : id of the output (int) and state (bool) ?

Rotational drifting

The last not-fully-characterized issue I'll post tonight, I promise. Every so often, our robot appears to be freely rotating about Z in space. It's unclear what the root cause of the issue is, but when it comes up, power cycling the IMU seems to clear it up, at least temporarily. This suggests to me it's not actually a driver issue, but has anyone else seen gyro offset like this? Could it be related to magnetometer calibration (or lack thereof)?

set_digital_output service has success=false, but output is set correctly

I have a PhidgetInterfaceKit 8/8/8 P/N1018. When I run

~$ rosrun phidgets_ik  phidgets_ik_node 
[ INFO] [1607075109.917870379]: Starting Phidgets IK
[ INFO] [1607075109.918402573]: Opening device
[ INFO] [1607075109.918626262]: Waiting for IK -1 to be attached...
Phidget attached (serial# 324112)
[ INFO] [1607075109.938885559]: 8 inputs, 8 outputs, 8 sensors
[ INFO] [1607075125.475819619]: Setting output 0 to 1

and then in another terminal

~$ rosservice call /set_digital_output "index: 0 
state: true" 
success: False

the success variable is false, but the output is actually set correctly. Why "success" is false?

[galactic] spatial-launch.py fails when not providing Magnetometer corrections

Bug Report

After the switch to ROS2 Galactic, the spatial-launch.py (and probably also the magnetometer) fails when not providing magnetometer corrections.

Reproduction

Simply calling ros2 launch phidgets_spatial spatial-launch.py yields:

[INFO] [component_container-1]: process started with pid [4695]
[component_container-1] 1626088543.095012 [0] component_: using network interface eth0 (udp/192.168.1.210) selected arbitrarily from: eth0, docker0
[component_container-1] [INFO] [1626088543.296766218] [phidget_container]: Load Library: /home/angsa/ros_ws/install/phidgets_spatial/lib/libphidgets_spatial.so
[component_container-1] [INFO] [1626088543.309701892] [phidget_container]: Found class: rclcpp_components::NodeFactoryTemplate<phidgets::SpatialRosI>
[component_container-1] [INFO] [1626088543.310028374] [phidget_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<phidgets::SpatialRosI>
[component_container-1] [INFO] [1626088543.336890208] [phidgets_spatial]: Starting Phidgets Spatial
[component_container-1] [ERROR] [1626088543.536905484] [phidget_container]: Component constructor threw an exception: expected [double] got [not set]
[ERROR] [launch_ros.actions.load_composable_nodes]: Failed to load node 'phidgets_spatial' of type 'phidgets::SpatialRosI' in container '/phidget_container': Component constructor threw an exception: expected [double] got [not set]

Reason

The declare_parameter here fails:

this->declare_parameter<double>("cc_mag_field");

Apparently the way ROS handles undeclared parameters changed.

I propose moving the declare_parameter in the try..catch clause and additionally catch the rclcpp::ParameterTypeException.

We did that in https://github.com/angsa-robotics/phidgets_drivers/commit/7cc3fe74f64d5b3462cf8dd934fc168f6d1dab5d

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.