ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

problem with publish in fork() process

asked 2015-11-11 07:34:38 -0500

wdsky2010 gravatar image

When I use fork() function, then the publish function of Publisher do not work, do any one who has met this problem, I am grateful that you can tell me something, thanks :-) the code

 #include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>
#include <stdio.h>
#include <unistd.h>
#include <stdlib.h>
#include <string.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>

void error(const char *msg)
{
    perror(msg);
    exit(1);
}
/**
 * This tutorial demonstrates simple sending of messages over the ROS system.
 */
int main(int argc, char **argv)
{
  ros::init(argc, argv, "talker");

  ros::NodeHandle nh;

  ros::Publisher chatter_pub = nh.advertise<std_msgs::String>("chatter", 1000);

  int sockfd, newsockfd, portno, pid;
  socklen_t clilen;
  struct sockaddr_in serv_addr, cli_addr;

  if (argc < 2) {
      fprintf(stderr,"ERROR, no port provided\n");
      exit(1);
  }

  sockfd = socket(AF_INET, SOCK_STREAM, 0);
  if (sockfd < 0)
     error("ERROR opening socket");
  bzero((char *) &serv_addr, sizeof(serv_addr));
  portno = atoi(argv[1]);
  //portno = 8888;
  serv_addr.sin_family = AF_INET;
  serv_addr.sin_addr.s_addr = INADDR_ANY;
  serv_addr.sin_port = htons(portno);
  if (bind(sockfd, (struct sockaddr *) &serv_addr, sizeof(serv_addr)) < 0)
      error("ERROR on binding");
  listen(sockfd,5);
  clilen = sizeof(cli_addr);
  while(ros::ok())
  {
      newsockfd = accept(sockfd, (struct sockaddr *) &cli_addr, &clilen);   
      if (newsockfd < 0)
        error("ERROR on accept");
    pid = fork();
    if (pid < 0)
        error("ERROR on fork");
    if (pid == 0)  {
        close(sockfd);
        std_msgs::String msg;
       //ros::NodeHandle nh;
       //ros::Publisher chatter_pub = nh.advertise<std_msgs::String>("chatter", 1000);
       int n;
       char buffer[256];
       //while(ros::ok())
       //{         
           bzero(buffer,256);
          n = read(newsockfd,buffer,255);
          if (0 > n) error("ERROR reading from socket");
          else if(0 < n)
          {
              msg.data = buffer;
              ROS_INFO("%s", msg.data.c_str());
              chatter_pub.publish(msg);
              printf("Here is the message: %s\n",buffer);
              n = write(newsockfd,"I got your message",18);
              if (n < 0) error("ERROR writing to socket");
          }
          else ;
        //dostuff(newsockfd, chatter_pub);
        exit(0);
    }
    else close(newsockfd);
  }
  close(sockfd);
  return 0;
}
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
3

answered 2015-11-12 17:12:37 -0500

Well, do not use fork() in multi-threaded application unless you really know what you are doing. Please see Threads and fork(): think twice before mixing them.

Yes, roscpp is implicitly multi-threaded. There are at least two threads after invoking ros::init(), one is your main thread, while another belong to PollManager which essentially processes all incoming and outgoing messages by polling a list of sockets which were opened by publishers and subscribers.

As stated on the man page fork(2) and also mentioned on the link above:

The child process is created with a single thread—the one that called fork(). The entire virtual address space of the parent is replicated in the child, including the states of mutexes, condition variables, and other pthreads objects; the use of pthread_atfork(3) may be helpful for dealing with problems that this can cause.

No wonder data is not published. The PollManager is not running because its thread was not created in the forked process and thus it is not polling socket descriptors for incoming or outgoing data.

If you really want to mix this 'classical server approach' and ROS code, then I would suggest to try initializing roscpp after the fork(). In this case make sure you are not using any ROS functionality before that, e.g. do not call ros::ok() as it relies on the initialization state of the roscpp library.

edit flag offensive delete link more

Comments

Firstly, many thanks for you, and according to your very appreciate explanation, I have soled this problem by multi-threads rather than using fork(). :-)

wdsky2010 gravatar image wdsky2010  ( 2015-11-12 20:28:33 -0500 )edit

And what's more, I wonder if there is a good mechanism to make such a server, I want to make a server that can have more than one non-ROS clients, and the server should publish or subscribe topics. Thank you.

wdsky2010 gravatar image wdsky2010  ( 2015-11-12 20:49:46 -0500 )edit

Check these server examples. Particularly take a look at threaded server example. One note though: since you are using ROS anyway which is heavily dependent on Boost, it would be a good idea to use boost threads instead of raw pthreads.

Boris gravatar image Boris  ( 2015-11-13 09:21:43 -0500 )edit

thank you again :-)

wdsky2010 gravatar image wdsky2010  ( 2015-11-14 10:18:05 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-11-11 07:34:38 -0500

Seen: 842 times

Last updated: Nov 12 '15