2.1 Create Service Server: how to update /scan values in while loop in /find_wall service

Hello world,

For the assignment 2.1 Create Service Server I’ve created a service /find_wall that is supposed to find the wall which is the closest by using /scan and searching for the lowest value in ranges[ ].

I’ve added a while loop in the custom_service_callback() that keeps checking of the value if self.laser_front has the smallest value thus is pointing to the closest wall.

The problem is that during the while-loop the self.laser_front is not updated by the the /scan subcriber.

The question: How can we keep on updating data from a subscriber inside a service?

see my code below:

import rclpy
# import the ROS2 python libraries
from rclpy.node import Node
from rclpy.qos import ReliabilityPolicy, QoSProfile
# import the Twist module from geometry_msgs interface
from geometry_msgs.msg import Twist
# import the LaserScan module from sensor_msgs interface
from sensor_msgs.msg import LaserScan
# import the custom service interface from wall_finder_int package
from wall_finder_int.srv import FindWall

class Service(Node):

    def __init__(self):
        # Here you have the class constructor
        # call the class constructor
        super().__init__('wall_finder_node')
        # create the publisher object
        self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 10)
        # create the subscriber object
        self.subscriber = self.create_subscription(LaserScan, 'scan', self.laser_callback, QoSProfile(depth=10, reliability=ReliabilityPolicy.RELIABLE))
        # create the service object
        self.srv = self.create_service(FindWall, 'find_wall', self.custom_service_callback)
        # create a Twist message
        self.cmd = Twist()
        # declare laser variables
        self.laser_right = 0
        self.laser_front = 0
        self.laser_min = 0

    def laser_callback(self,msg):
        # Save the  laser scan info
        self.laser_right= msg.ranges[270] 
        self.laser_front= msg.ranges[360]         
        self.laser_min = min(msg.ranges)


    def custom_service_callback(self, request, response):
        # The callback function receives the self-class parameter, 
        # received along with two parameters called request and response
        # - receive the data by request
        # - return a result as a response

        while (self.laser_front != self.laser_min):
            self.cmd.angular.z = 0.1
            self.publisher_.publish(self.cmd)
            # print a message
            self.get_logger().info('STATUS: Finding wall')
            self.get_logger().info('laser_front: "%s"' % str(self.laser_front))

        self.cmd.angular.z = 0.0
        self.cmd.linear.x = 0.0        
        self.publisher_.publish(self.cmd)
        # print a message
        self.get_logger().info('STATUS: Found wall')
        self.get_logger().info('laser_front: "%s"' % str(self.laser_front))

        response.wallfound = True
               
        # return the response parameter
        return response    
            
def main(args=None):
    # initialize the ROS communication
    rclpy.init(args=args)
    # declare the node constructor
    service = Service()       
    # pause the program execution, waits for a request to kill the node (ctrl+c)
    rclpy.spin(service)
    # Explicity destroy the node
    service.destroy_node()
    # shutdown the ROS communication
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Hi @rlekkerkerker ,

Welcome to this Community!

Nice intro! :heart_eyes:

The quick solution to your problem is to implement MultiThreadedExecutor with ReentrantCallbackGroup for both the service callback and scan callback.

Reason: You want the scan callback to run in parallel when service callback executes.

When you don’t explicitly use MultiThreadedExecutor in your program, by default, the program uses SingleThreadedExecutor. In SingleThreaded, you can use many callbacks, but only if they are operating one after another, that is, sequential. Therefore, you can use MutuallyExclusiveCallbackGroup in your SingleThreadedExecutor programs, but you cannot execute more than one callback together.
Thus, you need MultiThreaded with ReentrantCallbacks - to run your scan and service callback in parallel.

I hope this helped you. Let me know if anything is unclear.

Regards,
Girish

Hi Girish,

Thank you for your insights, they are really helpful to me as I’m still learning ROS2.
Good to know about the existence of MultiThreadedExecutor for my future projects.

I do not understand how to solve the 2.1 Create Service Server-assignment without MultiThreadedExecutor, because this has not been taught yet in the ROS2 Basics in 5 Days Humble (Python) course?

Best, Richard

Hi @rlekkerkerker ,

Ah, ok. You referred to the course assignment. I thought you were referring to the rosject.

Anyways, to get the service server working without using MultiThreadedExecutor,
you must use the rclpy.spin_once(self) inside your service callback if you have any loops - while or for.
This way, if you have a scan callback already defined, your service callback will still work.

Let me know if this fixed your problem.

Regards,
Girish

Hi @girishkumar.kannan,

Yes I’m trying to accomplish the Rosject assignment 2.1 where we need to setup a service that can find a wall and make the Turtlebot approach it and rotate so that the right side of the robot faces the wall.

I’ve added the ‘rclpy.spin_once(self)’ to the end of the while loop, but now the problem is that it get’s stuck in the while loop. The while loop is only run once after adding ‘rclpy.spin_once(self)’.

See the new code below.

ps: how do you mark-up this little pieces of code in your forum posts like MultiThreadedExecutor?

import rclpy
# import the ROS2 python libraries
from rclpy.node import Node
from rclpy.qos import ReliabilityPolicy, QoSProfile
# import the Twist module from geometry_msgs interface
from geometry_msgs.msg import Twist
# import the LaserScan module from sensor_msgs interface
from sensor_msgs.msg import LaserScan
# import the custom service interface from wall_finder_int package
from wall_finder_int.srv import FindWall

class Service(Node):

    def __init__(self):
        # Here you have the class constructor
        # call the class constructor
        super().__init__('wall_finder_node')
        # create the publisher object
        self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 10)
        # create the subscriber object
        self.subscriber = self.create_subscription(LaserScan, 'scan', self.laser_callback, QoSProfile(depth=10, reliability=ReliabilityPolicy.RELIABLE))
        # create the service object
        self.srv = self.create_service(FindWall, 'find_wall', self.custom_service_callback)
        # create a Twist message
        self.cmd = Twist()
        # declare laser variables
        self.laser_right = 0
        self.laser_front = 0
        self.laser_min = 0

    def laser_callback(self,msg):
        # Save the  laser scan info
        self.laser_right= msg.ranges[270] 
        self.laser_front= msg.ranges[360]         
        self.laser_min = min(msg.ranges)


    def custom_service_callback(self, request, response):
        # The callback function receives the self-class parameter, 
        # received along with two parameters called request and response
        # - receive the data by request
        # - return a result as a response

        while (self.laser_front != self.laser_min):
            
            self.cmd.angular.z = 0.1
            self.publisher_.publish(self.cmd)
            # print a message
            self.get_logger().info('STATUS: Finding wall')
            self.get_logger().info('laser_front: "%s"' % str(self.laser_front))
            rclpy.spin_once(self)

        self.cmd.angular.z = 0.0
        self.cmd.linear.x = 0.0        
        self.publisher_.publish(self.cmd)
        # print a message
        self.get_logger().info('STATUS: Found wall')
        self.get_logger().info('laser_front: "%s"' % str(self.laser_front))

        response.wallfound = True
               
        # return the response parameter
        return response    
            
def main(args=None):
    # initialize the ROS communication
    rclpy.init(args=args)
    # declare the node constructor
    service = Service()       
    # pause the program execution, waits for a request to kill the node (ctrl+c)
    rclpy.spin(service)
    # Explicity destroy the node
    service.destroy_node()
    # shutdown the ROS communication
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Hi @rlekkerkerker ,

Yes, this is a noted problem when you use rclpy.spin_once(self). You will also be able to call the service only once, a second call to the service while the server is online, the service will not actualize.
So, if it worked once for you, then it works. But the best way to do this is with MultiThreadedExecutor.

I am glad you asked about this!
You use two back-ticks for a few words like this : `print(“hello world”)`.
The result of the above will be print("hello world").
To post a code block, you enclose the whole code section between 3 back-ticks lines.
```<language_tag>
… code
… code
… code
```

The result for above would be (with c++ language tag):

// comment
/* this is my
 * block comment in 
 * three lines
 */

int a = 10;

int main() {
  cout << a << "\n";
  return 0;
}

The color of your code is determined by the <language_tag>:
You can use python for Python, cpp or c++ for C++, yaml for YAML, xml for XML, bash for normal text and console outputs.
Refer: Extended Syntax | Markdown Guide

Regards,
Girish

Hi @girishkumar.kannan,

Thanks again, the more I keep searching this forum, the more I believe that MultiThreadedExucutor is the way to go for this assignment. Still it’s weird that the course does not explain anything at all about MultiThreadedExucutor, because it seems essential knowledge to fix this service problem.

And thank you for the mark-up tips! For some reason I could not find this information in the Read Guidelines of thus forum, but maybe I did not look in the right place.

I wish you a pleasant day while I’m working on MultiThreadedExucutors :stuck_out_tongue:

Hi @rlekkerkerker ,

I see that you’re excited after knowing Markdown text formatting !
Also, by the way, it is MultiThreadedExecutors, not Exucutors. :grin:

Regards,
Girish

1 Like

Hi @bayodesegun,

Please see my post and replies here about what I think is a ‘gap’ between the course lessons and the linked assignments. Could you explain why we would need MultiThreadedExecutor techniques, but they are not taught in the course (up to this point)? Am I missing something?

Best, Richard

@rlekkerkerker
Thanks for calling it out. I might indeed be a gap, from what I see.

I have captured it for the course creators to review.

2 Likes