UP | HOME

ROS Basic Activity

Introduction

Create a node that accomplishes the following tasks:

  1. Publishes on turtle1/cmd_vel and causes the turtle to move forward in the x direction
  2. Subscribes to turtle1/pose and, when the turtle's x coordinate is greater than 7 resets the turtle's x position to 0
    • To reset the position use the turtle1/teleport_absolute service
  3. Offers a service to flip the turtle's direction (so it's x velocity is negative). The turtle should then reset when it's x coordinate is smaller than 3.
  4. Instead of using a threshold of 7, read a parameter called thresh from the parameter server

Examples

Publisher

#!/usr/bin/env python

import rospy
from geometry_msgs.msg import Twist, Vector3

if __name__ == '__main__':
      pub = rospy.Publisher("test", Twist, queue_size = 10)
      rospy.init_node('cartesian')
      rate = rospy.Rate(1)
      while not rospy.is_shutdown():
            rospy.loginfo("Next")
            pub.publish(Twist(Vector3(1,2,3),Vector3(4,5,6)))
            rate.sleep()

Subscriber

#!/usr/bin/env python
import rospy
from turtlesim.msg import Pose

def callback(data):
        rospy.loginfo(f"x: {data.x}, y: {data.y}")

if __name__ == "__main__":
        rospy.Subscriber("turtle1/pose", Pose, callback)
        rospy.ServiceProxy("turtle1/teleport_absolute", TeleportAbsolute)
        rospy.init_node("quadrant")
        rospy.spin()

Services

"""
SERVICES:
   jump_turtle (std_srvs/Empty): Cause the turtle to jump
"""
import rospy
from turtlesim.srv import TeleportRelative
from std_srvs.srv import Empty, EmptyResponse
import math

class Jump:
   """ Manage the services for the jump node """
   def __init__(self):
      self.__teleport_relative = rospy.ServiceProxy("turtle1/teleport_relative",
                                                    TeleportRelative)
      self.__service = rospy.Service("jump_turtle", Empty, self.jump_turtle_handler)

   def jump_turtle_handler(self, req):
      """ Cause the turtle to make a relative move 

          Args:
            req - this is empty for this service
      """
      self.__teleport_relative(0.5, math.pi/4)
      return EmptyResponse()


if __name__ == "__main__":
   rospy.init_node("jump")
   node = Jump()
   rospy.spin()

Reference

Tutorials

Author: Matthew Elwin