ROS Basics in 5 days (python) unit 7 service_quiz

this my service_server

#! /usr/bin/env python

import rospy
from services_quiz.srv import BB8CustomServiceMessage, BB8CustomServiceMessageResponse # you import the service message python classes 
from geometry_msgs.msg import Twist                                                                                        


def my_callback(request):
    #print("My_callback has been called")
    rospy.loginfo("move_bb8_in_square_custom has been called")
    
    for i in range(request.repetitions):
      move = Twist()
      rospy.sleep(1)
      
      for j in range(4):
            
            move.linear.x = request.side
            move.angular.z = 0.4
            pub.publish(move)
            rospy.loginfo("insede the loop")

    
    rospy.loginfo("outside the loop")

    move.linear.x = 0.0
    move.angular.z = 0.0
    rospy.loginfo("stoping BB8")
    rospy.loginfo("Finished service move_bb8_in_square_custom") 
    print("Request Data==> repetitons="+str(request.repetitions),"side"+ str(request.side))
    my_response = BB8CustomServiceMessageResponse()

    my_response.success = True
    
    return  my_response # the service Response class, in this case BBCustomServiceMessageResponse

rospy.init_node('service_server') 
my_service = rospy.Service('/move_bb8_in_square_custom', BB8CustomServiceMessage , my_callback) # create the Service called my_service with the defined callback
pub = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
# move = Twist()
# rate = rospy.Rate(1)
rospy.loginfo("Service /move_bb8_in_square_custom Ready")
# rospy.spin() # maintain the service open.
while not rospy.is_shutdown():
    # Wait for a service request
    request = rospy.wait_for_service('/move_bb8_in_square_custom', timeout=None)

    # If the service request is received, call the callback function
    if request is not None:
        response = my_callback(request)

    # If the service client exits cleanly, break out of the loop
    if rospy.is_shutdown():
        break

rospy.loginfo("Service /move_bb8_in_square_custom Shutdown")


this is service_client

#! /usr/bin/env python
import rospy
from services_quiz.srv import BB8CustomServiceMessage, BB8CustomServiceMessageRequest # you import the service message python classes 


# Initialise a ROS node with the name service_client
rospy.init_node('service_client')
# Wait for the service client to be running
rospy.wait_for_service('/move_bb8_in_square_custom')
# Create the connection to the service
service_client = rospy.ServiceProxy('/move_bb8_in_square_custom', BB8CustomServiceMessage)
# Create an object of type 
# Make two small squares

request_object = BB8CustomServiceMessageRequest()

request_object.repetitions = 2
request_object.side = 1.0

rospy.loginfo("Doing Service Call...")
result = service_client(request_object) # Send through the connection the path to the trajectory file to be executed
rospy.loginfo(str(result)) # Print the result given by the service called
rospy.loginfo("END of Service call...")

# Wait for a second
rospy.sleep(1)

# Make a big square
request_object.repetitions = 1
request_object.side = 1.5

rospy.loginfo("Doing Service Call...")
result = service_client(request_object) # Send through the connection the path to the trajectory file to be executed
rospy.loginfo(str(result)) # Print the result given by the service called
rospy.loginfo("END of Service call...")

Problems:

  • BB8 made continuous squares and not stoping(probably loop trouble, i dont understand what exactly)
  • BB8 not repeat small square 2 time(probably also related to loop or service call)
  • How to make it stop after each side to make real square, because mine looks like oval

Thanks

Hi @artem.nkfv ,

There are a few things that are wrong with your program.

Let me do some corrections on the service_client:

  1. You can make the service call as one function with repetitions and side as the arguments for the function:
    define call_move_bb8_in_square(repetitions, side):
        # create a service request object
        # set request.repetitions = repetitions
        # set request.side = side
        # call the service
        # wait for service to complete
        # return the service response
        return response
    
  2. You can then call the above function twice:
    call_move_bb8_in_square(repetitions=2, side=1.0)
    time.sleep(5.0) # wait for a few seconds (only if needed)
    call_move_bb8_in_square(repetitions=1, side=1.5)
    

Now, let us discuss your service_server:

  1. Your logic is wrong in the my_callback().
move.linear.x = request.side # this line will set linear velocity of robot
move.angular.z = 0.4 # this line will set angular velocity of robot
pub.publish(move)
rospy.loginfo("insede the loop")

So with the above line, you are not telling the robot to move for a certain distance, but you are actually setting the speed of the robot.
You need to travel a distance of 1.0 meters. So you choose a constant velocity and move till the distance is covered.
We know from mathematics that distance = speed x time.
So if you choose a constant speed, say 0.1 m/s and move the robot for 10 seconds, then you have covered 1 meter.
The above code that you have written will only make the robot go in circles, if not oval.

Also, how would you draw a square? (let us assume we take the same 90 degree turn always!)
draw a straight line, take a 90 degree at the end,
draw a straight line, take a 90 degree at the end,
draw a straight line, take a 90 degree at the end,
draw a straight line, take a 90 degree at the end.

So your logic would eventually become:

for i in range(4):
    # go straight (linear.x = some value, angular.z = 0.0)
    # sleep for calculated linear time
    # stop (linear.x = 0.0, angular.z = 0.0)
    # turn 90 degrees (linear.x = 0.0, angular.z = some value)
    # sleep for calculated angular time
    # stop (linear.x = 0.0, angular.z = 0.0)
  1. This line is unnecessary!

The callback is already attached to the service when you declare the service. Why do you want to call the callback again manually? Do not do this. Refer to the study material if you did not understand how to use callbacks.

  1. This line is also unnecessary!

you already have a while loop with the exact condition. Why do you repeat yourself? This is not a fail safe. This is unwanted extra coding. You already have the following line:

So if rospy is shutdown, the loop will automatically break out.

  1. This line will probably not be printed, since rospy will be shutdown right before this line.

If you fix all these logic issues in your code, your program will work fine.

Regards,
Girish

hi, i’m using while loop at end of service_server, because this is the only solution i find, instead of using rospy.spin().
checking the rest of your explanation.
Thank you

okay i redone service_server

#! /usr/bin/env python

import rospy
from services_quiz.srv import BB8CustomServiceMessage, BB8CustomServiceMessageResponse # you import the service message python classes 
from geometry_msgs.msg import Twist                                                                                        


def my_callback(request):
    #print("My_callback has been called")
    rospy.loginfo("move_bb8_in_square_custom has been called")
    
    for i in range(request.repetitions):
      move = Twist()
      
      for j in range(4):
        if request.side == 1.0:
            
          move.linear.x = 0.2
          move.angular.z = 0.0
          pub.publish(move)
          rospy.sleep(7)

          move.linear.x = 0.0
          move.angular.z = 0.2
          pub.publish(move)
          rospy.sleep(4)


        else:
          move.linear.x = 0.3
          move.angular.z = 0.0
          pub.publish(move)
          rospy.sleep(7)

          move.linear.x = 0.0
          move.angular.z = 0.2
          pub.publish(move)
          rospy.sleep(4)
            
            
            
        rospy.loginfo("insede the loop")

    
    rospy.loginfo("outside the loop")

    
    
    rospy.loginfo("stoping BB8")
    rospy.loginfo("Finished service move_bb8_in_square_custom") 
    print("Request Data==> repetitons="+str(request.repetitions),"side"+ str(request.side))
    my_response = BB8CustomServiceMessageResponse()

    my_response.success = True
    
    return  my_response # the service Response class, in this case BBCustomServiceMessageResponse

rospy.init_node('service_server') 
my_service = rospy.Service('/move_bb8_in_square_custom', BB8CustomServiceMessage , my_callback) # create the Service called my_service with the defined callback
pub = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
# move = Twist()
# rate = rospy.Rate(1)
rospy.loginfo("Service /move_bb8_in_square_custom Ready")
# rospy.spin() # maintain the service open.
while not rospy.is_shutdown():
    # Wait for a service request
    request = rospy.wait_for_service('/move_bb8_in_square_custom', timeout=None)

    # If the service request is received, call the callback function
    if request is not None:
        response = my_callback(request)
    
    # If the service client exits cleanly, break out of the loop
    if rospy.is_shutdown():
        break

rospy.loginfo("Service /move_bb8_in_square_custom Shutdown")

Please can some body explain why Robot skip linear movement, and start angular first.
And if i’m using rospy.sleep() function wrong?

Okay
This is working code that make robot move in squares, but it still skip first linear movement ,so i change the order of linear and angular movement in the loop.I know it sound silly but its drive me craze already.

#! /usr/bin/env python

import rospy
from services_quiz.srv import BB8CustomServiceMessage, BB8CustomServiceMessageResponse # you import the service message python classes 
from geometry_msgs.msg import Twist                                                                                        


def my_callback(request):
    #print("My_callback has been called")
    rospy.loginfo("move_bb8_in_square_custom has been called")
    
    for i in range(request.repetitions):
      move = Twist()
      
      for j in range(4):
        if request.side == 1.0:
            

          move.linear.x = 0.0
          move.angular.z = 0.3
          pub.publish(move)
          rospy.sleep(5)

          move.linear.x = 0.2
          move.angular.z = 0.0
          pub.publish(move)
          rospy.sleep(5)

        else:

          move.linear.x = 0.0
          move.angular.z = 0.3
          pub.publish(move)
          rospy.sleep(5)
            
          move.linear.x = 0.3
          move.angular.z = 0.0
          pub.publish(move)
          rospy.sleep(5)
            
            
        rospy.loginfo("insede the loop")

    move.linear.x = 0.0
    move.angular.z = 0.0
    pub.publish(move)
    rospy.sleep(5)
    rospy.loginfo("outside the loop")

    
    
    rospy.loginfo("stoping BB8")
    rospy.loginfo("Finished service move_bb8_in_square_custom") 
    print("Request Data==> repetitons="+str(request.repetitions),"side"+ str(request.side))
    my_response = BB8CustomServiceMessageResponse()

    my_response.success = True
    
    return  my_response # the service Response class, in this case BBCustomServiceMessageResponse

rospy.init_node('service_server') 
my_service = rospy.Service('/move_bb8_in_square_custom', BB8CustomServiceMessage , my_callback) # create the Service called my_service with the defined callback
pub = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
# move = Twist()
# rate = rospy.Rate(1)
rospy.loginfo("Service /move_bb8_in_square_custom Ready")
# rospy.spin() # maintain the service open.
while not rospy.is_shutdown():
    # Wait for a service request
    request = rospy.wait_for_service('/move_bb8_in_square_custom', timeout=None)

    # If the service request is received, call the callback function
    if request is not None:
        response = my_callback(request)
    
    # If the service client exits cleanly, break out of the loop
    if rospy.is_shutdown():
        break

rospy.loginfo("Service /move_bb8_in_square_custom Shutdown")

So is it my Loop wrong or it is something with the platform itself?
Yes it’s past the test)))

It’s your logic. It’s executing the angular part first.

This topic was automatically closed 5 days after the last reply. New replies are no longer allowed.