Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix bug in transport_tcp #1050

Merged
merged 2 commits into from
May 17, 2017
Merged

Fix bug in transport_tcp #1050

merged 2 commits into from
May 17, 2017

Conversation

bxwllzz
Copy link
Contributor

@bxwllzz bxwllzz commented May 9, 2017

Fix about Subscribing & Publishing from ROS nodes does not work · Issue #1391 · Microsoft/BashOnWindows

Line 316 in ros_comm/roscpp/src/libros/transport/transport_tcp.cpp

  312   int ret = ::connect(sock_, (sockaddr*) &sas, sas_len);
  313   // windows might need some time to sleep (input from service robotics hack) add this if testing proves it is necessary.
  314   ROS_ASSERT((flags_ & SYNCHRONOUS) || ret != 0);
  315   if (((flags_ & SYNCHRONOUS) && ret != 0) || // synchronous, connect() should return 0
  316       (!(flags_ & SYNCHRONOUS) && last_socket_error() != ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN)) // asynchronous, connect() should return -1 and WSAGetLastError()=WSAEWOULDBLOCK/errno=EINPROGRESS
  317   {
  318     ROSCPP_CONN_LOG_DEBUG("Connect to tcpros publisher [%s:%d] failed with error [%d, %s]", host.c_str(), port, ret, last_socket_error_string());
  319     close();
  320 
  321     return false;
  322   }

It assumes that the connect method of non-blocking scoket should return -1 and last_socket_error() should return ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN(=EINPROGRESS).
But a non-blocking connect can return 0 when TCP connection to 127.0.0.1 (localhost).
http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket

In Bash on Ubuntu on Windows, when connecting to 127.0.1.1 non-blocking, it returns 0 which raise an error
[WARN] [1479567965.827686]: Inbound TCP/IP connection failed: connection from sender terminated before handshake header received. 0 bytes were received. Please check sender for additional details.

After patch, topic tests successfully in ROS/Tutorials/WritingPublisherSubscriber(python), ROS/Tutorials/ExaminingPublisherSubscriber and turtlesim

It assumes that the `connect` method of non-blocking scoket should return -1 and `last_socket_error()` should return `ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN`(=`EINPROGRESS`). 
But a non-blocking `connect` can return 0 when TCP connection to 127.0.0.1 (localhost).
[http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket](http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket)
@gavanderhoorn
Copy link
Contributor

This is related to Installing ROS on Ubuntu Bash in Windows 10 on ROS Answers.

I've tested this briefly on my own Win10/WSL/Trusty/Indigo installation and it seems to work (meaning: both publishing and subscribing work from the 'WSL host'), although I'm not entirely convinced this is the way to implement the patch.

if (((flags_ & SYNCHRONOUS) && ret != 0) || // synchronous, connect() should return 0
(!(flags_ & SYNCHRONOUS) && last_socket_error() != ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN)) // asynchronous, connect() should return -1 and WSAGetLastError()=WSAEWOULDBLOCK/errno=EINPROGRESS
(!(flags_ & SYNCHRONOUS) && // asynchronous, connect() may return 0 or -1. When return -1, WSAGetLastError()=WSAEWOULDBLOCK/errno=EINPROGRESS
(ret != 0 && last_socket_error() != ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN)))
Copy link
Member

@dirk-thomas dirk-thomas May 9, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The added condition ret != 0 makes sense. Checking last_socket_error when ret is 0 doesn't make sense.

Can you please indent this line by another space (since the expression is nested within the open parenthesis from the line before). Also the additional parenthesis around this line are not necessary.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I hava modified the code format .

Modify code format
@dirk-thomas
Copy link
Member

Thanks!

@dirk-thomas dirk-thomas merged commit 0c36d4b into ros:lunar-devel May 17, 2017
@@ -311,9 +311,10 @@ bool TransportTCP::connect(const std::string& host, int port)

int ret = ::connect(sock_, (sockaddr*) &sas, sas_len);
// windows might need some time to sleep (input from service robotics hack) add this if testing proves it is necessary.
ROS_ASSERT((flags_ & SYNCHRONOUS) || ret != 0);
// ROS_ASSERT((flags_ & SYNCHRONOUS) || ret != 0);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should this commented line be left in?

There is no comment near it to explain what is going on here.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It could indeed be removed since it doesn't match the behavior on Windows.

@bxwllzz bxwllzz deleted the bxwllzz-patch-transport_tcp branch May 18, 2017 04:55
@janbernloehr
Copy link

Is it possible to make this fix available for kinetic as well?

@gonzalocasas
Copy link

It would be reaaaally good if this fix could be ported to Kinetic as well.

andyli pushed a commit to andyli/ros_comm that referenced this pull request May 29, 2017
* Fix bug in transport_tcp

It assumes that the `connect` method of non-blocking scoket should return -1 and `last_socket_error()` should return `ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN`(=`EINPROGRESS`). 
But a non-blocking `connect` can return 0 when TCP connection to 127.0.0.1 (localhost).
[http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket](http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket)

* Modify code format

Modify code format
sputnick1124 pushed a commit to sputnick1124/ros_comm that referenced this pull request Jul 30, 2017
* Fix bug in transport_tcp

It assumes that the `connect` method of non-blocking scoket should return -1 and `last_socket_error()` should return `ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN`(=`EINPROGRESS`). 
But a non-blocking `connect` can return 0 when TCP connection to 127.0.0.1 (localhost).
[http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket](http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket)

* Modify code format

Modify code format
@gavanderhoorn
Copy link
Contributor

gavanderhoorn commented Oct 18, 2017

@dirk-thomas: I couldn't find this (easily, or didn't try hard enough): can you confirm whether or not this fix has been back-ported to Kinetic?

@gonzalocasas
Copy link

gonzalocasas commented Oct 18, 2017 via email

@dirk-thomas
Copy link
Member

The last release into Kinetic is from before this bug has been fixed. It will be backported before the next Kinetic release.

@bxwllzz
Copy link
Contributor Author

bxwllzz commented Oct 23, 2017

https://github.com/ros/ros_comm/blob/lunar-devel/clients/roscpp/src/libros/transport/transport_tcp.cpp

I found another bug in transport_tcp.cpp with Windows Subsystem for Linux.
TransportTCP::read() did not check if socket is conneted. If socket is asynchronous, it may fails at recv() if its slow to connect (e.g. happens with wireless).
TransportTCP::read() and TransportTCP::write() needs to check if its connected or not when it's asynchronous.

Detailed debug log

Test Environment:

  • PC 1 (Windows Subsystem for Linux, wired): RViz
  • PC 2 (Ubuntu 16.04, wireless): roscore and other nodes
...
[DEBUG] [1508756684.267337700]: Retrying connection to [pc2:60159] for topic [/kinect/rgb/image_color]
[DEBUG] [1508756684.387001100]: Resolved publisher host [pc2] to [192.168.123.211] for socket [24]
[DEBUG] [1508756684.387432900]: setsockopt failed to set SO_KEEPALIVE on socket [24] [pc2:60159 on socket 24]
[DEBUG] [1508756684.387574800]: setsockopt failed to set TCP_KEEPCNT on socket [24] [pc2:60159 on socket 24]
[DEBUG] [1508756684.388021100]: Adding tcp socket [24] to pollset
[DEBUG] [1508756684.388515700]: Async connect() in progress to [pc2:60159] on socket [24]
[DEBUG] [1508756684.388849400]: recv() on socket [24] failed with error [传输端点尚未连接] (ENGLISH TRANSLATION: The transmission endpoint is not connected yet)
[DEBUG] [1508756684.389211800]: TCP socket [24] closed
[DEBUG] [1508756684.389618800]: Connection::drop(0)
[DEBUG] [1508756684.389992600]: Connection to publisher [TCPROS connection on port 3678 to [pc2:60159 on socket 24]] to topic [/kinect/rgb/image_color] dropped
...

Fix

man page connect(2)
EINPROGRESS
The socket is nonblocking and the connection cannot be
completed immediately. It is possible to select(2) or poll(2)
for completion by selecting the socket for writing. After
select(2) indicates writability, use getsockopt(2) to read the
SO_ERROR option at level SOL_SOCKET to determine whether
connect() completed successfully (SO_ERROR is zero) or
unsuccessfully (SO_ERROR is one of the usual error codes
listed here, explaining the reason for the failure).

I'm trying to add some code to check if its connected or not.

@dirk-thomas
Copy link
Member

@bxwllzz Please either open a new ticket about the new bug or propose a PR with the changes you described. Since this ticket is different and already closed it is unlikely that anybody will look at your comment in the future.

bxwllzz added a commit to bxwllzz/ros_comm that referenced this pull request Oct 25, 2017
* Fix bug in transport_tcp

It assumes that the `connect` method of non-blocking scoket should return -1 and `last_socket_error()` should return `ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN`(=`EINPROGRESS`). 
But a non-blocking `connect` can return 0 when TCP connection to 127.0.0.1 (localhost).
[http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket](http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket)

* Modify code format

Modify code format
@bxwllzz
Copy link
Contributor Author

bxwllzz commented Oct 25, 2017

@dirk-thomas I have proposed a new PR #1202 about this problem.

dirk-thomas pushed a commit that referenced this pull request Oct 25, 2017
* Fix bug in transport_tcp

It assumes that the `connect` method of non-blocking scoket should return -1 and `last_socket_error()` should return `ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN`(=`EINPROGRESS`). 
But a non-blocking `connect` can return 0 when TCP connection to 127.0.0.1 (localhost).
[http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket](http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket)

* Modify code format

Modify code format
dantwinkler added a commit to 6RiverSystems/ros_comm that referenced this pull request Dec 28, 2017
* fix open mode on Windows

* Fix BZip2 inclusion

* Respect if/unless for roslaunch-check.

* fix rosmsg show from bag

* fix rosbag::View::iterator copy assignment operator (ros#1017)

* refactor test_rosbag_storage

* fix rosbag::View::iterator copy assignment operator

the compiler-generated copy assignment operator did lead to segfault and
memory leaks.

* Add subscriber to connection log messages. (ros#1023)

* ensure cwd exists

* Sleep in rospy wait_for_service even if exceptions raised

* Avoid deleting XmlRpcClient's while they are being still in use on another thread (ros#1013)

* Avoid deleting XmlRpcClient's while they are being still in use on another thread

   * Acquire clients_mutex_ before deleting the clients
   * Remove the timed wait for the clients to become not in use
   * Only delete and erase clients that are not in use
   * Clients that would still be in use would delete themselves on release

* Wait for clients that are in use to finish in XmlRpcManager::shutdown

* Abort topic lookup on connection refused

In a multimaster environment where a topic has multiple publishers,
when a node drops out abruptly (host is shutdown), a single subscriber update on
that topic will cause multiple threads to be created (one for each host) in order to
resolve the topic location. This cause a thread leak as host which are turned off
will not respond and when they come back online, the xmlrpc URI is changed causing a
connection refused error at the socket layer.

This fix catches the connection refused error and terminate the thread with the understanding
that if the connection is refused, the rosnode cannot be reached now or never. This effectively
prevents thread leak.

Note: if the remote host where the rosnode is thought to be never comes back up,
then the thread will still be leaked as the exception received is a host unreachable type.
This is intentional to avoid abruptly terminating the thread in case of a temporary DNS failure.

* Fix bug in transport_tcp (ros#1050)

* Fix bug in transport_tcp

It assumes that the `connect` method of non-blocking scoket should return -1 and `last_socket_error()` should return `ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN`(=`EINPROGRESS`). 
But a non-blocking `connect` can return 0 when TCP connection to 127.0.0.1 (localhost).
[http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket](http://stackoverflow.com/questions/14027326/can-connect-return-0-with-non-blocing-socket)

* Modify code format

Modify code format

* Fix race condition that lead to miss first message (lunar) (ros#1058)

* Fix race condition that lead to miss first message

Callback queue waits for callback from "callOne" method.
When internal queue is not empty this last method succeeded even if id
info mapping does not contains related callback's id.
In this case, first callback (for one id) is never called since
"addCallback" method first push callback into internal queue and *then*
set info mapping.

So id info mapping has to be set before push callback into internal
queue. Otherwise first message could be ignored.

* Added test for addCallback race condition

* ensure pid file is removed on exit

* Changed the check command output to be a little bit more specific.

* [roslaunch] Fix pid file removing condition

* [rospy] Add option to reset timer when time moved backwards (ros#1083)

* Add option to reset timer when time moved backwards

* refactor logic

* add missing mutex lock for publisher links

* [rospy] Improve rospy.logXXX_throttle performance

* Added logging output when `roslogging` cannot change permissions (ros#1068)

* Added logging output when `roslogging` cannot change permissions

Added better differentiated logging output to `roslogging` so that
problems with permission is made clear to the user. Accompanying test
have also been added.

* Removed testing, updated warning message and fixed formatting

Removed testing since test folder should not be stored together with
tests. Since testing group permission requires intervention outside the
test harness the test it self is also removed.

Updated the warning message to include `WARNING` and updated to using
`%` formatting.

* [rostest] Check /clock publication neatly in publishtest (ros#973)

* Check /clock publication neatly in publishtest

- Use time.sleep because rospy.sleep(0.1) hangs if /clock is not published
- Add timeout for clock publication

* Add comment explaining use of time.sleep.

* Use logwarn_throttle not to flood the console

* A fix to a critical stack buffer overflow vulnerability which leads to direct control flow hijacking (ros#1092)

* A fix to a critical stack buffer overflow vulnerability which leads to control flow hi-jacking.

* Much more simple fix for the stack overflow bug

* only launch core nodes if master was launched by roslaunch

* Made copying rosbag::Bag a compiler error to prevent crashes and added a swap function instead (ros#1000)

* Made copying rosbag::Bag a compiler error to prevent crashes

* Added Bag::swap(Bag&) and rosbag::swap(Bag&, Bag&)

* Fixed bugs in Bag::swap

* Added tests for Bag::swap

* [roscpp] add missing header for writev().

After an update of gcc and glibc roscpp started to fail builds with the error:

    /home/rojkov/work/ros/build/tmp-glibc/work/i586-oe-linux/roscpp/1.11.21-r0/ros_comm-1.11.21/clients/roscpp/src/libros/transport/transport_udp.cpp:579:25: error: 'writev' was not declared in this scope
         ssize_t num_bytes = writev(sock_, iov, 2);
                             ^~~~~~

According to POSIX.1-2001 the function writev() is declared in sys/uio.h.

The patch includes the missing header for POSIX compliant systems.

* Add SteadyTimer (ros#1014)

* add SteadyTimer

based on SteadyTime (which uses the CLOCK_MONOTONIC).
This timer is not influenced by time jumps of the system time,
so ideal for things like periodic checks of timeout/heartbeat, etc...

* fix timer_manager to really use a steady clock when needed

This is a bit of a hack, since up to boost version 1.61 the time of the steady clock is always converted to system clock,
which is then used for the wait... which obviously doesn't help if we explicitly want the steady clock.

So as a workaround, include the backported versions of the boost condition variable if boost version is not recent enough.

* add tests for SteadyTimer

* [test] add -pthread to make some tests compile

not sure if this is only need in my case on ROS indigo...

* use SteadyTime for some timeouts

* add some checks to make sure the backported boost headers are included if needed

* specialize TimerManager threadFunc for SteadyTimer

to avoid the typeid check and make really sure the correct boost condition wait_until implementation is used

* Revert "[test] add -pthread to make some tests compile"

This reverts commit f62a3f2.

* set minimum version for rostime

* mostly spaces

* Close CLOSE_WAIT sockets by default (ros#1104)

* Add close_half_closed_sockets function

* Call close_half_closed_sockets in xmlrpcapi by default

* fix handling connections without indices

* fix rostopic prining long integers

* update tests to match stringify changes

* ignore headers with zero stamp in statistics

* Improves the stability of SteadyTimerHelper.

Due to scheduling / resource contention, `sleep`s and `wait_until`s may be delayed. The `SteadyTimerHelper` test class was not robust to these delays, which was likely the cause of a failing test (`multipleSteadyTimeCallbacks` in `timer_callbacks.cpp`:220).

* Improve steady timer tests (ros#1132)

* improve SteadyTimer tests

instead of checking when the callback was actually called,
check for when it was added to the callback queue.

This *should* make the test more reliable.

* more tolerant and unified timer tests

* xmlrpc_manager: use SteadyTime for timeout

* Replaced deprecated lz4 function call

* Removed deprecated dynamic exception specifications

* only use CLOCK_MONOTONIC if not apple

* Improved whitespace to fix g++ 7 warning

.../ros_comm/tools/rosbag_storage/src/view.cpp:249:5: warning: this ‘if’ clause does not guard... [-Wmisleading-indentation]
     if ((bag.getMode() & bagmode::Read) != bagmode::Read)
     ^~
.../ros_comm/tools/rosbag_storage/src/view.cpp:252:2: note: ...this statement, but the latter is misleadingly indented as if it were guarded by the ‘if’
  boost::function<bool(ConnectionInfo const*)> query = TrueQuery();
  ^~~~~

* Using poll() in favor of select() in the XmlRPCDispatcher (ros#833)

* Using poll() in favor of select() in the XmlRPCDispatcher

* ros#832: initialize pollfd event with 0. Added check for POLLHUP and POLLNVAL

* Fix syntax

* poll flags emulate select, verify requests, sync/init sources/fds

This commit makes sure that the poll flags emulate select (which it replaces).
It also double-checks event types to make sure they were requested (e.g. POLLERR might trigger both).
It keeps track of fd/src relationship through two parallel arrays, instead of an iterator / array hybrid.

* Fix rostopic hz and bw in Python 3 (ros#1126)

* string.atoi is not present in Python3, just use int(x)

* rostopic bw: set default value of window_size arg to -1 instead of None

* Check for window_size < 0 when constructing ROSTopicBandwidth object

* Revert "Check for window_size < 0 when constructing ROSTopicBandwidth object"

This reverts commit 86a2a29.

* Revert "rostopic bw: set default value of window_size arg to -1 instead of None"

This reverts commit 4c74df9.

* Check for argument != None before calling int(options.window_size)

* Properly check for options.window_size != None before converting to int

* Don't direct users to build rosout with rosmake. (ros#1140)

* Don't direct users to build rosout with rosmake.

* Eliminate special case for rosout being missing.

* use not deprecated console_bridge macros and undefine the deprecated ones

* Fix rosbag API for Python 3

Closes ros#1047

* Sort the output of rosnode info.

* Minor fixes for compatibility with both Python 2 & 3

* [bug] fixes ros#1158 (ros#1159)

* [bug] fixes ros#1158

XmlLoader and LoaderContext no longer share the param list to child 'node' contexts.
This was causing the creation of unintended private parameters when the tilde notation was used.

* added test cases for tilde param in launch

* added test cases for tilde param in python

* fixed tilde param issue for group tags

Issue ros#1158 manifested for group tags that appear before (but not containing) node tags.

* added one more test case for issue ros#1158
used param tag to make sure we test the proposed fix

* Added negative tests for extra parameters

Some parameters should not be present at all.

* rosconsole: replaced 'while(0)' by 'while(false)'

* Change rospy.Rate hz type from int to float (ros#1177)

* Don't try to set unknown socket options (ros#1172)

* Don't try to set unknown socket options

These are not avaible on FreeBSD, for example

* individualize ifdefs

* fix whitespace

* rosnode: Return exit code 1 if there is an error. (ros#1178)

* Fixed an out of bounds read in void rosbag::View::iterator::increment() (ros#1191)

- Only triggered if reduce_overlap_ = true
- When iters_.size() == 1 and iters_.pop_back() gets called in the loop,
  the next loop condition check would read from iters_.back(), but
  iters_ would be empty by then.

* Test bzfile_ and lz4s_ before reading/writing/closing (ros#1183)

* Test bzfile_ before reading/writing/closing

* Test lz4stream before reading/writing

* More agile demux. (ros#1196)

* More agile demux.

Publishers in demux are no longer destroyed and recreated when switching, which results in much faster switching behavior. The previous version took even 10 seconds to start publishing on the newly selected topic (all on localhost).

Please, comment if you feel the default behavior should stay as the old was, and this new behavior should be triggered by a parameter.

* update style

* catch exception with `socket.TCP_INFO` on WSL (ros#1212)

* catch exception with `socket.TCP_INFO` on WSL

fixes issue ros#1207
this only catches socket error 92

* Update util.py

* Update util.py

* avoid unnecessary changes, change import order

* fix path check

* fix error message to mention what was actually tested

* fix roswtf test when rosdep is not initialized

* update changelogs

* 1.12.8

* backward compatibility with libconsole-bridge in Jessie

* update changelogs

* 1.12.9

* backward compatibility with libconsole-bridge in Jessie (take 2)

* update changelogs

* 1.12.10

* Revert "Replaced deprecated lz4 function call"

This reverts commit a31ddd0.

* update changelogs

* 1.12.11

* backward compatibility with libconsole-bridge in Jessie (take 3) (ros#1235)

* backward compatibility with libconsole-bridge in Jessie (take 3)

* copy-n-paste error

* remove fragile undef

* dont rely on existence of short version of the macros, define the long with API calls instead

* remove empty line

* update changelogs

* 1.12.12

* place console_bridge macros definition in header and use it everywhere console_bridge is included (ros#1238)
@elahia
Copy link

elahia commented Jul 25, 2018

Hi guys,

I have the same problem, and i want to update the transport_tcp.cpp file, but i cannot find it!!
Can anyone please help me to find it!

Thanks

@gonzalocasas
Copy link

@elahia this is already solved, I am using Kinetic on WSL without any issues. Did you try updating kinetic?

@elahia
Copy link

elahia commented Jul 25, 2018

@gonzalocasas thank you for your fast reply, No, actually i'm not using kinetic, my ros pack is so small (at least by now) and i only need to publish and subscribe to a topic! but when i check the topic by : rostopic echo /topicname

i get this error:
[WARN] [1532505967.859467]: Inbound TCP/IP connection failed: timed out

so even for working with messages, i have to install kinetic?

Regards

@gavanderhoorn
Copy link
Contributor

gavanderhoorn commented Jul 25, 2018

kinetic is a release name, not a particular set of packages (well .. it sort of is actually).

What @gonzalocasas means is: as long as you have a version of ros_comm installed that is part of the kinetic release, things should work.

@elahia
Copy link

elahia commented Jul 25, 2018

@gavanderhoorn i tried this to install WSL on my windows 10. and now i have lunar installed on my win 10.
I'm not sure if by installing WSL the ros_comm also is installed or not!

if i have to install it separately, would you please suggest me some link?
Thanks

@gavanderhoorn
Copy link
Contributor

Lunar is newer than Kinetic, and the packages in ros_comm are a base dependency / integral part of ROS, so if you followed the instructions on that page it should work.

If it doesn't, then either something changed in WSL (that happens often, seeing as it's still being developed), a regression was introduced by a later commit to ros_comm or something else is wrong (firewall issue perhaps?).

In any case: the changes in this PR (ie: the one you're commenting on) were already merged, so manually changing transport_tcp.cpp should not be needed.

@elahia
Copy link

elahia commented Jul 25, 2018

oh my bad! I was just confused between Kinect and kinetic!
btw how can i fix my publisher ( .py file) to publish a topic without this error!

@gonzalocasas
Copy link

gonzalocasas commented Jul 25, 2018

@elahia if you have ROS Lunar installed, you should not have this error. Are you sure the issue you are seeing is really this same one? Could you post some more details about your setup and the log you are getting?

@gavanderhoorn
Copy link
Contributor

Let's not start diagnosing this on this thread.

@elahia: please post a question on ROS Answers. If it turns out something is not right in ros_comm, you can always post a new issue while referring to this one and your ROS Answers question.

@elahia
Copy link

elahia commented Jul 25, 2018

@gavanderhoorn @gonzalocasas I just switched to Linux 14.04 ( with ros indigo) to test my code (to be sure the problem is with WSL or my own code)

interestingly i get the same error:

[WARN] [WallTime: 1532521089.338552] Inbound TCP/IP connection failed: connection from sender terminated before handshake header received. 0 bytes were received. Please check sender for additional details.

So i think this is not related to this topic even by same error!

@gonzalocasas
Copy link

ROS Indigo definitely doesn't work properly with WSL, only Kinetic onwards. But as @gavanderhoorn recommended, please post the details on ROS Answers.

@elahia
Copy link

elahia commented Jul 25, 2018

Ok i will create a new post, but just to clarify, my ros indigo is installed in another pc and i just ran my code on another pc without any WSL. but got same error...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants