Browse Source

Fixed typos and syntax errors.

main
hello-sanchez 2 years ago
parent
commit
89086937ce
5 changed files with 7 additions and 7 deletions
  1. +2
    -2
      example_11.md
  2. +2
    -2
      example_4.md
  3. +1
    -1
      src/marker.py
  4. +1
    -1
      src/pointcloud_transformer.py
  5. +1
    -1
      src/scan_filter.py

+ 2
- 2
example_11.md View File

@ -102,7 +102,7 @@ class PointCloudTransformer:
""" """
while not rospy.is_shutdown(): while not rospy.is_shutdown():
try: try:
new_cloud = self.listener.transformPointCloud("/base_link" ,msg)
new_cloud = self.listener.transformPointCloud("base_link" ,msg)
return new_cloud return new_cloud
if new_cloud: if new_cloud:
break break
@ -191,7 +191,7 @@ Utilize the `transform_pointcloud` function to transform the points in the `Poin
```python ```python
while not rospy.is_shutdown(): while not rospy.is_shutdown():
try: try:
new_cloud = self.listener.transformPointCloud("/base_link" ,msg)
new_cloud = self.listener.transformPointCloud("base_link" ,msg)
return new_cloud return new_cloud
if new_cloud: if new_cloud:
break break

+ 2
- 2
example_4.md View File

@ -42,7 +42,7 @@ class Balloon():
""" """
self.publisher = rospy.Publisher('balloon', Marker, queue_size=10) self.publisher = rospy.Publisher('balloon', Marker, queue_size=10)
self.marker = Marker() self.marker = Marker()
self.marker.header.frame_id = '/base_link'
self.marker.header.frame_id = 'base_link'
self.marker.header.stamp = rospy.Time() self.marker.header.stamp = rospy.Time()
self.marker.type = self.marker.SPHERE self.marker.type = self.marker.SPHERE
self.marker.id = 0 self.marker.id = 0
@ -103,7 +103,7 @@ This section of code defines the talker's interface to the rest of ROS. `pub = r
```python ```python
self.marker = Marker() self.marker = Marker()
self.marker.header.frame_id = '/base_link'
self.marker.header.frame_id = 'base_link'
self.marker.header.stamp = rospy.Time() self.marker.header.stamp = rospy.Time()
self.marker.type = self.marker.SPHERE self.marker.type = self.marker.SPHERE
``` ```

+ 1
- 1
src/marker.py View File

@ -23,7 +23,7 @@ class Balloon():
# Set the frame ID and type. The frame ID is the frame in which the position of the marker # Set the frame ID and type. The frame ID is the frame in which the position of the marker
# is specified. The type is the shape of the marker, detailed on the wiki page # is specified. The type is the shape of the marker, detailed on the wiki page
self.marker.header.frame_id = '/base_link'
self.marker.header.frame_id = 'base_link'
self.marker.header.stamp = rospy.Time() self.marker.header.stamp = rospy.Time()
self.marker.type = self.marker.SPHERE self.marker.type = self.marker.SPHERE

+ 1
- 1
src/pointcloud_transformer.py View File

@ -80,7 +80,7 @@ class PointCloudTransformer:
try: try:
# run the transformPointCloud() function to change the referene frame # run the transformPointCloud() function to change the referene frame
# to the base_link # to the base_link
new_cloud = self.listener.transformPointCloud("/base_link" ,msg)
new_cloud = self.listener.transformPointCloud("base_link" ,msg)
return new_cloud return new_cloud
if new_cloud: if new_cloud:
break break

+ 1
- 1
src/scan_filter.py View File

@ -60,7 +60,7 @@ if __name__ == '__main__':
rospy.init_node('scan_filter') rospy.init_node('scan_filter')
# Instantiate the ScanFilter class # Instantiate the ScanFilter class
Scanfilter()
ScanFilter()
# Give control to ROS. This will allow the callback to be called whenever new # Give control to ROS. This will allow the callback to be called whenever new
# messages come in. If we don't put this line in, then the node will not work, # messages come in. If we don't put this line in, then the node will not work,

Loading…
Cancel
Save