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

error with action server and client

asked 2017-03-24 14:19:56 -0500

dinesh gravatar image

updated 2017-03-24 17:09:12 -0500

When i run below action server and client, i'm getting error:

[INFO] [WallTime: 1490393212.373839] /fibonacci: Succeeded
[INFO] [WallTime: 1490393212.374787] /fibonacci: Succeeded
[ERROR] [WallTime: 1490393212.375245] To transition to a succeeded state, the goal must be in a preempting or active state, it is currently in state: 3

My action server is:

   #! /usr/bin/env python

import rospy

import actionlib

from control_msgs.msg import (
    FollowJointTrajectoryGoal,
    FollowJointTrajectoryActionResult,
    FollowJointTrajectoryAction,
    FollowJointTrajectoryActionFeedback,
)

class FibonacciAction(object):
    # create messages that are used to publish feedback/result
    _feedback = FollowJointTrajectoryActionFeedback()
    _result = FollowJointTrajectoryActionResult()

    def __init__(self, name):
        self._action_name = name
        self._as = actionlib.SimpleActionServer(self._action_name, FollowJointTrajectoryAction, execute_cb=self.execute_cb, auto_start = False)
        self._as.start()

    def execute_cb(self, _goal):
        r = rospy.Rate(1)
        success = True

        # start executing the action
        for i in range(0, 2):
            # check that preempt has not been requested by the client
            if self._as.is_preempt_requested():
                rospy.loginfo('%s: Preempted' % self._action_name)
                self._as.set_preempted()
                success = False

            self._feedback.feedback.header.seq = 1
            self._as.publish_feedback(self._feedback.feedback)

            if success:
                self._result.header = self._feedback.header
                rospy.loginfo('%s: Succeeded' % self._action_name)
                self._as.set_succeeded(self._result.result)


if __name__ == '__main__':
    rospy.init_node('fibonacci')
    server = FibonacciAction(rospy.get_name())
    rospy.spin()

And my action client is:

    #include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <actionlib/client/terminal_state.h>
#include <control_msgs/FollowJointTrajectoryAction.h>
int main (int argc, char **argv)
{
  ros::init(argc, argv, "fibonacci_client_py");

  // create the action client
  // true causes the client to spin its own thread
  actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> ac("fibonacci", true);

  ROS_INFO("Waiting for action server to start.");
  // wait for the action server to start
  ac.waitForServer(); //will wait for infinite time

  ROS_INFO("Action server started, sending goal.");
  // send a goal to the action
  control_msgs::FollowJointTrajectoryGoal goal;

    goal.trajectory.joint_names.push_back("joint1");
    goal.trajectory.joint_names.push_back("joint2");

    // We will have two waypoints in this goal trajectory
    goal.trajectory.points.resize(2);

    // First trajectory point
    // Positions
    int ind = 0;
    goal.trajectory.points[ind].positions.resize(2);
    goal.trajectory.points[ind].positions[0] = 1.0;
    goal.trajectory.points[ind].positions[1] = 1.0;
    // Velocities
    goal.trajectory.points[ind].velocities.resize(2);
    for (size_t j = 0; j < 2; ++j)
    {
      goal.trajectory.points[ind].velocities[j] = 0.0;
    }
    // To be reached 1 second after starting along the trajectory
    goal.trajectory.points[ind].time_from_start = ros::Duration(1.0);

    // Second trajectory point
    // Positions
    ind += 1;
    goal.trajectory.points[ind].positions.resize(2);
    goal.trajectory.points[ind].positions[0] = 1;
    goal.trajectory.points[ind].positions[1] = 2;
    // Velocities
    goal.trajectory.points[ind].velocities.resize(2);
    for (size_t j = 0; j < 2; ++j)
    {
      goal.trajectory.points[ind].velocities[j] = 0.0;
    }
    // To be reached 2 seconds after starting along the trajectory
    goal.trajectory.points[ind].time_from_start = ros::Duration(2.0);
  ac.sendGoal(goal);

  //wait for the action to return
  bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));

  if (finished_before_timeout)
  {
    actionlib::SimpleClientGoalState state = ac.getState();
    ROS_INFO("Action finished: %s",state.toString().c_str());
  }
  else
    ROS_INFO("Action did not finish before the time out.");

  //exit
  return 0;
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2017-03-24 18:15:17 -0500

This error comes from the client. You are calling 2 times set_succeeded on the server, so the client complains, as the second time the action is already in a terminal state. You should call the set_X methods only once.

edit flag offensive delete link more

Comments

ok, solved it.

dinesh gravatar image dinesh  ( 2017-03-24 19:23:01 -0500 )edit

there is only one set_x in sever, where is 2 set_x script?

nullspace gravatar image nullspace  ( 2023-01-19 01:44:33 -0500 )edit

Look again. set_succeeded is called in a for loop scope.

scottie gravatar image scottie  ( 2023-03-06 09:36:20 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2017-03-24 14:19:56 -0500

Seen: 6,801 times

Last updated: Mar 24 '17