diff --git a/example_1.md b/example_1.md index 75e0f3b..9703432 100644 --- a/example_1.md +++ b/example_1.md @@ -81,7 +81,7 @@ Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at import rospy from geometry_msgs.msg import Twist ``` -You need to import rospy if you are writing a ROS Node. The geometry_msgs.msg import is so that we can send velocity commands to the robot. +You need to import rospy if you are writing a ROS Node. The `geometry_msgs.msg` import is so that we can send velocity commands to the robot. ```python @@ -89,7 +89,7 @@ class Move: def __init__(self): self.pub = rospy.Publisher('/stretch/cmd_vel', Twist, queue_size=1)#/stretch_diff_drive_controller/cmd_vel for gazebo ``` -This section of code defines the talker's interface to the rest of ROS. pub = rospy.Publisher("/stretch/cmd_vel", Twist, queue_size=1) declares that your node is publishing to the /stretch/cmd_vel topic using the message type Twist. The queue_size argument limits the amount of queued messages if any subscriber is not receiving them fast enough. +This section of code defines the talker's interface to the rest of ROS. `pub = rospy.Publisher("/stretch/cmd_vel", Twist, queue_size=1)` declares that your node is publishing to the /stretch/cmd_vel topic using the message type Twist. The queue_size argument limits the amount of queued messages if any subscriber is not receiving them fast enough. ```Python @@ -125,16 +125,16 @@ rospy.init_node('move') base_motion = Move() rate = rospy.Rate(10) ``` -The next line, rospy.init_node(NAME, ...), is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". +The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". -The `rospy.Rate()` function creates a Rate object rate. With the help of its method sleep(), it offers a convenient way for looping at the desired rate. With its argument of 10, we should expect to go through the loop 10 times per second (as long as our processing time does not exceed 1/10th of a second!) +The `rospy.Rate()` function creates a Rate object rate. With the help of its method `sleep()`, it offers a convenient way for looping at the desired rate. With its argument of 10, we should expect to go through the loop 10 times per second (as long as our processing time does not exceed 1/10th of a second!) ```python while not rospy.is_shutdown(): base_motion.move_forward() rate.sleep() ``` -This loop is a fairly standard rospy construct: checking the rospy.is_shutdown() flag and then doing work. You have to check is_shutdown() to check if your program should exit (e.g. if there is a Ctrl-C or otherwise). The loop calls rate.sleep(), which sleeps just long enough to maintain the desired rate through the loop. +This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown()` flag and then doing work. You have to check is_shutdown() to check if your program should exit (e.g. if there is a Ctrl-C or otherwise). The loop calls `rate.sleep()`, which sleeps just long enough to maintain the desired rate through the loop. ## Move Stretch in Simulation @@ -148,7 +148,7 @@ Using your preferred text editor, modify the topic name of the published *Twist* self.pub = rospy.Publisher('/stretch_diff_drive_controller/cmd_vel', Twist, queue_size=1) ``` -After saving the edited node, bringup [Stretch in the empty world simulation](gazebo_basics.md). To drive the robot with the node, type the follwing in a new terminal +After saving the edited node, bringup [Stretch in the empty world simulation](gazebo_basics.md). To drive the robot with the node, type the following in a new terminal ```bash cd catkin_ws/src/stretch_tutorials/src/ diff --git a/example_2.md b/example_2.md index acbb377..7f13bf2 100644 --- a/example_2.md +++ b/example_2.md @@ -127,7 +127,7 @@ from numpy import linspace, inf from math import sin from sensor_msgs.msg import LaserScan ``` -You need to import rospy if you are writing a ROS Node. There are functions from numpy and math that are required within this code, thus why linspace, inf, and sin are imported. The sensor_msgs.msg import is so that we can subscribe and publish LaserScan messages. +You need to import rospy if you are writing a ROS Node. There are functions from numpy and math that are required within this code, thus why linspace, inf, and sin are imported. The `sensor_msgs.msg` import is so that we can subscribe and publish LaserScan messages. ```python self.width = 1 @@ -138,7 +138,7 @@ We're going to assume that the robot is pointing up the x-axis, so that any poin ```python self.sub = rospy.Subscriber('/scan', LaserScan, self.callback) ``` -Set up a subscriber. We're going to subscribe to the topic "scan", looking for LaserScan messages. When a message comes in, ROS is going to pass it to the function "callback" automatically. +Set up a subscriber. We're going to subscribe to the topic *scan*, looking for LaserScan messages. When a message comes in, ROS is going to pass it to the function "callback" automatically. ```python self.pub = rospy.Publisher('filtered_scan', LaserScan, queue_size=10) @@ -171,7 +171,7 @@ Substitute in the new ranges in the original message, and republish it. rospy.init_node('scan_filter') ScanFilter() ``` -The next line, rospy.init_node(NAME, ...), is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". +The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". Instantiate the class with `ScanFilter()` diff --git a/example_3.md b/example_3.md index 9f99247..da3778b 100644 --- a/example_3.md +++ b/example_3.md @@ -103,19 +103,19 @@ from math import sin from geometry_msgs.msg import Twist from sensor_msgs.msg import LaserScan ``` -You need to import rospy if you are writing a ROS Node. There are functions from numpy and math that are required within this code, thus linspace, inf, tanh, and sin are imported. The sensor_msgs.msg import is so that we can subscribe to LaserScan messages. The geometry_msgs.msg import is so that we can send velocity commands to the robot. +You need to import rospy if you are writing a ROS Node. There are functions from numpy and math that are required within this code, thus linspace, inf, tanh, and sin are imported. The `sensor_msgs.msg` import is so that we can subscribe to LaserScan messages. The `geometry_msgs.msg` import is so that we can send velocity commands to the robot. ```python self.pub = rospy.Publisher('/stretch/cmd_vel', Twist, queue_size=1)#/stretch_diff_drive_controller/cmd_vel for gazebo ``` -This section of code defines the talker's interface to the rest of ROS. pub = rospy.Publisher("/stretch/cmd_vel", Twist, queue_size=1) declares that your node is publishing to the /stretch/cmd_vel topic using the message type Twist. +This section of code defines the talker's interface to the rest of ROS. `pub = rospy.Publisher("/stretch/cmd_vel", Twist, queue_size=1)` declares that your node is publishing to the */stretch/cmd_vel* topic using the message type `Twist`. ```python self.sub = rospy.Subscriber('/scan', LaserScan, self.set_speed) ``` -Set up a subscriber. We're going to subscribe to the topic "scan", looking for LaserScan messages. When a message comes in, ROS is going to pass it to the function "set_speed" automatically. +Set up a subscriber. We're going to subscribe to the topic "*scan*", looking for `LaserScan` messages. When a message comes in, ROS is going to pass it to the function "set_speed" automatically. ```python @@ -135,7 +135,7 @@ self.twist.angular.x = 0.0 self.twist.angular.y = 0.0 self.twist.angular.z = 0.0 ``` -Allocate a Twist to use, and set everything to zero. We're going to do this when the class is initiating. Redefining this within the callback function, `set_speed()` can be more computationally taxing. +Allocate a `Twist` to use, and set everything to zero. We're going to do this when the class is initiating. Redefining this within the callback function, `set_speed()` can be more computationally taxing. ```python angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges)) @@ -160,14 +160,14 @@ Set the speed according to a tanh function. This method gives a nice smooth mapp ```python self.pub.publish(self.twist) ``` -Publish the Twist message. +Publish the `Twist` message. ```python rospy.init_node('avoider') Avoider() rospy.spin() ``` -The next line, rospy.init_node(NAME, ...), is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". +The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". Instantiate class with `Avioder()` diff --git a/example_4.md b/example_4.md index e728013..891615f 100644 --- a/example_4.md +++ b/example_4.md @@ -93,12 +93,12 @@ Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at import rospy from visualization_msgs.msg import Marker ``` -You need to import rospy if you are writing a ROS Node. Import the `Marker` type from the visualization_msgs.msg package. This import is required to publish a Marker, which will be visualized in RViz. +You need to import rospy if you are writing a ROS Node. Import the `Marker` type from the visualization_msgs.msg package. This import is required to publish a `Marker`, which will be visualized in RViz. ```python self.pub = rospy.Publisher('balloon', Marker, queue_size=10) ``` -This section of code defines the talker's interface to the rest of ROS. pub = rospy.Publisher("balloon", Twist, queue_size=1) declares that your node is publishing to the */ballon* topic using the message type *Twist*. +This section of code defines the talker's interface to the rest of ROS. `pub = rospy.Publisher("balloon", Twist, queue_size=1)` declares that your node is publishing to the */ballon* topic using the message type `Twist`. ```python @@ -160,7 +160,7 @@ balloon = Balloon() rate = rospy.Rate(10) ``` -The next line, rospy.init_node(NAME, ...), is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". +The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". Instantiate class with `Balloon()` @@ -173,7 +173,7 @@ while not rospy.is_shutdown(): rate.sleep() ``` -This loop is a fairly standard rospy construct: checking the rospy.is_shutdown() flag and then doing work. You have to check is_shutdown() to check if your program should exit (e.g. if there is a Ctrl-C or otherwise). The loop calls rate.sleep(), which sleeps just long enough to maintain the desired rate through the loop. +This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown()` flag and then doing work. You have to check `is_shutdown()` to check if your program should exit (e.g. if there is a Ctrl-C or otherwise). The loop calls `rate.sleep()`, which sleeps just long enough to maintain the desired rate through the loop. **Previous Example:** [Example 3](example_3.md) **Next Example:** [Example 5](example_5.md) diff --git a/example_5.md b/example_5.md index 36ce422..459265c 100644 --- a/example_5.md +++ b/example_5.md @@ -97,12 +97,12 @@ import rospy import sys from sensor_msgs.msg import JointState ``` -You need to import rospy if you are writing a ROS Node. Import sensor_msgs.msg so that we can subscribe to JointState messages. +You need to import rospy if you are writing a ROS Node. Import `sensor_msgs.msg` so that we can subscribe to `JointState` messages. ```python self.sub = rospy.Subscriber('joint_states', JointState, self.callback) ``` -Set up a subscriber. We're going to subscribe to the topic "joint_states", looking for JointState messages. When a message comes in, ROS is going to pass it to the function "callback" automatically +Set up a subscriber. We're going to subscribe to the topic "*joint_states*", looking for `JointState` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically ```python def callback(self, msg): @@ -115,7 +115,7 @@ def print_states(self, joints): joint_positions = [] ``` -This is the *print_states()* function which takes in a list of joints of interest as its argument. the is also an empty list set as *joint_positions* and this is where the positions of the requested joints will be appended. +This is the `print_states()` function which takes in a list of joints of interest as its argument. the is also an empty list set as *joint_positions* and this is where the positions of the requested joints will be appended. ```python for joint in joints: @@ -123,20 +123,21 @@ for joint in joints: joint_positions.append(self.joint_states.position[index]) print(joint_positions) ``` -In this section of the code, a forloop is used to parse the names of the requested joints from the *self.joint_states* list. The index() function returns the index a of the name of the requested joint and appends the respective position to our *joint_positions* list. +In this section of the code, a forloop is used to parse the names of the requested joints from the *self.joint_states* list. The `index()` function returns the index a of the name of the requested joint and appends the respective position to our *joint_positions* list. ```python rospy.signal_shutdown("done") sys.exit(0) ``` -The first line of code initias a clean shutodwn of ROS. The second line of code exits the Python interpreter. + +The first line of code initiates a clean shutodwn of ROS. The second line of code exits the Python interpreter. ```python rospy.init_node('joint_state_printer', anonymous=True) JSP = JointStatePublisher() rospy.sleep(.1) ``` -The next line, rospy.init_node(NAME, ...), is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". +The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". Declare object, *JSP*, from the `JointStatePublisher` class. diff --git a/example_6.md b/example_6.md index 014bcef..715c752 100644 --- a/example_6.md +++ b/example_6.md @@ -149,7 +149,7 @@ if __name__ == '__main__': ### The Code Explained -This code is similar to that of the [multipoint_command](https://github.com/hello-robot/stretch_tutorials/blob/main/src/multipoint_command.py) and [joint_state_printer](https://github.com/hello-robot/stretch_tutorials/blob/main/src/joint_state_printer.py) node. Therefore, this example will highlight sections that are different from that tutorial. Now let's break the code down. +This code is similar to that of the [multipoint_command](https://github.com/hello-robot/stretch_tutorials/blob/main/src/multipoint_command.py) and [joint_state_printer](https://github.com/hello-robot/stretch_tutorials/blob/main/src/joint_state_printer.py) node. Therefore, this example will highlight sections that are different from those tutorials. Now let's break the code down. ```python #!/usr/bin/env python @@ -193,7 +193,7 @@ self.sub = rospy.Subscriber('joint_states', JointState, self.callback) self.joints = ['joint_lift'] ``` -Set up a subscriber. We're going to subscribe to the topic "joint_states", looking for `JointState` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically. Create a list of the desired joints you want to print. +Set up a subscriber. We're going to subscribe to the topic "*joint_states*", looking for `JointState` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically. Create a list of the desired joints you want to print. ```Python self.joint_effort = [] self.save_path = '/home/hello-robot/catkin_ws/src/stretch_tutorials/stored_data' @@ -257,7 +257,7 @@ def done_callback(self, status, result): """ ``` -The done callback function takes in the FollowJointTrajectoryActionResult messages as its arguments. +The done callback function takes in the `FollowJointTrajectoryActionResult` messages as its arguments. ```python if status == actionlib.GoalStatus.SUCCEEDED: diff --git a/example_7.md b/example_7.md index 36c770d..8c50058 100644 --- a/example_7.md +++ b/example_7.md @@ -144,7 +144,7 @@ from sensor_msgs.msg import Image from cv_bridge import CvBridge, CvBridgeError ``` -The sensor_msgs.msg is imported so that we can subscribe to ROS Image messages. Import [CvBridge](http://wiki.ros.org/cv_bridge) to convert between ROS Image messages and OpenCV images. +The `sensor_msgs.msg` is imported so that we can subscribe to ROS `Image` messages. Import [CvBridge](http://wiki.ros.org/cv_bridge) to convert between ROS `Image` messages and OpenCV images. ```python def __init__(self): @@ -194,7 +194,7 @@ The first line of code initiates a clean shutdown of ROS. The second line of cod rospy.init_node('capture_image', argv=sys.argv) CaptureImage() ``` -The next line, rospy.init_node(NAME, ...), is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". +The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". Instantiate the class with `CaptureImage()` diff --git a/example_8.md b/example_8.md index 8334a70..98a7d9e 100644 --- a/example_8.md +++ b/example_8.md @@ -87,7 +87,7 @@ You need to import rospy if you are writing a ROS Node. from speech_recognition_msgs.msg import SpeechRecognitionCandidates ``` -Import SpeechRecognitionCandidates from the speech_recgonition_msgs so that we can receive the interpreted speech. +Import `SpeechRecognitionCandidates` from the `speech_recgonition_msgs.msg` so that we can receive the interpreted speech. ```python def __init__(self): @@ -97,7 +97,7 @@ def __init__(self): self.sub = rospy.Subscriber("speech_to_text", SpeechRecognitionCandidates, self.callback) ``` -Set up a subscriber. We're going to subscribe to the topic "speech_to_text", looking for SpeechRecognitionCandidates messages. When a message comes in, ROS is going to pass it to the function "callback" automatically. +Set up a subscriber. We're going to subscribe to the topic "*speech_to_text*", looking for `SpeechRecognitionCandidates` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically. ```python self.save_path = '/home/hello-robot/catkin_ws/src/stretch_tutorials/stored_data @@ -132,7 +132,7 @@ rospy.init_node('speech_text') SpeechText() ``` -The next line, rospy.init_node(NAME, ...), is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". +The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/". Instantiate the class with `SpeechText()`