Skip to content

Commit

Permalink
Modified run file to launch local server as well now. Slight logging …
Browse files Browse the repository at this point in the history
…changes in global planner. RViz config changed to have an ortho overhead camera.
  • Loading branch information
mitchetm committed Jul 23, 2020
1 parent 1f10194 commit 35a83cc
Show file tree
Hide file tree
Showing 4 changed files with 41 additions and 33 deletions.
17 changes: 4 additions & 13 deletions cart_planning/scripts/global_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -455,26 +455,24 @@ def vel_callback(self, msg):
Args:
msg (Float32 message): Contains current cart speed
"""
# Current speed of the cart
# Current speed of the cart (meters/second)
cur_speed = msg.data

# Are we at a new node
can_update = self.prev_cart_node is not self.current_cart_node

# Calculate distance remaining if the cart is navigating
if self.navigating and can_update and cur_speed > 0.1:
if self.navigating and can_update and cur_speed > 1.0:
self.prev_cart_node = self.current_cart_node
# Update the remaining distance on the trip
self.total_distance = nx.dijkstra_path_length(self.global_graph, self.current_cart_node, self.destination_node)

# Remaining time in seconds
remaining_time = self.total_distance/cur_speed

rospy.loginfo("Remaining Time to Destination (Seconds): " + str(remaining_time))
rospy.loginfo("Remaining distance to destination(meters): " + str(self.total_distance))
# The time we should get there
arrive_time = time.time() + remaining_time
rospy.loginfo("Estimated time of arrival: " + str(time.ctime(arrive_time)) + "\n")
rospy.loginfo("Travel ETA: " + str(time.ctime(arrive_time)) + "\n")

def output_path_gps(self, path):
""" Function for converting the list of points along a path to latitude and longitude
Expand All @@ -500,14 +498,7 @@ def output_path_gps(self, path):
final_pose.longitude = lon

gps_path.gpspoints.append(final_pose)
'''
# Debug to file
out_file = open("/home/browermb/gps_out.txt", "w")
for point in gps_path.gpspoints:
out_file.write(str(point.latitude) + "," + str(point.longitude))
out_file.write("\n")
out_file.close()
'''

# Publish here
self.gps_path_pub.publish(gps_path)

Expand Down
28 changes: 10 additions & 18 deletions cart_simulator/testing_description/rviz/autoware_integration.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,6 @@ Panels:
Property Tree Widget:
Expanded:
- /TF1/Frames1
- /Obstacle Marker1
- /Marker1
Splitter Ratio: 0.5
Tree Height: 504
Toolbars:
Expand Down Expand Up @@ -85,8 +83,8 @@ Visualization Manager:
- Alpha: 0.0500000007
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Max Value: 33.7778625
Min Value: -3.27933836
Value: true
Axis: Z
Channel Name: intensity
Expand All @@ -97,7 +95,7 @@ Visualization Manager:
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Max Intensity: 232
Min Color: 0; 0; 0
Min Intensity: 0
Name: Points Map
Expand Down Expand Up @@ -131,10 +129,10 @@ Visualization Manager:
Unreliable: false
Value: false
Visibility:
"": true
Grid: true
LaserScan: true
Look Ahead Point: true
Marker: true
Obstacle Marker: true
Points Map: true
Points Raw: true
Expand Down Expand Up @@ -199,7 +197,6 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_left_caster:
Alpha: 1
Show Axes: false
Expand Down Expand Up @@ -386,26 +383,21 @@ Visualization Manager:
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 71.2472916
Angle: 0
Class: rviz/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -0.328191996
Y: -0.312988251
Z: -1.22253728
Focal Shape Fixed Size: false
Focal Shape Size: 0.0500000007
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.00999999978
Pitch: 1.54979634
Scale: 7.50715828
Target Frame: map
Value: Orbit (rviz)
Yaw: 0.355403513
Value: TopDownOrtho (rviz)
X: 15.720089
Y: 6.38741922
Saved: ~
Window Geometry:
Camera:
Expand Down
20 changes: 20 additions & 0 deletions npm-debug.log
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
0 info it worked if it ends with ok
1 verbose cli [ '/usr/bin/nodejs', '/usr/bin/npm', 'start' ]
2 info using [email protected]
3 info using [email protected]
4 verbose stack Error: ENOENT: no such file or directory, open '/home/browermb/catkin_ws/src/ai-navigation/package.json'
4 verbose stack at Error (native)
5 verbose cwd /home/browermb/catkin_ws/src/ai-navigation
6 error Linux 4.15.0-29-generic
7 error argv "/usr/bin/nodejs" "/usr/bin/npm" "start"
8 error node v4.2.6
9 error npm v3.5.2
10 error path /home/browermb/catkin_ws/src/ai-navigation/package.json
11 error code ENOENT
12 error errno -2
13 error syscall open
14 error enoent ENOENT: no such file or directory, open '/home/browermb/catkin_ws/src/ai-navigation/package.json'
15 error enoent ENOENT: no such file or directory, open '/home/browermb/catkin_ws/src/ai-navigation/package.json'
15 error enoent This is most likely not a problem with npm itself
15 error enoent and is related to npm not being able to find a file.
16 verbose exit [ -2, true ]
9 changes: 7 additions & 2 deletions run.sh
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
#!/bin/bash
echo "Configuring Velodyne..."
./velodyne_setup.sh
echo "Launching Navigation Code"
roslaunch cart_control navigation.launch
wait
sleep 2
echo "Starting local server..."
gnome-terminal --tab -e 'sh -c "cd ~; cd Desktop/jackart-local-server; npm start; exec bash"'
echo "Launching Navigation Code..."
sleep 2
gnome-terminal --tab -e 'sh -c "roslaunch cart_control navigation.launch; exec bash"'

0 comments on commit 35a83cc

Please sign in to comment.