From: <tpr...@us...> - 2009-05-09 02:36:34
|
Revision: 15146 http://personalrobots.svn.sourceforge.net/personalrobots/?rev=15146&view=rev Author: tpratkanis Date: 2009-05-09 02:36:16 +0000 (Sat, 09 May 2009) Log Message: ----------- Add planner run script. It does not work because there is no laser frame. Added Paths: ----------- pkg/trunk/demos/erratic_gazebo/2dnav-gazebo-simple-fake_localization.xml pkg/trunk/demos/erratic_gazebo/base_local_planner_params.yaml pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml pkg/trunk/demos/erratic_gazebo/navfn_params.yaml Added: pkg/trunk/demos/erratic_gazebo/2dnav-gazebo-simple-fake_localization.xml =================================================================== --- pkg/trunk/demos/erratic_gazebo/2dnav-gazebo-simple-fake_localization.xml (rev 0) +++ pkg/trunk/demos/erratic_gazebo/2dnav-gazebo-simple-fake_localization.xml 2009-05-09 02:36:16 UTC (rev 15146) @@ -0,0 +1,48 @@ +<launch> + <group name="wg"> + + <!-- start up robot --> + <include file="$(find erratic_gazebo)/erratic.launch"/> + + + <!-- Fake Localization --> + <node pkg="fake_localization" type="fake_localization" name="fake_localization" respawn="true" output="screen" > + <param name="odom_frame_id" value="odom"/> + </node> + + + <!-- Filter for base laser shadowing/veiling --> + <node pkg="laser_scan" type="scan_shadows_filter_node" respawn="true" name="base_shadow_filter_non_preserve" > + <param name="scan_topic" value="base_scan" /> + <param name="cloud_topic" value="base_scan_marking" /> + <param name="laser_max_range" value="30.0" /> + </node> + + <!-- for clearing we want preservative --> + <node pkg="laser_scan" type="scan_shadows_filter_node" respawn="true" name="base_shadow_filter_preserve" > + <param name="scan_topic" value="base_scan" /> + <param name="cloud_topic" value="base_scan_clearing" /> + <param name="preservative" value="true" /> + <param name="laser_max_range" value="30.0" /> + </node> + + <!-- for moving --> + <node pkg="nav" type="move_base" respawn="false" name="move_base" output="screen"> + <param name="controller_frequency" value="10.0" /> + + <rosparam file="$(find erratic_gazebo)/costmap_common_params.yaml" command="load" ns="navfn" /> + <rosparam file="$(find erratic_gazebo)/costmap_common_params.yaml" command="load" ns="base_local_planner" /> + <rosparam file="$(find erratic_gazebo)/navfn_params.yaml" command="load" /> + <rosparam file="$(find erratic_gazebo)/base_local_planner_params.yaml" command="load" /> + </node> + + <!-- load map --> + <node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/map3.png 0.1" respawn="false" output="screen" /> + + <!-- for visualization --> + <!--node pkg="rviz" type="rviz" respawn="false" output="screen" /--> + <node pkg="nav_view" type="nav_view" respawn="true" /> + + </group> +</launch> + Added: pkg/trunk/demos/erratic_gazebo/base_local_planner_params.yaml =================================================================== --- pkg/trunk/demos/erratic_gazebo/base_local_planner_params.yaml (rev 0) +++ pkg/trunk/demos/erratic_gazebo/base_local_planner_params.yaml 2009-05-09 02:36:16 UTC (rev 15146) @@ -0,0 +1,41 @@ +base_local_planner: + #Independent settings for the local costmap + costmap: + global_frame: map + robot_base_frame: base_link + update_frequency: 5.0 + publish_frequency: 0.0 + static_map: false + rolling_window: true + width: 6.0 + height: 6.0 + resolution: 0.025 + origin_x: 0.0 + origin_y: 0.0 + transform_tolerance: 0.2 + costmap_visualization_rate: 2.0 + world_model: freespace + sim_time: 1.7 + sim_granularity: 0.05 + dwa: true + vx_samples: 3 + vtheta_samples: 20 + max_vel_x: 0.65 + min_vel_x: 0.1 + max_vel_th: 1.0 + min_vel_th: -1.0 + min_in_place_vel_th: 0.4 + xy_goal_tolerance: 0.1 + yaw_goal_tolerance: 0.05 + goal_distance_bias: 0.8 + path_distance_bias: 0.6 + occdist_scale: 0.05 + heading_lookahead: 0.325 + oscillation_reset_dist: 0.05 + acc_limit_th: 3.2 + acc_limit_x: 2.5 + acc_limit_y: 2.5 + heading_scoring: false + heading_scoring_timestep: 0.8 + holonomic_robot: true + simple_attractor: false Added: pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml =================================================================== --- pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml (rev 0) +++ pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml 2009-05-09 02:36:16 UTC (rev 15146) @@ -0,0 +1,18 @@ +costmap: + transform_tolerance: 0.2 + obstacle_range: 2.5 + max_obstacle_height: 2.0 + raytrace_range: 3.0 + inscribed_radius: 0.325 + circumscribed_radius: 0.46 + inflation_radius: 0.55 + cost_scaling_factor: 25.0 + lethal_cost_threshold: 100 + + observation_topics: base_scan_marking base_scan + + base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2, + observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstalce_height: 2.0} + + base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2, + observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: 0.08, max_obstalce_height: 2.0} Added: pkg/trunk/demos/erratic_gazebo/navfn_params.yaml =================================================================== --- pkg/trunk/demos/erratic_gazebo/navfn_params.yaml (rev 0) +++ pkg/trunk/demos/erratic_gazebo/navfn_params.yaml 2009-05-09 02:36:16 UTC (rev 15146) @@ -0,0 +1,10 @@ +navfn: + transform_tolerance: 0.2 + #Independent settings for the planner's costmap + costmap: + global_frame: map + robot_base_frame: base_link + update_frequency: 5.0 + publish_frequency: 0.0 + static_map: true + rolling_window: false This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |