]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Added full_coverage_path_planner launch file
authorErik Andresen <erik@vontaene.de>
Sat, 24 Oct 2020 12:31:19 +0000 (14:31 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 24 Oct 2020 12:31:19 +0000 (14:31 +0200)
CMakeLists.txt
config/global_costmap_params.yaml
launch/full_coverage_path_planner.launch [new file with mode: 0644]
launch/move_base.launch
www/assets/javascripts/application.js
www/index.html

index 965b4ee9628ffed1cccf6ab0f2d5c66364067a35..999926aa31b0646b2ae5fe286142d0ebfa80760e 100644 (file)
@@ -1,5 +1,6 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(wild_thumper)
 cmake_minimum_required(VERSION 2.8.3)
 project(wild_thumper)
+EXECUTE_PROCESS( COMMAND uname -m COMMAND tr -d '\n' OUTPUT_VARIABLE ARCHITECTURE )
 
 ## Find catkin macros and libraries
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 
 ## Find catkin macros and libraries
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
@@ -109,7 +110,6 @@ include_directories(
 
 ## Declare a cpp executable
 add_executable(path_following src/path_following.cpp)
 
 ## Declare a cpp executable
 add_executable(path_following src/path_following.cpp)
-add_executable(wt_node src/wt_node.cpp)
 
 ## Add cmake target dependencies of the executable/library
 ## as an example, message headers may need to be generated before nodes
 
 ## Add cmake target dependencies of the executable/library
 ## as an example, message headers may need to be generated before nodes
@@ -120,10 +120,13 @@ target_link_libraries(path_following
    ${catkin_LIBRARIES}
    ${OpenCV_LIBS}
 )
    ${catkin_LIBRARIES}
    ${OpenCV_LIBS}
 )
-target_link_libraries(wt_node
-   ${catkin_LIBRARIES}
-   i2c
-)
+if(${ARCHITECTURE} EQUAL "armv7l")
+       add_executable(wt_node src/wt_node.cpp)
+       target_link_libraries(wt_node
+          ${catkin_LIBRARIES}
+          i2c
+       )
+endif()
 
 #############
 ## Install ##
 
 #############
 ## Install ##
index d44e361103e1616feabc8749f35aedbde92154ce..332d53341f77ae3becb2c199fe6e7add6897448f 100644 (file)
@@ -4,7 +4,7 @@ global_costmap:
   publish_frequency: 1.0
   plugins:
   - {name: static_layer, type: 'costmap_2d::StaticLayer'}
   publish_frequency: 1.0
   plugins:
   - {name: static_layer, type: 'costmap_2d::StaticLayer'}
-  #- {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
   inflation_layer:
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
   inflation_layer:
@@ -13,3 +13,4 @@ global_costmap:
   obstacle_layer:
     combination_method: 0 # overwrite
     track_unknown_space: true
   obstacle_layer:
     combination_method: 0 # overwrite
     track_unknown_space: true
+    enabled: false
diff --git a/launch/full_coverage_path_planner.launch b/launch/full_coverage_path_planner.launch
new file mode 100644 (file)
index 0000000..805ab3c
--- /dev/null
@@ -0,0 +1,23 @@
+<?xml version="1.0"?>
+<launch>
+       <arg name="coverage_area_offset" default="-5.0 -5.0 0 0 0 0"/>
+       <arg name="coverage_area_size_x" default="10"/>
+       <arg name="coverage_area_size_y" default="10"/>
+       <arg name="tool_radius" default="0.175"/>
+
+       <include file="$(find wild_thumper)/launch/move_base.launch">
+               <arg name="base_global_planner" value="full_coverage_path_planner/SpiralSTC"/>
+               <arg name="base_local_planner" value="pose_follower/PoseFollower"/>
+               <arg name="tool_radius" value="$(arg tool_radius)"/>
+       </include>
+
+       <!-- Launch coverage progress tracking -->
+       <node pkg="tf" type="static_transform_publisher" name="map_to_coveragemap" args="$(arg coverage_area_offset) map coverage_map 100" />
+       <node pkg="full_coverage_path_planner" type="coverage_progress" name="coverage_progress">
+               <param name="~target_area/x" value="$(arg coverage_area_size_x)" />
+               <param name="~target_area/y" value="$(arg coverage_area_size_y)" />
+               <param name="~coverage_radius" value="$(arg tool_radius)" />
+               <remap from="reset" to="coverage_progress/reset" />
+               <param name="~map_frame" value="/coverage_map"/>
+       </node>
+</launch>
index 33c5636f3cf9ffdb09eeb780b7ccc04440c5fe16..70974dc1d11bceec5d02268de3af7becf65002c1 100644 (file)
@@ -5,10 +5,11 @@
        <arg name="global_odom" default="false" />
        <arg name="close_to_obstacles" default="false" />
        <arg name="nomap" default="false" />
        <arg name="global_odom" default="false" />
        <arg name="close_to_obstacles" default="false" />
        <arg name="nomap" default="false" />
-       <arg name="base_global_planner" default="navfn/NavfnROS"/> <!-- navfn/NavfnROS || carrot_planner/CarrotPlanner -->
+       <arg name="base_global_planner" default="navfn/NavfnROS"/> <!-- navfn/NavfnROS || carrot_planner/CarrotPlanner || full_coverage_path_planner/SpiralSTC -->
        <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS || pose_follower/PoseFollower -->
        <!-- default: [{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]" -->
        <arg name="recovery_behaviors" default="[{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]"/>
        <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS || pose_follower/PoseFollower -->
        <!-- default: [{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]" -->
        <arg name="recovery_behaviors" default="[{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]"/>
+       <arg name="tool_radius" default="0.175"/>
 
        <!-- Run AMCL -->
        <group unless="$(arg nomap)">
 
        <!-- Run AMCL -->
        <group unless="$(arg nomap)">
@@ -50,6 +51,8 @@
                <param name="conservative_reset/affected_maps" value="local" />
                <param name="make_plan_clear_costmap" value="false" />
                <param name="make_plan_add_unreachable_goal" value="false" />
                <param name="conservative_reset/affected_maps" value="local" />
                <param name="make_plan_clear_costmap" value="false" />
                <param name="make_plan_add_unreachable_goal" value="false" />
+               <param name="SpiralSTC/robot_radius" value="0.23" />
+               <param name="SpiralSTC/tool_radius" value="$(arg tool_radius)" />
                <rosparam param="recovery_behaviors" subst_value="True">$(arg recovery_behaviors)</rosparam>
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
                <rosparam param="recovery_behaviors" subst_value="True">$(arg recovery_behaviors)</rosparam>
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
index 1a61324e4492bf7744c2e88b3112582eafc6dabf..02dfe59f101db11bf15bd00b1eedec34a51bdf95 100644 (file)
@@ -17,9 +17,9 @@ function init() {
 
        ros.on('close', function() {
                information.alerts.push({message: "Connection to websocket server closed.", info: true});
 
        ros.on('close', function() {
                information.alerts.push({message: "Connection to websocket server closed.", info: true});
-               setTimeout(function() {
-                       connect();
-               }, 2000);
+               //setTimeout(function() {
+               //      connect();
+               //}, 2000);
        });
 
        //tfClient.subscribe('base_link', function(tf) {
        });
 
        //tfClient.subscribe('base_link', function(tf) {
index 15e2aed484069c100bcae030a87fd390722b5d00..8202c20b1fdf9c1c256778bb12c4cd71d31fa1f7 100644 (file)
@@ -22,7 +22,7 @@
                <script src="assets/javascripts/vue.js"></script>
                <script src="assets/javascripts/application.js"></script>
                <script type="text/javascript">
                <script src="assets/javascripts/vue.js"></script>
                <script src="assets/javascripts/application.js"></script>
                <script type="text/javascript">
-                       const robothostname="wildthumper"
+                       const robothostname="localhost"
                </script>
 
                <title>Wild Thumper control</title>
                </script>
 
                <title>Wild Thumper control</title>