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

ROS Action with no Subscriber

asked 2022-04-26 22:18:57 -0600

naihart gravatar image

Iam creating an action server and the process is just rotating turtlesim depending on how many times the goal is set to. As far as I researched, the sample codes for ROS Action have their main function inside the subscriber callback. From my problem, I dont need to have a subscriber so I dont need subscriber callback. What I have tried is to put the main function inside the goal callback, the problem is the preempt. with this method, I cant preempt the server because the goal callback should finish first before other callbacks are called. Another is to have isPreemptRequested() function but when I cancel the goal, It finishes the last rotation first before canceling the goal (it does not cancel/ stop immediately). And for my last try, for the goal callback, I only put the acceptNewGoal() function and put the main function to new function. My problem with this is the main function is not working (probably because I dont have another function with callback to call this function [expected for subscriber callback]). Anyone have done action server with no subscriber? any tips or suggestion?

Here's my last try code:

 #include <ros/ros.h>
 #include <actionlib/server/simple_action_server.h>
 #include <geometry_msgs/Twist.h>
 #include "actn_turtlesim/testAction.h"

 class testAction
{
   protected:
   ros::NodeHandle nh;
   actionlib::SimpleActionServer<actn_turtlesim::testAction> action_srv;
   std::string action_name;

  int rotation;
  int counter;
  double time_diff;
  float PI = 3.14159265359;

  actn_turtlesim::testResult result;
  actn_turtlesim::testFeedback feedback;
  ros::Publisher pub;
  geometry_msgs::Twist vel_msg;

public:

   testAction(std::string name) : 
   action_srv(nh, name, false),
   action_name(name)
  {
      action_srv.registerGoalCallback(boost::bind(&testAction::goalCB, this));
      action_srv.registerPreemptCallback(boost::bind(&testAction::preemptCB, this));
      pub = nh.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 1);
      action_srv.start();
      ROS_INFO("Action Server started");
  }

  ~testAction(void)
 {
 }

 void goalCB()
 {
      rotation = action_srv.acceptNewGoal()->rotation;
 }

 void rotate()
{
      if (action_rotate.action_srv.isNewGoalAvailable())
     {
        ros::Rate rate(1);
        ros::Time time_begin = ros::Time::now();
        ros::Time time_end;

       for (counter = 0; rotation != counter; counter++)
       {
          vel_msg.linear.x = 10.0;
          vel_msg.angular.z = PI * 2;
          pub.publish(vel_msg);
          feedback.rotation = counter;
          action_srv.publishFeedback(feedback);
          ROS_INFO("%d Rotation/s done", counter); 
          time_end = ros::Time::now();
          time_diff = time_end.toSec() - time_begin.toSec();
          rate.sleep();
        }
       if (rotation == counter && success == true)
       {
          result.time = time_diff; 
          ROS_INFO("Result: %f secs", time_diff);
          action_srv.setSucceeded(result);
        }
    }
   }

  void preemptCB()
  {
      vel_msg.linear.x = 0.0;
      vel_msg.angular.z = 0.0;
      pub.publish(vel_msg);
      ROS_INFO("%s: Preempted", action_name.c_str());
      ROS_INFO("Result: %f secs", time_diff);
      action_srv.setPreempted();
      success = false;
  }
};

int main(int argc, char** argv)
{
   ros::init(argc, argv, "action_server_turtle");
   testAction action_rotate("turtle_rotate");
   ros::spin();
   return 0;
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2022-04-30 13:40:45 -0600

Mike Scheutzow gravatar image

Your ActionServer is a regular ros node. You must create a loop inside what you call goalCB(), and do all your "server work" inside that loop. You must sleep inside the loop, usually using a ros::Rate object. The SimpleActonServer tutorial shows you how to do this: link

ROS will check for preempt each time you call sleep() on the Rate object, so that will work fine.

edit flag offensive delete link more

Comments

Thank you for your reply, from what Ive done/ experienced, I already have ros::Rate in my callback but the preempt still doesnt work appropriately (Im guessing it is because of the for loop). Nevertheless, I already have a solution for this, and it is almost same as your suggestion. I got my "server work" inside goalCB and separate preemptCB. I also added boolean in which becomes true if the preemptCB has been called, this will flag inside the for loop so the rotation will stop abruptly. And the most important thing is to have your class structure like this testAction(std::string name) : action_srv(nh, name, boost::bind(&testAction::goalCB, this, _1), false), action_name(name) { action_srv.registerPreemptCallback(boost::bind(&testAction::preemptCB, this)); //initialize something }

naihart gravatar image naihart  ( 2022-05-09 12:43:48 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2022-04-26 22:18:57 -0600

Seen: 164 times

Last updated: Apr 30 '22