diff --git a/waypoint_manager/scripts/devel_GUI.py b/waypoint_manager/scripts/devel_GUI.py
index 1d40c7e..81e18d9 100755
--- a/waypoint_manager/scripts/devel_GUI.py
+++ b/waypoint_manager/scripts/devel_GUI.py
@@ -143,7 +143,7 @@
--- 今はパスを直接指定して読み込んでいるので、rospy.get_param()を使って読み込めるように ---
"""
def get_map_info(self):
- map_path = Path('..','..','waypoint_nav','maps','map_gakunai') # .pgmと.yamlの手前までのパス
+ map_path = Path('/home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap') # .pgmと.yamlの手前までのパス
map_img_pil = Image.open(Path(str(map_path)+'.pgm')) # .pgmをplillowで読み込む
with open(str(map_path)+'.yaml') as file: # .yamlを読み込む
map_yaml = ruamel.yaml.YAML().load(file)
@@ -157,7 +157,7 @@
--- これもget_param()でパスを受け取り、読み込めるようにする ---
"""
def get_waypoints(self):
- file_path = Path('..','..','waypoint_nav','param','waypoints_gakunai.yaml')
+ file_path = Path('/home/ubuntu/catkin_ws/src/tsukuba2022/config/waypoints/waypoints.yaml')
with open(file_path) as file:
waypoints = ruamel.yaml.YAML().load(file)
self.master.title(file_path.name + " - " + self.master.title())
diff --git a/waypoint_nav/launch/waypoint_nav.launch b/waypoint_nav/launch/waypoint_nav.launch
index b8127ff..4f5d4cb 100644
--- a/waypoint_nav/launch/waypoint_nav.launch
+++ b/waypoint_nav/launch/waypoint_nav.launch
@@ -3,10 +3,12 @@
+
+
@@ -15,4 +17,4 @@
-
\ No newline at end of file
+
diff --git a/waypoint_nav/rviz_cfg/nav.rviz b/waypoint_nav/rviz_cfg/nav.rviz
index 4e51bd4..261f562 100644
--- a/waypoint_nav/rviz_cfg/nav.rviz
+++ b/waypoint_nav/rviz_cfg/nav.rviz
@@ -5,7 +5,7 @@
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.5
- Tree Height: 532
+ Tree Height: 694
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
@@ -21,7 +21,6 @@
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
- Experimental: false
Name: Time
SyncMode: 0
SyncSource: LaserScan
@@ -81,12 +80,7 @@
Show Axes: false
Show Trail: false
Value: true
- base_scan:
- Alpha: 1
- Show Axes: false
- Show Trail: false
- Value: true
- caster_back_link:
+ hokuyo_link:
Alpha: 1
Show Axes: false
Show Trail: false
@@ -95,12 +89,28 @@
Alpha: 1
Show Axes: false
Show Trail: false
- wheel_left_link:
+ Value: true
+ left_caster_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
- wheel_right_link:
+ left_wheel:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ right_caster_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ right_wheel:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ velodyne_link:
Alpha: 1
Show Axes: false
Show Trail: false
@@ -175,7 +185,7 @@
Length: 0.30000001192092896
Line Style: Lines
Line Width: 0.029999999329447746
- Name: Path
+ Name: Global Plan
Offset:
X: 0
Y: 0
@@ -189,6 +199,30 @@
Topic: /move_base/NavfnROS/plan
Unreliable: false
Value: true
+ - Alpha: 1
+ Buffer Length: 1
+ Class: rviz/Path
+ Color: 255; 255; 0
+ Enabled: true
+ Head Diameter: 0.30000001192092896
+ Head Length: 0.20000000298023224
+ Length: 0.30000001192092896
+ Line Style: Billboards
+ Line Width: 0.10000000149011612
+ Name: Local Plan
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Pose Color: 255; 85; 255
+ Pose Style: None
+ Queue Size: 10
+ Radius: 0.029999999329447746
+ Shaft Diameter: 0.10000000149011612
+ Shaft Length: 0.10000000149011612
+ Topic: /move_base/TrajectoryPlannerROS/local_plan
+ Unreliable: false
+ Value: true
- Alpha: 0.699999988079071
Class: rviz/Map
Color Scheme: costmap
@@ -292,7 +326,7 @@
Views:
Current:
Class: rviz/ThirdPersonFollower
- Distance: 11.816969871520996
+ Distance: 35.39775466918945
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
@@ -300,25 +334,25 @@
Value: false
Field of View: 0.7853981852531433
Focal Point:
- X: -0.31653428077697754
- Y: -0.3555675148963928
+ X: -0.3276565670967102
+ Y: -0.7599051594734192
Z: 0
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
- Pitch: 1.5697963237762451
+ Pitch: 0.904796838760376
Target Frame: base_link
- Yaw: 3.145397424697876
+ Yaw: 3.1003949642181396
Saved: ~
Window Geometry:
Displays:
collapsed: false
- Height: 778
+ Height: 957
Hide Left Dock: false
Hide Right Dock: true
- QMainWindow State: 000000ff00000000fd000000040000000000000193000002affc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e00000251000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c0100000295000000580000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000046900fffffffb0000000800540069006d0065010000000000000450000000000000000000000376000002af00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+ QMainWindow State: 000000ff00000000fd00000004000000000000019300000362fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e000002f3000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c0100000337000000690000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d00650100000000000004500000000000000000000004190000036200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
StateTriggerPanel:
@@ -329,6 +363,6 @@
collapsed: false
Views:
collapsed: true
- Width: 1295
- X: -1
- Y: -17
+ Width: 1458
+ X: 374
+ Y: -40
diff --git a/waypoint_nav/src/waypoint_nav.cpp b/waypoint_nav/src/waypoint_nav.cpp
index c4e74a0..33b2ff4 100644
--- a/waypoint_nav/src/waypoint_nav.cpp
+++ b/waypoint_nav/src/waypoint_nav.cpp
@@ -388,6 +388,7 @@
}
// go to current waypoint
ROS_INFO_STREAM("Go to waypoint " << wp_num_.data);
+ ROS_INFO_STREAM("x: " << waypoint_list_[wp_num_.data-1].x << ", y: " << waypoint_list_[wp_num_.data-1].y);
startNavigationGL(*current_waypoint_);
int resend_goal = 0;
double start_nav_time = ros::Time::now().toSec();
@@ -467,4 +468,4 @@
w_nav.run();
return 0;
-}
\ No newline at end of file
+}