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

action client stuck waiting on server

asked 2019-06-10 16:30:16 -0500

morten_nissov gravatar image

I've been trying to write an action file (cpp) using the Fibonacci example as a guide but so far it's just getting stuck on starting the server and i can't quite see why.

#include <stdio.h>
#include <std_msgs/String.h>

#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include <actionlib/client/simple_action_client.h>

#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/CommandBool.h>

#include <rovexp/ModeAction.h>

typedef actionlib::SimpleActionServer<rovexp::ModeAction> Server;
class ModeActionServer {
protected:
    ros::NodeHandle nh_;

    ros::ServiceClient arming_client_;
    ros::ServiceClient set_mode_client_;

    Server mode_server_;

    rovexp::ModeFeedback feedback_;
    rovexp::ModeResult result_;
    std::string action_name_;
public:
    ModeActionServer(std::string name) :
        mode_server_(nh_, name, boost::bind(&ModeActionServer::executeCB, this, _1), false),
        action_name_(name)
    {
        mode_server_.start();
        ROS_INFO("Mode action server started...");
    }
    ~ModeActionServer(void) { }

    void executeCB(const rovexp::ModeGoalConstPtr &goal)
    {
        ROS_INFO_STREAM("mode experiment started...");

        /*
        set_mode_client_ = nh_.serviceClient<mavros_msgs::SetMode>("mavros/set_mode");
        mavros_msgs::SetMode offb_set_mode;
        offb_set_mode.request.custom_mode = goal->mode_num;

        set_mode_client_.call(offb_set_mode);
        */

        arming_client_ = nh_.serviceClient<mavros_msgs::CommandBool>("mavros/cmd/arming");
        ros::Rate rate(20.0);
        mavros_msgs::CommandBool arm_cmd;
        arm_cmd.request.value = true;
        arming_client_.call(arm_cmd);
    }
};

typedef actionlib::SimpleActionClient<rovexp::ModeAction> Client;
void modeActionClient(uint8_t mode_num)
{
    Client client("mode_client", true);

    ROS_INFO("Waiting for action server to start");
    client.waitForServer();

    rovexp::ModeGoal goal;
    goal.mode_num = mode_num;
    printf("%d\t4\n",goal.mode_num);
    client.sendGoal(goal);

    client.waitForResult();
}

int main(int argc, char**argv)
{
    if(std::string(argv[1])=="-server")
    {
      ros::init(argc, argv, "mode_server");
      ModeActionServer server("mode_server");
      //server.start();
      ros::spin();

    }
    else if(std::string(argv[1])=="-client")
    {
        if ( std::string(argv[2])=="-h" ) {
            printf("Use: rosrun rovexp mode -client @mode\n"); 
            exit(-1);
        }
        ros::init(argc, argv, "mode_action_client");
        uint8_t mode_num = atoi(argv[2]);
        modeActionClient(mode_num);
    }
    printf("done\n");   
    return 0;
}

This is the action cpp file. After running the server and the client I get both "Mode action server started..." and "Waiting for action server to start" so I figure that means the client is getting caught up on ROS_INFO_STREAM("mode experiment started...");. I'm not quite sure why the server is taking so long to start up. I've also attempted the Fibonacci example in link and that works fine.

Ubuntu 16.04 LTS and ROS Kinetic.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2019-06-11 04:07:49 -0500

gvdhoorn gravatar image

updated 2019-06-11 04:09:27 -0500

ModeActionServer server("mode_server");

and

Client client("mode_client", true);

If I'm not mistaken, the first argument to the ctor would be the namespace the client uses to communicate with the server (docs).

You set that to mode_server for the server, but to mode_client for the client.

That would make them unable to find each other, causing the client to wait for the server to come up.

The example server and client you mention use fibonacci for both the server and the client. That's probably why that version of the code does "work".

edit flag offensive delete link more

Comments

I didn't notice that at all but yeah after doing that it works when run off a roscore on my computer.

I'm currently using ROS within the frame of an underwater ROV. When I connect to the robot and use the robot's address as the master_uri instead the same problem occurs.

Am I missing some mavros library or something?

morten_nissov gravatar image morten_nissov  ( 2019-06-11 06:18:44 -0500 )edit

I didn't notice that at all but yeah after doing that it works when run off a roscore on my computer.

Good. So your question has been answered.

I'm currently using ROS within the frame of an underwater ROV. When I connect to the robot and use the robot's address as the master_uri instead the same problem occurs.

that would be a different question, and it's bad form to post follow-up questions in comments.

gvdhoorn gravatar image gvdhoorn  ( 2019-06-11 06:25:02 -0500 )edit

I would suggest to lookup older Q&As about multi-host network setups and ROS, as it's most likely a problem with you using hostnames and not having a working DNS that is able to resolve all names into IPs. To check whether that is the case, set ROS_IP on all involved hosts and try again.

gvdhoorn gravatar image gvdhoorn  ( 2019-06-11 06:26:19 -0500 )edit

Thanks for the advice. And sorry I had totally forgotten to do that.

morten_nissov gravatar image morten_nissov  ( 2019-06-16 06:02:06 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-06-10 16:30:16 -0500

Seen: 2,987 times

Last updated: Jun 11 '19