void setSimpleState(SimpleGoalState next_state) { ROS.Debug("actionlib", "Transitioning SimpleState from [%s] to [%s]", goalState.toString(), next_state.toString()); goalState = next_state; }
/** * \brief Sends a goal to the ActionServer, and also registers callbacks * * If a previous goal is already active when this is called. We simply forget * about that goal and start tracking the new goal. No cancel requests are made. * \param done_cb Callback that gets called on transitions to Done * \param active_cb Callback that gets called on transitions to Active * \param feedback_cb Callback that gets called whenever feedback for this goal is received */ public void sendGoal(AGoal goal, SimpleDoneCallback done_cb = null, SimpleActiveCallback active_cb = null, SimpleFeedbackCallback feedback_cb = null) { // Reset the old GoalHandle, so that our callbacks won't get called anymore goalHandle.reset(); // Store all the callbacks doneCallback = done_cb; activeCallback = active_cb; feedbackCallback = feedback_cb; goalState = new SimpleGoalState(SimpleGoalState.StateEnum.PENDING); // Send the goal to the ActionServer goalHandle = actionClient.sendGoal(goal, handleTransition, handleFeedback); }
/** * \brief Simple constructor * * Constructs a SingleGoalActionClient and sets up the necessary ros topics for the ActionInterface * \param name The action name. Defines the namespace in which the action communicates * \param spin_thread If true, spins up a thread to service this action's subscriptions. If false, * then the user has to call ros.spin() themselves. Defaults to True */ public SimpleActionClient(string name, bool spin_thread = true) { goalState = new SimpleGoalState(SimpleGoalState.StateEnum.PENDING); initSimpleClient(nodeHandle, name, spin_thread); }