Robotics StackExchange | Archived questions

How to publish Voice Output (PocketSpinx) to move-base goal

Hi Guys,

I am correctly using PocketSpinx and i have an output of "Position Three" and "Position Four".. I am currently trying to hardcode coordinates on my map to the positions i stated above.

I came up with this code, can anyone put me through on what i did wrong or how to go about it?

The voice output is published on "kws_data/output"

Please see code below: Thanks

UPDATE

Fixed the code, it works but doesnt give me the coordinates of "position Three" when i give a voice input.. it shows position and orientation as all "0"s instead of the coordinates predefined in the code

UPDATE Edited the code, and hardcoded it directly instead of using a dictionary for the coordinates,, The topic "move_base/simple" prints the right coordinates now..

About to test it on the robot now.

Updated Code below:

Voicetomove_base.py

  #!/usr/bin/env python

#!/usr/bin/env python

import rospy
from std_msgs.msg import String
from geometry_msgs.msg import PoseStamped
from actionlib_msgs.msg import GoalStatus
from move_base_msgs.msg import MoveBaseAction
from geometry_msgs.msg import Twist

class ASRControl(object):

    def __init__(self):

    # Intializing message type
    self.goal = PoseStamped()
    self.msg = Twist()

    rospy.init_node("asr_control")
    rospy.on_shutdown(self.shutdown)

    #Initializing publisher with buffer size of 10 messages
    self.pub_pos = rospy.Publisher("move_base_simple/goal", PoseStamped, queue_size=10)
    self.pub_ = rospy.Publisher("cmd_vel", Twist, queue_size=10)

    #subscribe to kws output
    rospy.Subscriber('kws_data', String, self.parse_asr_result, queue_size=10)
    rospy.spin()

    def parse_asr_result(self, detected_words):
    """Function to perform action on detected word"""
        if detected_words.data.find("position three") > -1:
        self.goal.header.frame_id = "map"
        self.goal.header.stamp = rospy.Time.now()
        self.goal.pose.position.z = 2.780
        self.goal.pose.position.x = 18.295
        self.goal.pose.position.y = 2.915
        self.goal.pose.orientation.w = 1.0
    elif detected_words.data.find("position four") > -1:
        self.goal.header.frame_id = "map"
        self.goal.header.stamp = rospy.Time.now()
        self.goal.pose.position.z = -3.058
        self.goal.pose.position.x = 25.755
        self.goal.pose.position.y = 3.235
        self.goal.pose.orientation.w = 1.0
    elif detected_words.data.find("stop") > -1:
        self.msg = Twist()

    # Publish required message
    self.pub_pos.publish(self.goal)
    self.pub_.publish(self.msg)


    def shutdown(self):
    """
        command executed after Ctrl+C is pressed
        """ 
    rospy.loginfo("Stop")
    self.pub_.publish(Twist())
    rospy.sleep(1)

if __name__ == '__main__':
    ASRControl()

Asked by femitof on 2020-05-03 00:52:10 UTC

Comments

Need help guys please.. Been on this all day

Asked by femitof on 2020-05-03 04:20:21 UTC

see you got it working - nice

Asked by billy on 2020-05-03 17:44:07 UTC

@billy Thanks I have one question totally unrelated to this topic,

My Local cost map always almost doesnt always match the map, hence path planning fails and it fails to reach its destination.

A good example is I start navigation trying to go from point A to B and then B to C. I successfully navigate to Point B from A, but when i try navigating to point C from B, the local cost map is slightly different from the static map and thus might drive into walls or something.

Please how do i fix this? I am currently using the RpLIdar A2M8 Laser scanner.. Look forward to your response as always..

I will probably delete this questionn of the comment once you answer ,thanks..

Asked by femitof on 2020-05-07 00:25:35 UTC

"My Local cost map always almost doesnt always match the map, hence path planning fails and it fails to reach its destination."

So you mean the localization fails and the cost map laid out by the laser scanner doesn't line up with the static map? Or do you mean the cost map laid out by the laser scanner is a different shape than the static map? If the later, which one is correct IRL? This should be a separate question.

Asked by billy on 2020-05-09 15:06:36 UTC

The localization doesnt fail cost map laid out is the same shape with the static map, but has a slightly different angle/orientation than the static map.

I asked the question properly here.. Please see the link to the question...

https://answers.ros.org/question/351678/navigation-issues-local-costmap-doesnt-match-the-static-map-after-inital-navigation/

You can answer on there

Asked by femitof on 2020-05-09 16:35:30 UTC

Answers

Here is what I see. You put a spin at the end of your constructor. Spin never returns. So when you get a destination on the topic, your callback will run and setup the variables. Then nothing. You'll be stuck at the end of your constructor.

Your callback should send the goal so move most your go_to code into the callback.

In general the code needs a bit more thought on flow control. But you can work through that once it is sending the commands.

When asking questions, tell us what is or isn't happening. Is the subscriber parse_asr_result callback being called? Is the simple goal being published? Do you get an error?

I don't see any debugging print or log statements that indicate you're probing to learn about how the program is flowing or not flowing. All of that will help you understand, and will help us help you get it running.

I don't understand why you have that rospy.signal_shutdown("Restarting nav node") bit in there.

Asked by billy on 2020-05-03 14:33:29 UTC

Comments

@billy Hi thanks alot.. Took all you said into consideration, worked on the code.. I updated the code above,please look at it It produces an output now with x,y,z pose and orientation all zeros

Without the rospy.spin(), the code runs and stops almost immediately. with the Spin, i can get my desired coordinates on the topic..

Thanks alot for all you have done.. i really do appreciate you @billy

Will keep you updated

Asked by femitof on 2020-05-03 16:44:33 UTC