Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions cob_map_accessibility_analysis/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@ find_package(catkin REQUIRED COMPONENTS
find_package(Boost REQUIRED)
find_package(OpenCV REQUIRED)

set(CMAKE_CXX_COMPILER "clang++")
set(CMAKE_C_COMPILER "clang")

catkin_python_setup()

add_service_files(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ obstacle_layer:
inflation_layer:

# The radius in meters to which the map inflates obstacle cost values.
inflation_radius: 0.55 # default: 0.55
inflation_radius: 0.65 # default: 0.55

# A scaling factor to apply to cost values during inflation.
cost_scaling_factor: 8.01 # default: 10.0
29 changes: 29 additions & 0 deletions cob_navigation_global/config/local_planner_eband.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
max_vel_lin: 0.74
max_vel_th: 0.5

min_vel_lin: 0.0
min_vel_th: 0.0

min_in_place_vel_th: 0.0
in_place_trans_vel: 0.0

xy_goal_tolerance: 0.02
yaw_goal_tolerance: 0.04
tolerance_timeout: 0.5

k_prop: 4.0
k_damp: 3.5

Ctrl_Rate: 15.0

max_acceleration: 0.3
virtual_mass: 0.75

max_translational_acceleration: 0.3
max_rotational_acceleration: 1.5

rotation_correction_threshold: 2.0


#Stuff from utexas which we don't need for Care-O-bot 3
differential_drive: false
21 changes: 21 additions & 0 deletions cob_navigation_global/launch/2dnav_ros_eband.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<launch>

<arg name="robot" default="$(optenv ROBOT !!NO_ROBOT_SET!!)"/>
<arg name="robot_env" default="$(optenv ROBOT_ENV !!NO_ROBOT_ENV_SET!!)"/>
<arg name="map" default="$(find cob_default_env_config)/$(arg robot_env)/map.yaml" />

<!--- Run map_server -->
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map)"/>

<!--- Run AMCL -->
<include file="$(find cob_navigation_global)/launch/amcl_node.xml" >
<arg name="robot" value="$(arg robot)"/>
</include>

<!--- Run move base -->
<include file="$(find cob_navigation_global)/launch/2dnav_ros_eband.xml" >
<arg name="robot" value="$(arg robot)"/>
</include>

</launch>
30 changes: 30 additions & 0 deletions cob_navigation_global/launch/2dnav_ros_eband.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
<?xml version="1.0"?>
<launch>

<arg name="robot"/>

<!-- delete old parameters -->
<rosparam command="delete" param="/move_base"/>

<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<remap from="cmd_vel" to="base/twist_mux/command_navigation"/>
<remap from="odom" to="base/odometry_controller/odometry"/>
<param name="controller_frequency" value="10"/>

<!-- Use the dwa local planner for the PR2 -->
<param name="base_local_planner" value="eband_local_planner/EBandPlannerROS" />
<rosparam file="$(find cob_navigation_global)/config/local_planner_eband.yaml" command="load" ns="EBandPlannerROS"/>
<!--- load common configuration files -->
<rosparam file="$(find cob_navigation_config)/robots/$(arg robot)/nav/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find cob_navigation_config)/robots/$(arg robot)/nav/costmap_common_params.yaml" command="load" ns="local_costmap" />

<!--- load global navigation specific parameters -->
<rosparam file="$(find cob_navigation_global)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find cob_navigation_global)/config/global_costmap_params.yaml" command="load" />

<!--- load planner parameters -->
<rosparam file="$(find cob_navigation_config)/robots/$(arg robot)/nav/base_local_planner_params.yaml" command="load" />

</node>

</launch>
2 changes: 1 addition & 1 deletion cob_navigation_global/launch/amcl_node.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<param name="gui_publish_rate" value="-1.0"/>
<param name="laser_max_beams" value="30"/>
<param name="laser_max_range" value="29.5"/>
<param name="min_particles" value="100"/>
<param name="min_particles" value="150"/>
<param name="max_particles" value="5000"/>
<param name="update_min_d" value="0.2"/>
<!--param name="update_min_a" value="1.0"/-->
Expand Down