Browse Source

Added addtional comments.

main
Alan G. Sanchez 2 years ago
parent
commit
f1d54f89bd
2 changed files with 14 additions and 16 deletions
  1. +12
    -14
      example_1.md
  2. +2
    -2
      src/move.py

+ 12
- 14
example_1.md View File

@ -12,7 +12,7 @@ Begin by running the following command in a new terminal.
roslaunch stretch_core stretch_driver.launch
```
Switch the mode to *navigation* mode using a rosservice call. Then drive the robot forward with the move node.
Switch the mode to *navigation* mode using a rosservice call. Then drive the robot forward with the `move` node.
```bash
# Terminal 2
@ -33,7 +33,7 @@ from geometry_msgs.msg import Twist
class Move:
"""
A class that sends Twist messages to move the Stretch robot foward.
A class that sends Twist messages to move the Stretch robot forward.
"""
def __init__(self):
"""
@ -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](http://wiki.ros.org/Nodes). The `geometry_msgs.msg` import is so that we can send velocity commands to the robot.
```python
@ -89,21 +89,20 @@ 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
command = Twist()
```
Make a Twist message. We're going to set all of the elements, since we
can't depend on them defaulting to safe values.
Make a `Twist` message. We're going to set all of the elements, since we can't depend on them defaulting to safe values.
```python
command.linear.x = 0.1
command.linear.y = 0.0
command.linear.z = 0.0
```
A Twist has three linear velocities (in meters per second), along each of the axes. For Stretch, it will only pay attention to the x velocity, since it can't directly move in the y direction or the z direction.
A `Twist` data structure has three linear velocities (in meters per second), along each of the axes. For Stretch, it will only pay attention to the x velocity, since it can't directly move in the y direction or the z direction.
```python
@ -111,30 +110,29 @@ command.angular.x = 0.0
command.angular.y = 0.0
command.angular.z = 0.0
```
A *Twist* also has three rotational velocities (in radians per second).
The Stretch will only respond to rotations around the z (vertical) axis.
A `Twist` message also has three rotational velocities (in radians per second). The Stretch will only respond to rotations around the z (vertical) axis.
```python
self.pub.publish(command)
```
Publish the Twist commands in the previously defined topic name */stretch/cmd_vel*.
Publish the `Twist` commands in the previously defined topic name */stretch/cmd_vel*.
```Python
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. **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. 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
@ -142,7 +140,7 @@ This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown(
<img src="images/move.gif"/>
</p>
Using your preferred text editor, modify the topic name of the published *Twist* messages. Please review the edit in the **move.py** script below.
Using your preferred text editor, modify the topic name of the published `Twist` messages. Please review the edit in the **move.py** script below.
```python
self.pub = rospy.Publisher('/stretch_diff_drive_controller/cmd_vel', Twist, queue_size=1)

+ 2
- 2
src/move.py View File

@ -8,12 +8,12 @@ from geometry_msgs.msg import Twist
class Move:
"""
A class that sends Twist messages to move the Stretch robot foward.
A class that sends Twist messages to move the Stretch robot forward.
"""
def __init__(self):
"""
Function that initializes the publisher.
:param self: The self reference
:param self: The self reference.
"""
# Setup a publisher that will send the velocity commands to Stretch
# This will publish on a topic called "/stretch/cmd_vel" with a message type Twist

Loading…
Cancel
Save