Action Feedback is not publishing at 1 Hz

Hi,

I am trying to get my feedback to publish once every second but when I am using:

rostopic echo /action_custom_msg_as/feedback

I am only seeing a response when I pass the action a goal. I am expecting the code to continue publishing my goal as feedback. What am I missing?

#! /usr/bin/env python
import rospy
import actionlib
from actionlib.msg import TestAction, TestActionResult, TestActionFeedback
from geometry_msgs.msg import Twist
from std_msgs.msg import Empty
from actions_quiz.msg import CustomActionMsgAction, CustomActionMsgResult, CustomActionMsgFeedback
import time

class Move_Drone_Class(object):

  # create messages that are used to publish feedback/result
  _feedback = CustomActionMsgFeedback()
  _result   = CustomActionMsgResult()

  def __init__(self):
    # creates the action server
    self._as = actionlib.SimpleActionServer("/action_custom_msg_as", CustomActionMsgAction, self.goal_callback, False)
    self._as.start()
    self.rate = rospy.Rate(1)

  def goal_callback(self, goal):
    r = rospy.Rate(1)
    success = True

    if self._as.is_preempt_requested():
        rospy.loginfo('The goal has been cancelled/preempted')
        # the following line, sets the client in preempted state (goal cancelled)
        self._as.set_preempted()
        success = False

    # define the publishers we'll be using
    self.pub_takeoff = rospy.Publisher('/drone/takeoff', Empty, queue_size=1)
    self.takeoff_msg = Empty()
    self.pub_land = rospy.Publisher('/drone/land', Empty, queue_size=1)
    self.land_msg = Empty()

    command = goal.goal
    rospy.loginfo(command)

   if command == "TAKEOFF":
        rospy.loginfo('Drone is taking off')
        self.pub_takeoff.publish(Empty())
    elif command == "LAND":
        rospy.loginfo('Drone is landing')
        self.pub_land.publish(Empty())

    self._feedback.feedback = command
    self._as.publish_feedback(self._feedback)
    rospy.loginfo("we are publshing at 1 Hz")
    # the sequence is computed at 1 Hz frequency
    self.rate.sleep()

    if success:
        #self._result.result = None
        self._as.set_succeeded(self._result)

if __name__ == '__main__':
  rospy.init_node('drone_command_via_string')
  Move_Drone_Class()
  rospy.spin()

Hi @nrjbs87, the Rate object is useless outside a loop:

For things to work as expected,

  • you need to publish the feedback in a loop.
  • self.rate.sleep() will need to be in the loop as well.

Something like:

# be careful here: don't use a condition that will never be false
# otherwise your action will never finish!
while some_condition_is_true:  
    self._feedback.feedback = command
    self._as.publish_feedback(self._feedback)
    self.rate.sleep()

That said, I don’t think publishing the feedback every second will work out of the box though, because the whole action will be completed in probably less than a second. Of course, you can intentionally make the action last longer just to have some fun!

Hmm OK super helpful. Here is my concern: for the actions_quiz one of the conditions is

  • As a feedback, it publishes once a second what action is taking place (taking off or landing).

I am wanting to make sure this condition holds true even if the action is only a 1 second interval. To your point about having it in a loop, I tried using the get_state() method demonstrated in the last section, but turns out that’s only for clients :stuck_out_tongue:

What kind of loop can we use with an _as to get a similar effect?

1 Like

Also in that same vein for the requirement of:

  • As a feedback, it publishes once a second what action is taking place (taking off or landing).

Is the grading program looking for a specific string for feedback? such as “TAKINGOFF” or “LANDING”?

I understand your concern. But don’t worry too much about the feedback condition; just ensure the TAKEOFF and LAND commands work and you send feedback at least once.

Sending the goal as feedback, as you have already done, should be fine.

Should you run into any problems with the quiz evaluator because of following this advice, I’ve got your back :wink: !

Thanks so much for the help! So the quiz did have an error…but for a different reason that is out of my control.

I have experienced several instances where the simulation will not take my takeoff or land command until I have reset the simulation. This unfortunately happened during the scoring and took off points because of this. When tested multiple times before, the code worked. Code is below. Could you please advise?

#! /usr/bin/env python
import rospy
import actionlib
from actionlib.msg import TestAction, TestActionResult, TestActionFeedback
from geometry_msgs.msg import Twist
from std_msgs.msg import Empty
from actions_quiz.msg import CustomActionMsgAction, CustomActionMsgResult, CustomActionMsgFeedback
import time

class Drone_Custom_Action_Class(object):

  # create messages that are used to publish feedback/result
  _feedback = CustomActionMsgFeedback()
  _result   = CustomActionMsgResult()

  def __init__(self):
    # creates the action server
    self._as = actionlib.SimpleActionServer("/action_custom_msg_as", CustomActionMsgAction, self.goal_callback, False)
    self._as.start()
    self.rate = rospy.Rate(1)

  def goal_callback(self, goal):
    r = rospy.Rate(1)
    success = True

    if self._as.is_preempt_requested():
        rospy.loginfo('The goal has been cancelled/preempted')
        # the following line, sets the client in preempted state (goal cancelled)
        self._as.set_preempted()
        success = False

    # define the publishers we'll be using
    self.pub_takeoff = rospy.Publisher('/drone/takeoff', Empty, queue_size=1)
    self.takeoff_msg = Empty()
    self.pub_land = rospy.Publisher('/drone/land', Empty, queue_size=1)
    self.land_msg = Empty()

    command = goal.goal
    rospy.loginfo(command)

    if command == "TAKEOFF":

        rospy.loginfo('Drone is taking off')
        self.pub_takeoff.publish(Empty())
        self._feedback.feedback = command
        self._as.publish_feedback(self._feedback)
        self.rate.sleep()

    elif command == "LAND":

        rospy.loginfo('Drone is landing')
        self.pub_land.publish(Empty())
        self._feedback.feedback = command
        self._as.publish_feedback(self._feedback)
        self.rate.sleep()

    if success:
        self._as.set_succeeded(self._result)

if __name__ == '__main__':
  rospy.init_node('drone_command_via_string')
  Drone_Custom_Action_Class()
  rospy.spin()

Hi @nrjbs87,

Thanks for the feedback.

I’ve just reset your quiz score and you can try again!

I think the problem of the drone not “obeying” the commands sometimes might be happening because the associated publishers might not be ready to receive commands (no connection to the publisher) when the commands were issued.

Before submitting the quiz again, please check the following post to see how waiting for a publisher connection is done. (PS: the post is not specifically about this, but it contains the trick to do this. I will write a separate post for this later).

Kindly let us know how it goes before submitting the quiz again.

Further hints:

  • A good place to publish your 1Hz feedback is within the while loop that waits for a connection to a publisher.
  • Publish your feedback before executing the TAKEOFF/LAND command…publish it both within and outside the loop (while waiting for a connection and after a connection is made, so that you will at least publish once if the while loop is skipped, i.e. a connection was already available).
  • It seems you are not using self.takeoff_msg and self.land_msg anywhere; consider removing them.
1 Like

You my friend…are a great teacher :D.

Thank you, quiz resubmitted.
Thanks!

2 Likes